mirror of https://github.com/ArduPilot/ardupilot
AP_TemperatureSensor: refactor for upcoming upgrades
This commit is contained in:
parent
ea27d40cf6
commit
c4f7470cbc
|
@ -42,18 +42,50 @@ const AP_Param::GroupInfo AP_TemperatureSensor::var_info[] = {
|
||||||
// @Path: AP_TemperatureSensor_Params.cpp
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
AP_SUBGROUPINFO(_params[0], "1_", 10, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
AP_SUBGROUPINFO(_params[0], "1_", 10, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES > 1
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 2
|
||||||
// @Group: 2_
|
// @Group: 2_
|
||||||
// @Path: AP_TemperatureSensor_Params.cpp
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
AP_SUBGROUPINFO(_params[1], "2_", 11, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
AP_SUBGROUPINFO(_params[1], "2_", 11, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES > 2
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 3
|
||||||
// @Group: 3_
|
// @Group: 3_
|
||||||
// @Path: AP_TemperatureSensor_Params.cpp
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
AP_SUBGROUPINFO(_params[2], "3_", 12, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
AP_SUBGROUPINFO(_params[2], "3_", 12, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 4
|
||||||
|
// @Group: 4_
|
||||||
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
|
AP_SUBGROUPINFO(_params[3], "4_", 13, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 5
|
||||||
|
// @Group: 5_
|
||||||
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
|
AP_SUBGROUPINFO(_params[4], "5_", 14, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
#endif
|
||||||
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 6
|
||||||
|
// @Group: 6_
|
||||||
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
|
AP_SUBGROUPINFO(_params[5], "6_", 15, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
#endif
|
||||||
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 7
|
||||||
|
// @Group: 7_
|
||||||
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
|
AP_SUBGROUPINFO(_params[6], "7_", 16, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
#endif
|
||||||
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 8
|
||||||
|
// @Group: 8_
|
||||||
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
|
AP_SUBGROUPINFO(_params[7], "8_", 17, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
#endif
|
||||||
|
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 9
|
||||||
|
// @Group: 9_
|
||||||
|
// @Path: AP_TemperatureSensor_Params.cpp
|
||||||
|
AP_SUBGROUPINFO(_params[8], "9_", 18, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -86,18 +118,19 @@ void AP_TemperatureSensor::init()
|
||||||
for (uint8_t instance = 0; instance < AP_TEMPERATURE_SENSOR_MAX_INSTANCES; instance++) {
|
for (uint8_t instance = 0; instance < AP_TEMPERATURE_SENSOR_MAX_INSTANCES; instance++) {
|
||||||
|
|
||||||
switch (get_type(instance)) {
|
switch (get_type(instance)) {
|
||||||
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLE
|
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
|
||||||
case Type::TSYS01:
|
case AP_TemperatureSensor::Type::TSYS01:
|
||||||
drivers[instance] = new AP_TemperatureSensor_TSYS01(*this, _state[instance], _params[instance]);
|
drivers[instance] = new AP_TemperatureSensor_TSYS01(*this, _state[instance], _params[instance]);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
case Type::NONE:
|
case AP_TemperatureSensor::Type::NONE:
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// call init function for each backend
|
// call init function for each backend
|
||||||
if (drivers[instance] != nullptr) {
|
if (drivers[instance] != nullptr) {
|
||||||
|
_state[instance].instance = instance;
|
||||||
drivers[instance]->init();
|
drivers[instance]->init();
|
||||||
// _num_instances is actually the index for looping over instances
|
// _num_instances is actually the index for looping over instances
|
||||||
// the user may have TEMP_TYPE=0 and TEMP2_TYPE=7, in which case
|
// the user may have TEMP_TYPE=0 and TEMP2_TYPE=7, in which case
|
||||||
|
@ -112,47 +145,47 @@ void AP_TemperatureSensor::init()
|
||||||
void AP_TemperatureSensor::update()
|
void AP_TemperatureSensor::update()
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<_num_instances; i++) {
|
for (uint8_t i=0; i<_num_instances; i++) {
|
||||||
if (drivers[i] != nullptr && get_type(i) != Type::NONE) {
|
if (drivers[i] != nullptr && get_type(i) != AP_TemperatureSensor::Type::NONE) {
|
||||||
drivers[i]->update();
|
drivers[i]->update();
|
||||||
|
|
||||||
#if HAL_LOGGING_ENABLED
|
#if HAL_LOGGING_ENABLED
|
||||||
const AP_Logger *logger = AP_Logger::get_singleton();
|
const AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
if (logger != nullptr && _log_flag) {
|
if (logger != nullptr && _log_flag) {
|
||||||
const uint64_t time_us = AP_HAL::micros64();
|
drivers[i]->Log_Write_TEMP();
|
||||||
drivers[i]->Log_Write_TEMP(time_us);
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_TemperatureSensor::Type AP_TemperatureSensor::get_type(uint8_t instance) const
|
AP_TemperatureSensor::Type AP_TemperatureSensor::get_type(const uint8_t instance) const
|
||||||
{
|
{
|
||||||
if (instance >= AP_TEMPERATURE_SENSOR_MAX_INSTANCES) {
|
if (instance >= AP_TEMPERATURE_SENSOR_MAX_INSTANCES) {
|
||||||
return Type::NONE;
|
return AP_TemperatureSensor::Type::NONE;
|
||||||
}
|
}
|
||||||
return (Type)_params[instance]._type.get();
|
return (AP_TemperatureSensor::Type)_params[instance].type.get();
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns true if there is a temperature reading
|
// returns true if there is a temperature reading
|
||||||
bool AP_TemperatureSensor::temperature(float &temp, const uint8_t instance) const
|
bool AP_TemperatureSensor::get_temperature(float &temp, const uint8_t instance) const
|
||||||
{
|
{
|
||||||
if (instance >= AP_TEMPERATURE_SENSOR_MAX_INSTANCES || drivers[instance] == nullptr) {
|
if (!healthy(instance)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
temp = _state[instance].temperature;
|
temp = _state[instance].temperature;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
return drivers[instance]->healthy();
|
bool AP_TemperatureSensor::healthy(const uint8_t instance) const
|
||||||
|
{
|
||||||
|
return instance < _num_instances && drivers[instance] != nullptr && drivers[instance]->healthy();
|
||||||
}
|
}
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
AP_TemperatureSensor &temperature_sensor() {
|
||||||
AP_TemperatureSensor &temperature_sensor()
|
|
||||||
{
|
|
||||||
return *AP_TemperatureSensor::get_singleton();
|
return *AP_TemperatureSensor::get_singleton();
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#ifndef AP_TEMPERATURE_SENSOR_ENABLED
|
#ifndef AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
#define AP_TEMPERATURE_SENSOR_ENABLED (BOARD_FLASH_SIZE > 1024)
|
#define AP_TEMPERATURE_SENSOR_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
|
@ -29,7 +29,9 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// first sensor is always the primary sensor
|
// first sensor is always the primary sensor
|
||||||
|
#ifndef AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE
|
||||||
#define AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE 0
|
#define AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE 0
|
||||||
|
#endif
|
||||||
|
|
||||||
// declare backend class
|
// declare backend class
|
||||||
class AP_TemperatureSensor_Backend;
|
class AP_TemperatureSensor_Backend;
|
||||||
|
@ -42,12 +44,6 @@ class AP_TemperatureSensor
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
// temperature sensor types
|
|
||||||
enum class Type {
|
|
||||||
NONE = 0,
|
|
||||||
TSYS01 = 1,
|
|
||||||
};
|
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_TemperatureSensor();
|
AP_TemperatureSensor();
|
||||||
|
|
||||||
|
@ -55,12 +51,26 @@ public:
|
||||||
|
|
||||||
static AP_TemperatureSensor *get_singleton() { return _singleton; }
|
static AP_TemperatureSensor *get_singleton() { return _singleton; }
|
||||||
|
|
||||||
|
// temperature sensor types
|
||||||
|
enum class Type : uint8_t {
|
||||||
|
NONE = 0,
|
||||||
|
TSYS01 = 1,
|
||||||
|
};
|
||||||
|
|
||||||
|
// option to map to another system component
|
||||||
|
enum class Source : uint8_t {
|
||||||
|
None = 0,
|
||||||
|
ESC = 1,
|
||||||
|
Motor = 2,
|
||||||
|
Battery_Index = 3,
|
||||||
|
Battery_ID_SerialNumber = 4,
|
||||||
|
};
|
||||||
|
|
||||||
// The TemperatureSensor_State structure is filled in by the backend driver
|
// The TemperatureSensor_State structure is filled in by the backend driver
|
||||||
struct TemperatureSensor_State {
|
struct TemperatureSensor_State {
|
||||||
const struct AP_Param::GroupInfo *var_info;
|
const struct AP_Param::GroupInfo *var_info;
|
||||||
uint32_t last_time_micros; // time when the sensor was last read in microseconds
|
uint32_t last_time_ms; // time when the sensor was last read in milliseconds
|
||||||
float temperature; // temperature (deg C)
|
float temperature; // temperature (deg C)
|
||||||
bool healthy; // temperature sensor is communicating correctly
|
|
||||||
uint8_t instance; // instance number
|
uint8_t instance; // instance number
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -73,13 +83,14 @@ public:
|
||||||
// Update the temperature for all temperature sensors
|
// Update the temperature for all temperature sensors
|
||||||
void update();
|
void update();
|
||||||
|
|
||||||
// get_type - returns temperature sensor type
|
bool get_temperature(float &temp, const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
|
||||||
Type get_type() const { return get_type(AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE); }
|
|
||||||
Type get_type(uint8_t instance) const;
|
|
||||||
|
|
||||||
// temperature
|
bool healthy(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
|
||||||
bool temperature(float &temp) const { return temperature(temp, AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE); }
|
|
||||||
bool temperature(float &temp, const uint8_t instance) const;
|
// accessors to params
|
||||||
|
Type get_type(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
|
||||||
|
Source get_source(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
|
||||||
|
int32_t get_source_id(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
|
|
@ -18,15 +18,14 @@
|
||||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
#include "AP_TemperatureSensor_Backend.h"
|
#include "AP_TemperatureSensor_Backend.h"
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
/*
|
/*
|
||||||
base class constructor.
|
base class constructor.
|
||||||
This incorporates initialisation as well.
|
This incorporates initialisation as well.
|
||||||
*/
|
*/
|
||||||
AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend(AP_TemperatureSensor &front, AP_TemperatureSensor::TemperatureSensor_State &state,
|
AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend(AP_TemperatureSensor &front,
|
||||||
|
AP_TemperatureSensor::TemperatureSensor_State &state,
|
||||||
AP_TemperatureSensor_Params ¶ms):
|
AP_TemperatureSensor_Params ¶ms):
|
||||||
_front(front),
|
_front(front),
|
||||||
_state(state),
|
_state(state),
|
||||||
|
@ -34,14 +33,29 @@ AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend(AP_TemperatureSensor
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_TemperatureSensor_Backend::Log_Write_TEMP(uint64_t time_us) const
|
// returns true if a temperature has been recently updated
|
||||||
|
bool AP_TemperatureSensor_Backend::healthy(void) const
|
||||||
|
{
|
||||||
|
return (_state.last_time_ms > 0) && (AP_HAL::millis() - _state.last_time_ms < 5000);
|
||||||
|
}
|
||||||
|
|
||||||
|
void AP_TemperatureSensor_Backend::Log_Write_TEMP() const
|
||||||
{
|
{
|
||||||
AP::logger().Write("TEMP",
|
AP::logger().Write("TEMP",
|
||||||
"TimeUS," "Instance," "Temp" , // labels
|
"TimeUS," "Instance," "Temp" , // labels
|
||||||
"s" "#" "O" , // units
|
"s" "#" "O" , // units
|
||||||
"F" "-" "0" , // multipliers
|
"F" "-" "0" , // multipliers
|
||||||
"Q" "B" "f" , // types
|
"Q" "B" "f" , // types
|
||||||
time_us, _state.instance, _state.temperature);
|
AP_HAL::micros64(), _state.instance, _state.temperature);
|
||||||
|
}
|
||||||
|
|
||||||
|
void AP_TemperatureSensor_Backend::set_temperature(const float temperature)
|
||||||
|
{
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(_sem);
|
||||||
|
_state.temperature = temperature;
|
||||||
|
_state.last_time_ms = AP_HAL::millis();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
#include "AP_TemperatureSensor.h"
|
#include "AP_TemperatureSensor.h"
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
|
#include <AP_HAL/Semaphores.h>
|
||||||
|
|
||||||
class AP_TemperatureSensor_Backend
|
class AP_TemperatureSensor_Backend
|
||||||
{
|
{
|
||||||
|
@ -31,15 +32,24 @@ public:
|
||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
|
|
||||||
// do we have a valid temperature reading?
|
// do we have a valid temperature reading?
|
||||||
bool healthy(void) const { return _state.healthy; }
|
virtual bool healthy(void) const;
|
||||||
|
|
||||||
// logging functions
|
// logging functions
|
||||||
void Log_Write_TEMP(const uint64_t time_us) const;
|
void Log_Write_TEMP() const;
|
||||||
|
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
||||||
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
void set_temperature(const float temperature);
|
||||||
|
|
||||||
AP_TemperatureSensor &_front; // reference to front-end
|
AP_TemperatureSensor &_front; // reference to front-end
|
||||||
AP_TemperatureSensor::TemperatureSensor_State &_state; // reference to this instance's state (held in the front-end)
|
AP_TemperatureSensor::TemperatureSensor_State &_state; // reference to this instance's state (held in the front-end)
|
||||||
AP_TemperatureSensor_Params &_params; // reference to this instance's parameters (held in the front-end)
|
AP_TemperatureSensor_Params &_params; // reference to this instance's parameters (held in the front-end)
|
||||||
|
|
||||||
|
private:
|
||||||
|
HAL_Semaphore _sem; // used to copy from backend to frontend
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
|
|
|
@ -1,18 +1,41 @@
|
||||||
|
/*
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#include "AP_TemperatureSensor_Params.h"
|
#include "AP_TemperatureSensor_Params.h"
|
||||||
#include "AP_TemperatureSensor.h"
|
#include "AP_TemperatureSensor.h"
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
|
|
||||||
#ifndef HAL_TEMPERATURE_SENSOR_I2C_TYPE_DEFAULT
|
#ifndef AP_TEMPERATURE_SENSOR_TYPE_DEFAULT
|
||||||
#define HAL_TEMPERATURE_SENSOR_I2C_TYPE_DEFAULT 0
|
#define AP_TEMPERATURE_SENSOR_TYPE_DEFAULT 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT
|
#ifndef AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT
|
||||||
#define HAL_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT 0
|
#define AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT
|
#ifndef AP_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT
|
||||||
#define HAL_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT 0
|
#define AP_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_TEMPERATURE_SENSOR_SOURCE_ID_DEFAULT
|
||||||
|
#define AP_TEMPERATURE_SENSOR_SOURCE_ID_DEFAULT -1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_TEMPERATURE_SENSOR_SOURCE_DEFAULT
|
||||||
|
#define AP_TEMPERATURE_SENSOR_SOURCE_DEFAULT (int8_t)AP_TemperatureSensor::Source::None
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
|
const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
|
||||||
|
@ -22,23 +45,23 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
|
||||||
// @Values: 0:Disabled, 1:TSYS01
|
// @Values: 0:Disabled, 1:TSYS01
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, _type, HAL_TEMPERATURE_SENSOR_I2C_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE),
|
AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, AP_TEMPERATURE_SENSOR_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
// @Param: BUS
|
// @Param: BUS
|
||||||
// @DisplayName: Temperature sensor I2C bus
|
// @DisplayName: Temperature sensor bus
|
||||||
// @Description: Temperature sensor I2C bus number
|
// @Description: Temperature sensor bus number, typically used to select from multiple I2C buses
|
||||||
// @Range: 0 3
|
// @Range: 0 3
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("BUS", 3, AP_TemperatureSensor_Params, _i2c_bus, HAL_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT),
|
AP_GROUPINFO("BUS", 2, AP_TemperatureSensor_Params, bus, AP_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT),
|
||||||
|
|
||||||
// @Param: ADDR
|
// @Param: ADDR
|
||||||
// @DisplayName: Temperature sensor I2C address
|
// @DisplayName: Temperature sensor address
|
||||||
// @Description: Temperature sensor I2C address
|
// @Description: Temperature sensor address, typically used for I2C address
|
||||||
// @Range: 0 127
|
// @Range: 0 127
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("ADDR", 4, AP_TemperatureSensor_Params, _i2c_address, HAL_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT),
|
AP_GROUPINFO("ADDR", 3, AP_TemperatureSensor_Params, bus_address, AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,3 +1,18 @@
|
||||||
|
/*
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
@ -10,7 +25,8 @@ public:
|
||||||
|
|
||||||
CLASS_NO_COPY(AP_TemperatureSensor_Params);
|
CLASS_NO_COPY(AP_TemperatureSensor_Params);
|
||||||
|
|
||||||
AP_Int8 _type; // 0=disabled, others see frontend enum TYPE
|
AP_Int8 type; // AP_TemperatureSensor::Type, 0=disabled, others see frontend enum TYPE
|
||||||
AP_Int8 _i2c_bus; // I2C bus number
|
AP_Int8 bus; // I2C bus number
|
||||||
AP_Int8 _i2c_address; // I2C address
|
AP_Int8 bus_address; // I2C address
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,12 +1,30 @@
|
||||||
|
/*
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#include "AP_TemperatureSensor_TSYS01.h"
|
#include "AP_TemperatureSensor_TSYS01.h"
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLE
|
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
|
||||||
#include <utility>
|
#include <utility>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
#include <AP_HAL/I2CDevice.h>
|
#include <AP_HAL/I2CDevice.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
|
#ifndef AP_TEMPERATURE_SENSOR_TSYS01_ENFORCE_KNOWN_VALID_I2C_ADDRESS
|
||||||
|
#define AP_TEMPERATURE_SENSOR_TSYS01_ENFORCE_KNOWN_VALID_I2C_ADDRESS 1
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
static const uint8_t TSYS01_CMD_RESET = 0x1E;
|
static const uint8_t TSYS01_CMD_RESET = 0x1E;
|
||||||
|
@ -18,14 +36,15 @@ void AP_TemperatureSensor_TSYS01::init()
|
||||||
{
|
{
|
||||||
constexpr char name[] = "TSYS01";
|
constexpr char name[] = "TSYS01";
|
||||||
|
|
||||||
|
#if AP_TEMPERATURE_SENSOR_TSYS01_ENFORCE_KNOWN_VALID_I2C_ADDRESS
|
||||||
// I2C Address: Default to using TSYS01_ADDR_CSB0 & Check I2C Address is Correct
|
// I2C Address: Default to using TSYS01_ADDR_CSB0 & Check I2C Address is Correct
|
||||||
uint8_t addr = _params._i2c_address;
|
if ((_params.bus_address != TSYS01_ADDR_CSB0) && (_params.bus_address != TSYS01_ADDR_CSB1)) {
|
||||||
if ((addr != TSYS01_ADDR_CSB0) && (addr != TSYS01_ADDR_CSB1)) {
|
printf("%s wrong I2C addr of 0x%2X, setting to 0x%2X", name, (unsigned)_params.bus_address.get(), (unsigned)TSYS01_ADDR_CSB0);
|
||||||
printf("%s, wrong I2C addr", name);
|
_params.bus_address.set(TSYS01_ADDR_CSB0);
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
_dev = std::move(hal.i2c_mgr->get_device(_params._i2c_bus, _params._i2c_address));
|
_dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address));
|
||||||
if (!_dev) {
|
if (!_dev) {
|
||||||
printf("%s device is null!", name);
|
printf("%s device is null!", name);
|
||||||
return;
|
return;
|
||||||
|
@ -35,19 +54,20 @@ void AP_TemperatureSensor_TSYS01::init()
|
||||||
|
|
||||||
_dev->set_retries(10);
|
_dev->set_retries(10);
|
||||||
|
|
||||||
if (!_reset()) {
|
// reset
|
||||||
|
if (!_dev->transfer(&TSYS01_CMD_RESET, 1, nullptr, 0)) {
|
||||||
printf("%s reset failed", name);
|
printf("%s reset failed", name);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
hal.scheduler->delay(4);
|
hal.scheduler->delay(4);
|
||||||
|
|
||||||
if (!_read_prom()) {
|
if (!read_prom()) {
|
||||||
printf("%s prom read failed", name);
|
printf("%s prom read failed", name);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
_convert();
|
start_next_sample();
|
||||||
|
|
||||||
// lower retries for run
|
// lower retries for run
|
||||||
_dev->set_retries(3);
|
_dev->set_retries(3);
|
||||||
|
@ -58,11 +78,6 @@ void AP_TemperatureSensor_TSYS01::init()
|
||||||
FUNCTOR_BIND_MEMBER(&AP_TemperatureSensor_TSYS01::_timer, void));
|
FUNCTOR_BIND_MEMBER(&AP_TemperatureSensor_TSYS01::_timer, void));
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_TemperatureSensor_TSYS01::_reset() const
|
|
||||||
{
|
|
||||||
return _dev->transfer(&TSYS01_CMD_RESET, 1, nullptr, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Register map
|
// Register map
|
||||||
// prom word Address
|
// prom word Address
|
||||||
// 0 0xA0 -> unused
|
// 0 0xA0 -> unused
|
||||||
|
@ -73,67 +88,65 @@ bool AP_TemperatureSensor_TSYS01::_reset() const
|
||||||
// 5 0xAA -> _k[0]
|
// 5 0xAA -> _k[0]
|
||||||
// 6 0xAC -> unused
|
// 6 0xAC -> unused
|
||||||
// 7 0xAE -> unused
|
// 7 0xAE -> unused
|
||||||
bool AP_TemperatureSensor_TSYS01::_read_prom()
|
bool AP_TemperatureSensor_TSYS01::read_prom()
|
||||||
{
|
{
|
||||||
bool success = false;
|
bool success = false;
|
||||||
for (int i = 0; i < 5; i++) {
|
for (uint8_t i = 0; i < ARRAY_SIZE(_k); i++) {
|
||||||
// Read only the prom values that we use
|
// Read only the prom values that we use
|
||||||
_k[i] = _read_prom_word(5-i);
|
_k[i] = read_prom_word(ARRAY_SIZE(_k)-i);
|
||||||
success |= _k[i] != 0;
|
success |= (_k[i] != 0);
|
||||||
}
|
}
|
||||||
return success;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Borrowed from MS Baro driver
|
// Borrowed from MS Baro driver
|
||||||
uint16_t AP_TemperatureSensor_TSYS01::_read_prom_word(uint8_t word) const
|
uint16_t AP_TemperatureSensor_TSYS01::read_prom_word(const uint8_t word) const
|
||||||
{
|
{
|
||||||
const uint8_t reg = TSYS01_CMD_READ_PROM + (word << 1);
|
const uint8_t reg = TSYS01_CMD_READ_PROM + (word << 1);
|
||||||
uint8_t val[2];
|
uint8_t val[2];
|
||||||
if (!_dev->transfer(®, 1, val, 2)) {
|
if (!_dev->transfer(®, 1, val, 2)) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
return (val[0] << 8) | val[1];
|
return UINT16_VALUE(val[0], val[1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_TemperatureSensor_TSYS01::_convert() const
|
uint32_t AP_TemperatureSensor_TSYS01::read_adc() const
|
||||||
{
|
|
||||||
return _dev->transfer(&TSYS01_CMD_CONVERT, 1, nullptr, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t AP_TemperatureSensor_TSYS01::_read_adc() const
|
|
||||||
{
|
{
|
||||||
uint8_t val[3];
|
uint8_t val[3];
|
||||||
if (!_dev->transfer(&TSYS01_CMD_READ_ADC, 1, val, 3)) {
|
if (!_dev->transfer(&TSYS01_CMD_READ_ADC, 1, val, 3)) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
return (val[0] << 16) | (val[1] << 8) | val[2];
|
return UINT32_VALUE(0,val[0],val[1],val[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_TemperatureSensor_TSYS01::_timer(void)
|
void AP_TemperatureSensor_TSYS01::_timer(void)
|
||||||
{
|
{
|
||||||
const uint32_t adc = _read_adc();
|
const uint32_t adc = read_adc();
|
||||||
_state.healthy = adc != 0;
|
|
||||||
|
|
||||||
if (_state.healthy) {
|
if (adc != 0) {
|
||||||
_calculate(adc);
|
const float temp = calculate(adc);
|
||||||
} else {
|
set_temperature(temp);
|
||||||
_state.temperature = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//printf("\nTemperature: %.2lf C", _state.temperature;
|
start_next_sample();
|
||||||
|
|
||||||
_convert();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_TemperatureSensor_TSYS01::_calculate(uint32_t adc)
|
void AP_TemperatureSensor_TSYS01::start_next_sample()
|
||||||
|
{
|
||||||
|
_dev->transfer(&TSYS01_CMD_CONVERT, 1, nullptr, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
float AP_TemperatureSensor_TSYS01::calculate(const uint32_t adc) const
|
||||||
{
|
{
|
||||||
const float adc16 = adc/256;
|
const float adc16 = adc/256;
|
||||||
_state.temperature =
|
const float temperature =
|
||||||
-2 * _k[4] * powf(10, -21) * powf(adc16, 4) +
|
-2 * _k[4] * powf(10, -21) * powf(adc16, 4) +
|
||||||
4 * _k[3] * powf(10, -16) * powf(adc16, 3) +
|
4 * _k[3] * powf(10, -16) * powf(adc16, 3) +
|
||||||
-2 * _k[2] * powf(10, -11) * powf(adc16, 2) +
|
-2 * _k[2] * powf(10, -11) * powf(adc16, 2) +
|
||||||
1 * _k[1] * powf(10, -6) * adc16 +
|
1 * _k[1] * powf(10, -6) * adc16 +
|
||||||
-1.5 * _k[0] * powf(10, -2);
|
-1.5 * _k[0] * powf(10, -2);
|
||||||
|
|
||||||
|
return temperature;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_TEMPERATURE_SENSOR_TSYS01_ENABLE
|
#endif // AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
|
||||||
|
|
|
@ -1,3 +1,18 @@
|
||||||
|
/*
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* I2C driver for Measurement Specialties MEAS TSYS01 digital temperature sensor
|
* I2C driver for Measurement Specialties MEAS TSYS01 digital temperature sensor
|
||||||
*/
|
*/
|
||||||
|
@ -5,14 +20,11 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
#include "AP_TemperatureSensor_Backend.h"
|
#include "AP_TemperatureSensor_Backend.h"
|
||||||
|
|
||||||
#ifndef AP_TEMPERATURE_SENSOR_TSYS01_ENABLE
|
#ifndef AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
|
||||||
#define AP_TEMPERATURE_SENSOR_TSYS01_ENABLE AP_TEMPERATURE_SENSOR_ENABLED
|
#define AP_TEMPERATURE_SENSOR_TSYS01_ENABLED AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLE
|
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
#include <AP_HAL/Semaphores.h>
|
|
||||||
#include <AP_HAL/Device.h>
|
|
||||||
|
|
||||||
#define TSYS01_ADDR_CSB0 0x77
|
#define TSYS01_ADDR_CSB0 0x77
|
||||||
#define TSYS01_ADDR_CSB1 0x76
|
#define TSYS01_ADDR_CSB1 0x76
|
||||||
|
@ -25,26 +37,25 @@ public:
|
||||||
|
|
||||||
void update() override {};
|
void update() override {};
|
||||||
|
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint16_t _k[5]; // internal calibration for temperature calculation
|
uint16_t _k[5]; // internal calibration for temperature calculation
|
||||||
|
|
||||||
// reset device
|
// reset device
|
||||||
bool _reset(void) const;
|
bool reset(void) const;
|
||||||
|
|
||||||
// read (relevant) internal calibration registers into _k
|
// read (relevant) internal calibration registers into _k
|
||||||
bool _read_prom(void);
|
bool read_prom(void);
|
||||||
uint16_t _read_prom_word(uint8_t word) const;
|
uint16_t read_prom_word(const uint8_t word) const;
|
||||||
|
|
||||||
// begin an ADC conversion (min:7.40ms typ:8.22ms max:9.04ms)
|
// begin an ADC conversion (min:7.40ms typ:8.22ms max:9.04ms)
|
||||||
bool _convert(void) const;
|
void start_next_sample();
|
||||||
uint32_t _read_adc(void) const;
|
uint32_t read_adc(void) const;
|
||||||
|
|
||||||
// update the temperature, called at 20Hz
|
// update the temperature, called at 20Hz
|
||||||
void _timer(void);
|
void _timer(void);
|
||||||
|
|
||||||
// calculate temperature using adc reading and internal calibration
|
// calculate temperature using adc reading and internal calibration
|
||||||
void _calculate(uint32_t adc);
|
float calculate(const uint32_t adc) const;
|
||||||
};
|
};
|
||||||
#endif // AP_TEMPERATURE_SENSOR_TSYS01_ENABLE
|
#endif // AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue