Skip to content

Commit b1f704c

Browse files
peterbarkertridge
authored andcommitted
AP_TemperatureSensor: add support for SHT3x-DIS temperature sensor
1 parent 8df29a3 commit b1f704c

File tree

6 files changed

+204
-1
lines changed

6 files changed

+204
-1
lines changed

libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
#include "AP_TemperatureSensor_Analog.h"
3434
#include "AP_TemperatureSensor_DroneCAN.h"
3535
#include "AP_TemperatureSensor_MLX90614.h"
36+
#include "AP_TemperatureSensor_SHT3x.h"
3637

3738
#include <AP_Logger/AP_Logger.h>
3839
#include <AP_Vehicle/AP_Vehicle_Type.h>
@@ -192,6 +193,11 @@ void AP_TemperatureSensor::init()
192193
drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_MAX31865(*this, _state[instance], _params[instance]);
193194
break;
194195
#endif
196+
#if AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
197+
case AP_TemperatureSensor_Params::Type::SHT3x:
198+
drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_SHT3x(*this, _state[instance], _params[instance]);
199+
break;
200+
#endif // AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
195201
#if AP_TEMPERATURE_SENSOR_TSYS03_ENABLED
196202
case AP_TemperatureSensor_Params::Type::TSYS03:
197203
drivers[instance] = NEW_NOTHROW AP_TemperatureSensor_TSYS03(*this, _state[instance], _params[instance]);

libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
3434
// @Param: TYPE
3535
// @DisplayName: Temperature Sensor Type
3636
// @Description: Enables temperature sensors
37-
// @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog, 6:DroneCAN, 7:MLX90614
37+
// @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog, 6:DroneCAN, 7:MLX90614, 8:SHT3x
3838
// @User: Standard
3939
// @RebootRequired: True
4040
AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, (float)Type::NONE, AP_PARAM_FLAG_ENABLE),

libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ class AP_TemperatureSensor_Params {
3535
ANALOG = 5,
3636
DRONECAN = 6,
3737
MLX90614 = 7,
38+
SHT3x = 8,
3839
};
3940

4041
// option to map to another system component
Lines changed: 115 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,115 @@
1+
/*
2+
This program is free software: you can redistribute it and/or modify
3+
it under the terms of the GNU General Public License as published by
4+
the Free Software Foundation, either version 3 of the License, or
5+
(at your option) any later version.
6+
7+
This program is distributed in the hope that it will be useful,
8+
but WITHOUT ANY WARRANTY; without even the implied warranty of
9+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10+
GNU General Public License for more details.
11+
12+
You should have received a copy of the GNU General Public License
13+
along with this program. If not, see <http://www.gnu.org/licenses/>.
14+
15+
Written with reference to the PX4 driver written by Roman Dvorak <dvorakroman@thunderfly.cz>
16+
17+
*/
18+
19+
#include "AP_TemperatureSensor_SHT3x.h"
20+
21+
#if AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
22+
#include <utility>
23+
#include <stdio.h>
24+
#include <AP_HAL/I2CDevice.h>
25+
#include <AP_Math/AP_Math.h>
26+
27+
#include <GCS_MAVLink/GCS.h>
28+
29+
extern const AP_HAL::HAL &hal;
30+
31+
void AP_TemperatureSensor_SHT3x::init()
32+
{
33+
constexpr char name[] = "SHT3x";
34+
(void)name; // sometimes this is unused (e.g. HAL_GCS_ENABLED false)
35+
36+
_dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address));
37+
if (!_dev) {
38+
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s device is null!", name);
39+
return;
40+
}
41+
42+
WITH_SEMAPHORE(_dev->get_semaphore());
43+
44+
_dev->set_retries(10);
45+
46+
// read serial number
47+
static const uint8_t read_sn_cmd[2] { 0x37, 0x80 };
48+
uint8_t sn[6];
49+
if (!_dev->transfer(read_sn_cmd, ARRAY_SIZE(read_sn_cmd), sn, ARRAY_SIZE(sn))) {
50+
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s read sn failed", name);
51+
return;
52+
}
53+
// emit serial number, more of confirmation we have the sensor:
54+
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SHT3x: SN%x%x%x%x%x%x", sn[0], sn[1], sn[2], sn[3], sn[4], sn[5]);
55+
56+
// reset
57+
static const uint8_t soft_reset_cmd[2] { 0x30, 0xA2 }; // page 12
58+
if (!_dev->transfer(soft_reset_cmd, ARRAY_SIZE(soft_reset_cmd), nullptr, 0)) {
59+
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s reset failed", name);
60+
return;
61+
}
62+
63+
hal.scheduler->delay(4);
64+
65+
start_next_sample();
66+
67+
// lower retries for run
68+
_dev->set_retries(3);
69+
70+
/* Request 20Hz update */
71+
_dev->register_periodic_callback(50 * AP_USEC_PER_MSEC,
72+
FUNCTOR_BIND_MEMBER(&AP_TemperatureSensor_SHT3x::_timer, void));
73+
}
74+
75+
bool AP_TemperatureSensor_SHT3x::read_measurements(uint16_t &temp, uint16_t &humidity) const
76+
{
77+
uint8_t val[6];
78+
if (!_dev->transfer(nullptr, 1, val, ARRAY_SIZE(val))) {
79+
return 0;
80+
}
81+
82+
if (val[2] != crc8_generic(&val[0], 2, 0x31, 0xff)) {
83+
// temperature CRC is incorrect
84+
return false;
85+
}
86+
87+
if (val[5] != crc8_generic(&val[3], 2, 0x31, 0xff)) {
88+
// humidity CRC is incorrect
89+
return false;
90+
}
91+
92+
temp = val[0] << 8 | val[1];
93+
humidity = val[3] << 8 | val[4];
94+
return true;
95+
}
96+
97+
void AP_TemperatureSensor_SHT3x::_timer(void)
98+
{
99+
uint16_t encoded_temp;
100+
uint16_t encoded_humidity;
101+
if (read_measurements(encoded_temp, encoded_humidity)) {
102+
const float temp = -45 + 175 * (encoded_temp/65535.0);
103+
set_temperature(temp);
104+
}
105+
106+
start_next_sample();
107+
}
108+
109+
void AP_TemperatureSensor_SHT3x::start_next_sample()
110+
{
111+
static const uint8_t start_measurement_command[2] { 0x2c, 0x06 };
112+
_dev->transfer(start_measurement_command, ARRAY_SIZE(start_measurement_command), nullptr, 0);
113+
}
114+
115+
#endif // AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
/*
2+
This program is free software: you can redistribute it and/or modify
3+
it under the terms of the GNU General Public License as published by
4+
the Free Software Foundation, either version 3 of the License, or
5+
(at your option) any later version.
6+
7+
This program is distributed in the hope that it will be useful,
8+
but WITHOUT ANY WARRANTY; without even the implied warranty of
9+
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10+
GNU General Public License for more details.
11+
12+
You should have received a copy of the GNU General Public License
13+
along with this program. If not, see <http://www.gnu.org/licenses/>.
14+
*/
15+
16+
/*
17+
* I2C driver for Sensiron SHT3x digital temperature sensor
18+
19+
https://sensirion.com/media/documents/213E6A3B/63A5A569/Datasheet_SHT3x_DIS.pdf
20+
21+
22+
Testing:
23+
24+
pbarker@fx:~$ cat /tmp/extra.hwdef
25+
define AP_TEMPERATURE_SENSOR_ENABLED 1
26+
define AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED 1
27+
pbarker@fx:~$ ./waf configure --board=CubeOrange --extra-hwdef=/tmp/extra.hwdef
28+
pbarker@fx:~/rc/ardupilot(pr/SHT3x)$ ./waf rover --upload
29+
30+
# when plugging into I2C1 on a CubeOrange:
31+
param set TEMP1_TYPE 8
32+
param set TEMP1_BUS 0
33+
34+
this is bad:
35+
AP: SHT3x reset failed
36+
AP: SHT3x: SN1841CC41FC5
37+
38+
param set TEMP_LOG 1
39+
param set LOG_DISARMED 1
40+
...
41+
param set LOG_DISARMED 0
42+
43+
Download log and check for temperatures
44+
45+
*/
46+
47+
#pragma once
48+
49+
#include "AP_TemperatureSensor_config.h"
50+
51+
#if AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
52+
53+
#include "AP_TemperatureSensor_Backend.h"
54+
55+
class AP_TemperatureSensor_SHT3x : public AP_TemperatureSensor_Backend {
56+
57+
using AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend;
58+
59+
public:
60+
__INITFUNC__ void init(void) override;
61+
62+
void update() override {};
63+
64+
private:
65+
// reset device
66+
bool reset(void) const;
67+
68+
// prod device to start preparing a measurement:
69+
void start_next_sample();
70+
// read measurements from device:
71+
bool read_measurements(uint16_t &temp, uint16_t &humidity) const;
72+
73+
// update the temperature, called at 20Hz
74+
void _timer(void);
75+
76+
};
77+
#endif // AP_TEMPERATURE_SENSOR_SHT3X_ENABLED

libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,10 @@
3939
#define AP_TEMPERATURE_SENSOR_MLX90614_ENABLED AP_TEMPERATURE_SENSOR_ENABLED
4040
#endif
4141

42+
#ifndef AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
43+
#define AP_TEMPERATURE_SENSOR_SHT3X_ENABLED AP_TEMPERATURE_SENSOR_ENABLED
44+
#endif // AP_TEMPERATURE_SENSOR_SHT3X_ENABLED
45+
4246
// maximum number of Temperature Sensors
4347
#ifndef AP_TEMPERATURE_SENSOR_MAX_INSTANCES
4448
#define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 3

0 commit comments

Comments
 (0)