Skip to content

Commit

Permalink
AP_Temperature: fix MCP9600 i2c address and TEMP9 index
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Oct 14, 2024
1 parent 2524583 commit 0bcdcf6
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 17 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor::var_info[] = {

// @Group: 9_
// @Path: AP_TemperatureSensor_Analog.cpp
AP_SUBGROUPVARPTR(drivers[8], "9_", 26, AP_TemperatureSensor, backend_var_info[8]),
AP_SUBGROUPVARPTR(drivers[8], "9_", 27, AP_TemperatureSensor, backend_var_info[8]),
#endif

AP_GROUPEND
Expand Down
21 changes: 5 additions & 16 deletions libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ static const uint8_t MCP9601_WHOAMI = 0x41;


#define MCP9600_ADDR_LOW 0x60 // ADDR pin pulled low
#define MCP9600_ADDR_HIGH 0x66 // ADDR pin pulled high
#define MCP9600_ADDR_HIGH 0x67 // ADDR pin pulled high

#define AP_TemperatureSensor_MCP9600_UPDATE_INTERVAL_MS 500
#define AP_TemperatureSensor_MCP9600_SCALE_FACTOR (0.0625f)
Expand All @@ -56,10 +56,6 @@ static const uint8_t MCP9601_WHOAMI = 0x41;
#define AP_TemperatureSensor_MCP9600_ADDR_DEFAULT MCP9600_ADDR_LOW
#endif

#ifndef AP_TemperatureSensor_MCP9600_ENFORCE_KNOWN_VALID_I2C_ADDRESS
#define AP_TemperatureSensor_MCP9600_ENFORCE_KNOWN_VALID_I2C_ADDRESS 1
#endif

#ifndef AP_TemperatureSensor_MCP9600_Filter
#define AP_TemperatureSensor_MCP9600_Filter 2 // can be values 0 through 7 where 0 is no filtering (fast) and 7 is lots of smoothing (very very slow)
#endif
Expand All @@ -68,13 +64,6 @@ void AP_TemperatureSensor_MCP9600::init()
{
constexpr char name[] = "MCP9600";

#if AP_TemperatureSensor_MCP9600_ENFORCE_KNOWN_VALID_I2C_ADDRESS
// I2C Address: Default to using MCP9600_ADDR_LOW if it's out of range
if ((_params.bus_address < MCP9600_ADDR_LOW) || ( _params.bus_address > MCP9600_ADDR_HIGH)) {
_params.bus_address.set(MCP9600_ADDR_LOW);
}
#endif

_dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address));
if (!_dev) {
// device not found
Expand Down Expand Up @@ -137,14 +126,14 @@ bool AP_TemperatureSensor_MCP9600::read_temperature(float &temperature)
if ((data[0] & MCP9600_CMD_STATUS_UPDATE_READY) == 0) {
return false;
}
// clear update bit:
if (!_dev->write_register(0x04, data[0] & ~MCP9600_CMD_STATUS_UPDATE_READY)) {
return false;
}
// read temperature:
if (!_dev->read_registers(MCP9600_CMD_HOT_JUNCT_TEMP, data, 2)) {
return false;
}
// clear update bit:
if (!_dev->write_register(0x04, data[0] & ~MCP9600_CMD_STATUS_UPDATE_READY)) {
return false;
}

// scale temperature:
temperature = int16_t(UINT16_VALUE(data[0], data[1])) * AP_TemperatureSensor_MCP9600_SCALE_FACTOR;
Expand Down

0 comments on commit 0bcdcf6

Please sign in to comment.