Skip to content

Commit

Permalink
AP_TemperatureSensor: new MLX90614 sensor backend driver added
Browse files Browse the repository at this point in the history
  • Loading branch information
rahulOCR committed Aug 16, 2024
1 parent bc29550 commit 693258b
Show file tree
Hide file tree
Showing 8 changed files with 105 additions and 1 deletion.
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -299,6 +299,7 @@ def __init__(self,
Feature('Sensors', 'TEMP_TSYS01', 'AP_TEMPERATURE_SENSOR_TSYS01_ENABLED', 'Enable Temp Sensor - TSYS01', 0, "TEMP"),
Feature('Sensors', 'TEMP_MCP9600', 'AP_TEMPERATURE_SENSOR_MCP9600_ENABLED', 'Enable Temp Sensor - MCP9600', 0, "TEMP"),
Feature('Sensors', 'TEMP_TSYS03', 'AP_TEMPERATURE_SENSOR_TSYS03_ENABLED', 'Enable Temp Sensor - TSYS03', 0, "TEMP"),
Feature('Sensors', 'TEMP_MLX90614', 'AP_TEMPERATURE_SENSOR_MLX90614_ENABLED', 'Enable Temp Sensor - MLX90614', 0, "TEMP"),

Feature('Sensors', 'AIRSPEED', 'AP_AIRSPEED_ENABLED', 'Enable Airspeed Sensors', 1, None), # Default to enabled to not annoy Plane users # NOQA: E501
Feature('Sensors', 'BEACON', 'AP_BEACON_ENABLED', 'Enable Beacon', 0, None),
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include "AP_TemperatureSensor_MAX31865.h"
#include "AP_TemperatureSensor_Analog.h"
#include "AP_TemperatureSensor_DroneCAN.h"
#include "AP_TemperatureSensor_MLX90614.h"

#include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
Expand Down Expand Up @@ -201,6 +202,11 @@ void AP_TemperatureSensor::init()
case AP_TemperatureSensor_Params::Type::DRONECAN:
drivers[instance] = new AP_TemperatureSensor_DroneCAN(*this, _state[instance], _params[instance]);
break;
#endif
#if AP_TEMPERATURE_SENSOR_MLX90614_ENABLED
case AP_TemperatureSensor_Params::Type::MLX90614:
drivers[instance] = new AP_TemperatureSensor_MLX90614(*this, _state[instance], _params[instance]);
break;
#endif
case AP_TemperatureSensor_Params::Type::NONE:
default:
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_TemperatureSensor/AP_TemperatureSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ class AP_TemperatureSensor_MCP9600;
class AP_TemperatureSensor_MAX31865;
class AP_TemperatureSensor_TSYS03;
class AP_TemperatureSensor_Analog;
class AP_TemperatureSensor_MLX90614;

class AP_TemperatureSensor
{
Expand All @@ -37,6 +38,7 @@ class AP_TemperatureSensor
friend class AP_TemperatureSensor_TSYS03;
friend class AP_TemperatureSensor_Analog;
friend class AP_TemperatureSensor_DroneCAN;
friend class AP_TemperatureSensor_MLX90614;

public:

Expand Down
66 changes: 66 additions & 0 deletions libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#include "AP_TemperatureSensor_config.h"

#if AP_TEMPERATURE_SENSOR_MLX90614_ENABLED

#include "AP_TemperatureSensor_MLX90614.h"

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_Math/AP_Math.h>


extern const AP_HAL::HAL &hal;

#define MLX90614_I2CDEFAULTADDR 0x5A // Device default slave address
#define MLX90614_BROADCASTADDR 0 // Device broadcast slave address

// RAM addresses
#define MLX90614_RAWIR1 0x04 // RAM reg - Raw temperature, source #1
#define MLX90614_RAWIR2 0x05 // RAM reg - Raw temperature, source #2
#define MLX90614_TA 0x06 // RAM reg - Linearized temperature, ambient
#define MLX90614_TOBJ1 0x07 // RAM reg - Linearized temperature, source #1
#define MLX90614_TOBJ2 0x08 // RAM reg - Linearized temperature, source #2

void AP_TemperatureSensor_MLX90614::init()
{
_params.bus_address.set_default(MLX90614_I2CDEFAULTADDR);

_dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address));
if (!_dev) {
return;
}

WITH_SEMAPHORE(_dev->get_semaphore());

_dev->register_periodic_callback(50 * AP_USEC_PER_MSEC,
FUNCTOR_BIND_MEMBER(&AP_TemperatureSensor_MLX90614::_timer, void));
}


void AP_TemperatureSensor_MLX90614::_timer()
{
const uint16_t _crude_value = read_data(MLX90614_TA);

if (_crude_value == 0) {
return;
}

WITH_SEMAPHORE(_dev->get_semaphore());

// temp * 0.02 - 273.15 = degrees, temp * 0.02 is temperature in kelvin
const float tmp = KELVIN_TO_C(_crude_value) * 0.02;
set_temperature(tmp);
}



uint16_t AP_TemperatureSensor_MLX90614::read_data(uint8_t cmd)
{
uint8_t val[3];

if (!_dev->transfer(&cmd, 1, val, 3)) {
return 0;
}
return UINT16_VALUE(val[1],val[0]);
}
#endif // AP_TEMPERATURE_SENSOR_MLX90614_ENABLED
24 changes: 24 additions & 0 deletions libraries/AP_TemperatureSensor/AP_TemperatureSensor_MLX90614.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#pragma once

#include "AP_TemperatureSensor_Backend.h"

#if AP_TEMPERATURE_SENSOR_MLX90614_ENABLED


class AP_TemperatureSensor_MLX90614 : public AP_TemperatureSensor_Backend {
using AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend;
public:

void init(void) override;

void update() override {};

private:

// update the temperature, called at 20Hz
void _timer(void);

uint16_t read_data(uint8_t cmd);
uint16_t read_eeprom(uint8_t address) {return read_data(address | 0x20);};
};
#endif // AP_TEMPERATURE_SENSOR_MLX90614_ENABLED
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
// @Param: TYPE
// @DisplayName: Temperature Sensor Type
// @Description: Enables temperature sensors
// @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog, 6:DroneCAN
// @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog, 6:DroneCAN, 7:MLX90614
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, (float)Type::NONE, AP_PARAM_FLAG_ENABLE),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ class AP_TemperatureSensor_Params {
TSYS03 = 4,
ANALOG = 5,
DRONECAN = 6,
MLX90614 = 7,
};

// option to map to another system component
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,10 @@
#error AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS
#endif

#ifndef AP_TEMPERATURE_SENSOR_MLX90614_ENABLED
#define AP_TEMPERATURE_SENSOR_MLX90614_ENABLED AP_TEMPERATURE_SENSOR_ENABLED
#endif

// maximum number of Temperature Sensors
#ifndef AP_TEMPERATURE_SENSOR_MAX_INSTANCES
#define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 3
Expand Down

0 comments on commit 693258b

Please sign in to comment.