Skip to content

Commit

Permalink
Multi instance SHT3x driver support
Browse files Browse the repository at this point in the history
  • Loading branch information
roman-dvorak committed Jan 27, 2022
1 parent bdddf35 commit 1c8a015
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 7 deletions.
6 changes: 2 additions & 4 deletions ROMFS/px4fmu_common/init.d/rc.sensors
Original file line number Diff line number Diff line change
Expand Up @@ -133,10 +133,8 @@ fi
# SHT3x temperature and hygrometer sensor, external I2C
if param compare -s SENS_EN_SHT3X 1
then
if ! sht3x start -X
then
sht3x start -X -a 0x45
fi
sht3x start -X
sht3x start -X -a 0x45
fi

# TE MS4525 differential pressure sensor external I2C
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/hygrometer/sht3x/sht3x.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/sensor_hygrometer.h>

#define SHT3X_CMD_READ_STATUS 0xF32D
Expand Down Expand Up @@ -114,7 +114,7 @@ class SHT3X : public device::I2C, public ModuleParams, public I2CSPIDriver<SHT3X
int _last_state = sht3x_state::INIT;
uint32_t _time_in_state = hrt_absolute_time();
uint16_t _last_command = 0;
uORB::Publication<sensor_hygrometer_s> _sensor_hygrometer_pub{ORB_ID(sensor_hygrometer)};
uORB::PublicationMulti<sensor_hygrometer_s> _sensor_hygrometer_pub{ORB_ID(sensor_hygrometer)};

DEFINE_PARAMETERS(
(ParamInt<px4::params::SENS_EN_SHT3X>) _param_sens_en_sht3x
Expand Down
2 changes: 1 addition & 1 deletion src/modules/logger/logged_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ void LoggedTopics::add_default_topics()
add_topic("rtl_time_estimate", 1000);
add_topic("safety");
add_topic("sensor_combined");
add_topic("sensor_hygrometer", 500);
add_optional_topic("sensor_correction");
add_optional_topic("sensor_gyro_fft", 50);
add_topic("sensor_selection");
Expand Down Expand Up @@ -123,6 +122,7 @@ void LoggedTopics::add_default_topics()
add_topic_multi("airspeed_wind", 1000, 4);
add_topic_multi("control_allocator_status", 200, 2);
add_optional_topic_multi("rate_ctrl_status", 200, 2);
add_topic_multi("sensor_hygrometer", 500, 4);
add_optional_topic_multi("telemetry_status", 1000, 4);

// EKF multi topics (currently max 9 estimators)
Expand Down

0 comments on commit 1c8a015

Please sign in to comment.