aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/drivers/drv_mag.h1
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp3
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp22
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp124
-rw-r--r--src/drivers/px4io/px4io.cpp18
-rw-r--r--src/modules/sdlog2/module.mk2
-rw-r--r--src/modules/sdlog2/sdlog2.c68
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h9
-rw-r--r--src/modules/sensors/sensors.cpp9
-rw-r--r--src/modules/uORB/topics/sensor_combined.h11
10 files changed, 170 insertions, 97 deletions
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 7fcff9d38..ca33966b0 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -63,6 +63,7 @@ struct mag_report {
float z;
float range_ga;
float scaling;
+ float temperature;
int16_t x_raw;
int16_t y_raw;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 2b3520fc8..fd4d4cff5 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -927,6 +927,9 @@ HMC5883::collect()
/* z remains z */
new_report.z = ((zraw_f * _range_scale) - _scale.z_offset) * _scale.z_scale;
+ /* this sensor does not measure temperature, output a constant value */
+ new_report.temperature = 0.0f;
+
if (!(_pub_blocked)) {
if (_mag_topic != -1) {
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 84f7fb5c8..e594c92a1 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -305,6 +305,9 @@ private:
float _last_accel[3];
uint8_t _constant_accel_count;
+ // last temperature value
+ float _last_temperature;
+
// this is used to support runtime checking of key
// configuration registers to detect SPI bus errors and sensor
// reset
@@ -567,6 +570,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota
_accel_filter_z(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
_rotation(rotation),
_constant_accel_count(0),
+ _last_temperature(0),
_checked_next(0)
{
@@ -711,7 +715,7 @@ LSM303D::reset()
/* enable mag */
write_checked_reg(ADDR_CTRL_REG7, REG7_CONT_MODE_M);
- write_checked_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
+ write_checked_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M | REG5_ENABLE_T);
write_checked_reg(ADDR_CTRL_REG3, 0x04); // DRDY on ACCEL on INT1
write_checked_reg(ADDR_CTRL_REG4, 0x04); // DRDY on MAG on INT2
@@ -1507,6 +1511,9 @@ LSM303D::measure()
accel_report.timestamp = hrt_absolute_time();
+ // use the temperature from the last mag reading
+ accel_report.temperature = _last_temperature;
+
// report the error count as the sum of the number of bad
// register reads and bad values. This allows the higher level
// code to decide if it should use this sensor based on
@@ -1588,6 +1595,7 @@ LSM303D::mag_measure()
#pragma pack(push, 1)
struct {
uint8_t cmd;
+ int16_t temperature;
uint8_t status;
int16_t x;
int16_t y;
@@ -1603,7 +1611,7 @@ LSM303D::mag_measure()
/* fetch data from the sensor */
memset(&raw_mag_report, 0, sizeof(raw_mag_report));
- raw_mag_report.cmd = ADDR_STATUS_M | DIR_READ | ADDR_INCREMENT;
+ raw_mag_report.cmd = ADDR_OUT_TEMP_L | DIR_READ | ADDR_INCREMENT;
transfer((uint8_t *)&raw_mag_report, (uint8_t *)&raw_mag_report, sizeof(raw_mag_report));
/*
@@ -1632,7 +1640,7 @@ LSM303D::mag_measure()
float yraw_f = mag_report.y_raw;
float zraw_f = mag_report.z_raw;
- // apply user specified rotation
+ /* apply user specified rotation */
rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
mag_report.x = ((xraw_f * _mag_range_scale) - _mag_scale.x_offset) * _mag_scale.x_scale;
@@ -1642,9 +1650,14 @@ LSM303D::mag_measure()
mag_report.range_ga = (float)_mag_range_ga;
mag_report.error_count = perf_event_count(_bad_registers) + perf_event_count(_bad_values);
+ /* remember the temperature. The datasheet isn't clear, but it
+ * seems to be a signed offset from 25 degrees C in units of 0.125C
+ */
+ _last_temperature = 25 + (raw_mag_report.temperature * 0.125f);
+ mag_report.temperature = _last_temperature;
+
_mag_reports->force(&mag_report);
- /* XXX please check this poll_notify, is it the right one? */
/* notify anyone waiting for data */
poll_notify(POLLIN);
@@ -1681,6 +1694,7 @@ LSM303D::print_info()
(unsigned)_checked_values[i]);
}
}
+ ::printf("temperature: %.2f\n", (double)_last_temperature);
}
void
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index eaf25a9f3..b6642e2bb 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -284,6 +284,9 @@ private:
// self test
volatile bool _in_factory_test;
+ // last temperature reading for print_info()
+ float _last_temperature;
+
/**
* Start automatic measurement.
*/
@@ -359,7 +362,7 @@ private:
* @param max_g The maximum G value the range must support.
* @return OK if the value can be supported, -ERANGE otherwise.
*/
- int set_range(unsigned max_g);
+ int set_accel_range(unsigned max_g);
/**
* Swap a 16-bit value read from the MPU6000 to native byte order.
@@ -518,7 +521,8 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev
_gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
_rotation(rotation),
_checked_next(0),
- _in_factory_test(false)
+ _in_factory_test(false),
+ _last_temperature(0)
{
// disable debug() calls
_debug_enabled = false;
@@ -713,37 +717,7 @@ int MPU6000::reset()
_gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F);
_gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F;
- // product-specific scaling
- switch (_product) {
- case MPU6000ES_REV_C4:
- case MPU6000ES_REV_C5:
- case MPU6000_REV_C4:
- case MPU6000_REV_C5:
- // Accel scale 8g (4096 LSB/g)
- // Rev C has different scaling than rev D
- write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
- break;
-
- case MPU6000ES_REV_D6:
- case MPU6000ES_REV_D7:
- case MPU6000ES_REV_D8:
- case MPU6000_REV_D6:
- case MPU6000_REV_D7:
- case MPU6000_REV_D8:
- case MPU6000_REV_D9:
- case MPU6000_REV_D10:
- // default case to cope with new chip revisions, which
- // presumably won't have the accel scaling bug
- default:
- // Accel scale 8g (4096 LSB/g)
- write_checked_reg(MPUREG_ACCEL_CONFIG, 2 << 3);
- break;
- }
-
- // Correct accel scale factors of 4096 LSB/g
- // scale to m/s^2 ( 1g = 9.81 m/s^2)
- _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
- _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
+ set_accel_range(8);
usleep(1000);
@@ -1297,11 +1271,8 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
case ACCELIOCSRANGE:
- /* XXX not implemented */
- // XXX change these two values on set:
- // _accel_range_scale = (9.81f / 4096.0f);
- // _accel_range_m_s2 = 8.0f * 9.81f;
- return -EINVAL;
+ return set_accel_range(arg);
+
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2)/MPU6000_ONE_G + 0.5f);
@@ -1451,44 +1422,46 @@ MPU6000::write_checked_reg(unsigned reg, uint8_t value)
}
int
-MPU6000::set_range(unsigned max_g)
+MPU6000::set_accel_range(unsigned max_g_in)
{
-#if 0
- uint8_t rangebits;
- float rangescale;
-
- if (max_g > 16) {
- return -ERANGE;
-
- } else if (max_g > 8) { /* 16G */
- rangebits = OFFSET_LSB1_RANGE_16G;
- rangescale = 1.98;
-
- } else if (max_g > 4) { /* 8G */
- rangebits = OFFSET_LSB1_RANGE_8G;
- rangescale = 0.99;
-
- } else if (max_g > 3) { /* 4G */
- rangebits = OFFSET_LSB1_RANGE_4G;
- rangescale = 0.5;
-
- } else if (max_g > 2) { /* 3G */
- rangebits = OFFSET_LSB1_RANGE_3G;
- rangescale = 0.38;
-
- } else if (max_g > 1) { /* 2G */
- rangebits = OFFSET_LSB1_RANGE_2G;
- rangescale = 0.25;
+ // workaround for bugged versions of MPU6k (rev C)
+ switch (_product) {
+ case MPU6000ES_REV_C4:
+ case MPU6000ES_REV_C5:
+ case MPU6000_REV_C4:
+ case MPU6000_REV_C5:
+ write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
+ _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
+ _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
+ return OK;
+ }
- } else { /* 1G */
- rangebits = OFFSET_LSB1_RANGE_1G;
- rangescale = 0.13;
+ uint8_t afs_sel;
+ float lsb_per_g;
+ float max_accel_g;
+
+ if (max_g_in > 8) { // 16g - AFS_SEL = 3
+ afs_sel = 3;
+ lsb_per_g = 2048;
+ max_accel_g = 16;
+ } else if (max_g_in > 4) { // 8g - AFS_SEL = 2
+ afs_sel = 2;
+ lsb_per_g = 4096;
+ max_accel_g = 8;
+ } else if (max_g_in > 2) { // 4g - AFS_SEL = 1
+ afs_sel = 1;
+ lsb_per_g = 8192;
+ max_accel_g = 4;
+ } else { // 2g - AFS_SEL = 0
+ afs_sel = 0;
+ lsb_per_g = 16384;
+ max_accel_g = 2;
}
- /* adjust sensor configuration */
- modify_reg(ADDR_OFFSET_LSB1, OFFSET_LSB1_RANGE_MASK, rangebits);
- _range_scale = rangescale;
-#endif
+ write_checked_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
+ _accel_range_scale = (MPU6000_ONE_G / lsb_per_g);
+ _accel_range_m_s2 = max_accel_g * MPU6000_ONE_G;
+
return OK;
}
@@ -1729,8 +1702,10 @@ MPU6000::measure()
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
+ _last_temperature = (report.temp) / 361.0f + 35.0f;
+
arb.temperature_raw = report.temp;
- arb.temperature = (report.temp) / 361.0f + 35.0f;
+ arb.temperature = _last_temperature;
grb.x_raw = report.gyro_x;
grb.y_raw = report.gyro_y;
@@ -1755,7 +1730,7 @@ MPU6000::measure()
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
- grb.temperature = (report.temp) / 361.0f + 35.0f;
+ grb.temperature = _last_temperature;
_accel_reports->force(&arb);
_gyro_reports->force(&grb);
@@ -1803,6 +1778,7 @@ MPU6000::print_info()
(unsigned)_checked_values[i]);
}
}
+ ::printf("temperature: %.1f\n", (double)_last_temperature);
}
void
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index f62df54f6..1512566fa 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1291,6 +1291,24 @@ PX4IO::io_set_rc_config()
input_map[ichan - 1] = 4;
}
+ /* AUX 1*/
+ param_get(param_find("RC_MAP_AUX1"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ input_map[ichan - 1] = 5;
+ }
+
+ /* AUX 2*/
+ param_get(param_find("RC_MAP_AUX2"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ input_map[ichan - 1] = 6;
+ }
+
+ /* AUX 3*/
+ param_get(param_find("RC_MAP_AUX3"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ input_map[ichan - 1] = 7;
+ }
+
/* MAIN MODE SWITCH */
param_get(param_find("RC_MAP_MODE_SW"), &ichan);
if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
index 91a9611d4..8fded0bdb 100644
--- a/src/modules/sdlog2/module.mk
+++ b/src/modules/sdlog2/module.mk
@@ -46,5 +46,5 @@ MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
-EXTRACFLAGS = -Wframe-larger-than=1300
+EXTRACFLAGS = -Wframe-larger-than=1400
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 04bf71c17..1c8cdd4be 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -340,15 +340,32 @@ int sdlog2_main(int argc, char *argv[])
exit(0);
}
+ if (!thread_running) {
+ warnx("not started\n");
+ return 1;
+ }
+
if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- sdlog2_status();
+ sdlog2_status();
+ return 0;
+ }
- } else {
- warnx("not started\n");
- }
+ if (!strcmp(argv[1], "on")) {
+ struct vehicle_command_s cmd;
+ cmd.command = VEHICLE_CMD_PREFLIGHT_STORAGE;
+ cmd.param3 = 1;
+ int fd = orb_advertise(ORB_ID(vehicle_command), &cmd);
+ close(fd);
+ return 0;
+ }
- exit(0);
+ if (!strcmp(argv[1], "off")) {
+ struct vehicle_command_s cmd;
+ cmd.command = VEHICLE_CMD_PREFLIGHT_STORAGE;
+ cmd.param3 = 0;
+ int fd = orb_advertise(ORB_ID(vehicle_command), &cmd);
+ close(fd);
+ return 0;
}
sdlog2_usage("unrecognized command");
@@ -627,13 +644,16 @@ static void *logwriter_thread(void *arg)
void sdlog2_start_log()
{
+ if (logging_enabled) {
+ return;
+ }
+
/* create log dir if needed */
if (create_log_dir() != 0) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] error creating log dir");
exit(1);
}
-
/* initialize statistics counter */
log_bytes_written = 0;
start_time = hrt_absolute_time();
@@ -674,6 +694,10 @@ void sdlog2_start_log()
void sdlog2_stop_log()
{
+ if (!logging_enabled) {
+ return;
+ }
+
logging_enabled = false;
/* wake up write thread one last time */
@@ -1347,6 +1371,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0];
log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1];
log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2];
+ log_msg.body.log_IMU.temp_gyro = buf.sensor.gyro_temp;
+ log_msg.body.log_IMU.temp_acc = buf.sensor.accelerometer_temp;
+ log_msg.body.log_IMU.temp_mag = buf.sensor.magnetometer_temp;
LOGBUFFER_WRITE_AND_COUNT(IMU);
}
@@ -1402,6 +1429,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer1_ga[0];
log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer1_ga[1];
log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer1_ga[2];
+ log_msg.body.log_IMU.temp_gyro = buf.sensor.gyro1_temp;
+ log_msg.body.log_IMU.temp_acc = buf.sensor.accelerometer1_temp;
+ log_msg.body.log_IMU.temp_mag = buf.sensor.magnetometer1_temp;
LOGBUFFER_WRITE_AND_COUNT(IMU);
}
@@ -1431,6 +1461,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer2_ga[0];
log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer2_ga[1];
log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer2_ga[2];
+ log_msg.body.log_IMU.temp_gyro = buf.sensor.gyro2_temp;
+ log_msg.body.log_IMU.temp_acc = buf.sensor.accelerometer2_temp;
+ log_msg.body.log_IMU.temp_mag = buf.sensor.magnetometer2_temp;
LOGBUFFER_WRITE_AND_COUNT(IMU);
}
@@ -1810,13 +1843,18 @@ int sdlog2_thread_main(int argc, char *argv[])
void sdlog2_status()
{
- float kibibytes = log_bytes_written / 1024.0f;
- float mebibytes = kibibytes / 1024.0f;
- float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
-
- warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
warnx("extended logging: %s", (_extended_logging) ? "ON" : "OFF");
- mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
+ if (!logging_enabled) {
+ warnx("standing by");
+ } else {
+
+ float kibibytes = log_bytes_written / 1024.0f;
+ float mebibytes = kibibytes / 1024.0f;
+ float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
+
+ warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
+ mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
+ }
}
/**
@@ -1904,13 +1942,15 @@ void handle_command(struct vehicle_command_s *cmd)
switch (cmd->command) {
case VEHICLE_CMD_PREFLIGHT_STORAGE:
- param = (int)(cmd->param3);
+ param = (int)(cmd->param3 + 0.5f);
if (param == 1) {
sdlog2_start_log();
} else if (param == 0) {
sdlog2_stop_log();
+ } else {
+ warnx("unknown storage cmd");
}
break;
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 54b0fe73f..49483b15a 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -89,6 +89,9 @@ struct log_IMU_s {
float mag_x;
float mag_y;
float mag_z;
+ float temp_acc;
+ float temp_gyro;
+ float temp_mag;
};
/* --- SENS - OTHER SENSORS --- */
@@ -471,9 +474,9 @@ static const struct log_format_s log_formats[] = {
/* business-level messages, ID < 0x80 */
LOG_FORMAT(ATT, "fffffffffffff", "qw,qx,qy,qz,Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
- LOG_FORMAT_S(IMU, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
- LOG_FORMAT_S(IMU1, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
- LOG_FORMAT_S(IMU2, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT_S(IMU, IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"),
+ LOG_FORMAT_S(IMU1, IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"),
+ LOG_FORMAT_S(IMU2, IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"),
LOG_FORMAT_S(SENS, SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
LOG_FORMAT_S(AIR1, SENS, "fffff", "BaroPa,BaroAlt,BaroTmp,DiffPres,DiffPresF"),
LOG_FORMAT(LPOS, "ffffffffLLfBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,GFlg,EPH,EPV"),
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 527ca2210..3b93393d2 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1015,6 +1015,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer_timestamp = accel_report.timestamp;
raw.accelerometer_errcount = accel_report.error_count;
+ raw.accelerometer_temp = accel_report.temperature;
}
orb_check(_accel1_sub, &accel_updated);
@@ -1037,6 +1038,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer1_timestamp = accel_report.timestamp;
raw.accelerometer1_errcount = accel_report.error_count;
+ raw.accelerometer1_temp = accel_report.temperature;
}
orb_check(_accel2_sub, &accel_updated);
@@ -1059,6 +1061,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer2_timestamp = accel_report.timestamp;
raw.accelerometer2_errcount = accel_report.error_count;
+ raw.accelerometer2_temp = accel_report.temperature;
}
}
@@ -1086,6 +1089,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.timestamp = gyro_report.timestamp;
raw.gyro_errcount = gyro_report.error_count;
+ raw.gyro_temp = gyro_report.temperature;
}
orb_check(_gyro1_sub, &gyro_updated);
@@ -1108,6 +1112,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.gyro1_timestamp = gyro_report.timestamp;
raw.gyro1_errcount = gyro_report.error_count;
+ raw.gyro1_temp = gyro_report.temperature;
}
orb_check(_gyro2_sub, &gyro_updated);
@@ -1130,6 +1135,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.gyro2_timestamp = gyro_report.timestamp;
raw.gyro2_errcount = gyro_report.error_count;
+ raw.gyro2_temp = gyro_report.temperature;
}
}
@@ -1158,6 +1164,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer_timestamp = mag_report.timestamp;
raw.magnetometer_errcount = mag_report.error_count;
+ raw.magnetometer_temp = mag_report.temperature;
}
orb_check(_mag1_sub, &mag_updated);
@@ -1181,6 +1188,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer1_timestamp = mag_report.timestamp;
raw.magnetometer1_errcount = mag_report.error_count;
+ raw.magnetometer1_temp = mag_report.temperature;
}
orb_check(_mag2_sub, &mag_updated);
@@ -1204,6 +1212,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer2_timestamp = mag_report.timestamp;
raw.magnetometer2_errcount = mag_report.error_count;
+ raw.magnetometer2_temp = mag_report.temperature;
}
}
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index ded82adea..a19f3dc10 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -83,6 +83,7 @@ struct sensor_combined_s {
int16_t gyro_raw[3]; /**< Raw sensor values of angular velocity */
float gyro_rad_s[3]; /**< Angular velocity in radian per seconds */
unsigned gyro_errcount; /**< Error counter for gyro 0 */
+ float gyro_temp; /**< Temperature of gyro 0 */
int16_t accelerometer_raw[3]; /**< Raw acceleration in NED body frame */
float accelerometer_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
@@ -90,6 +91,7 @@ struct sensor_combined_s {
float accelerometer_range_m_s2; /**< Accelerometer measurement range in m/s^2 */
uint64_t accelerometer_timestamp; /**< Accelerometer timestamp */
unsigned accelerometer_errcount; /**< Error counter for accel 0 */
+ float accelerometer_temp; /**< Temperature of accel 0 */
int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame */
float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
@@ -98,36 +100,43 @@ struct sensor_combined_s {
float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */
uint64_t magnetometer_timestamp; /**< Magnetometer timestamp */
unsigned magnetometer_errcount; /**< Error counter for mag 0 */
+ float magnetometer_temp; /**< Temperature of mag 0 */
int16_t gyro1_raw[3]; /**< Raw sensor values of angular velocity */
float gyro1_rad_s[3]; /**< Angular velocity in radian per seconds */
uint64_t gyro1_timestamp; /**< Gyro timestamp */
unsigned gyro1_errcount; /**< Error counter for gyro 1 */
+ float gyro1_temp; /**< Temperature of gyro 1 */
int16_t accelerometer1_raw[3]; /**< Raw acceleration in NED body frame */
float accelerometer1_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
uint64_t accelerometer1_timestamp; /**< Accelerometer timestamp */
unsigned accelerometer1_errcount; /**< Error counter for accel 1 */
+ float accelerometer1_temp; /**< Temperature of accel 1 */
int16_t magnetometer1_raw[3]; /**< Raw magnetic field in NED body frame */
float magnetometer1_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
uint64_t magnetometer1_timestamp; /**< Magnetometer timestamp */
- unsigned magnetometer1_errcount; /**< Error counter for mag 0 */
+ unsigned magnetometer1_errcount; /**< Error counter for mag 1 */
+ float magnetometer1_temp; /**< Temperature of mag 1 */
int16_t gyro2_raw[3]; /**< Raw sensor values of angular velocity */
float gyro2_rad_s[3]; /**< Angular velocity in radian per seconds */
uint64_t gyro2_timestamp; /**< Gyro timestamp */
unsigned gyro2_errcount; /**< Error counter for gyro 1 */
+ float gyro2_temp; /**< Temperature of gyro 1 */
int16_t accelerometer2_raw[3]; /**< Raw acceleration in NED body frame */
float accelerometer2_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
uint64_t accelerometer2_timestamp; /**< Accelerometer timestamp */
unsigned accelerometer2_errcount; /**< Error counter for accel 2 */
+ float accelerometer2_temp; /**< Temperature of accel 2 */
int16_t magnetometer2_raw[3]; /**< Raw magnetic field in NED body frame */
float magnetometer2_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
uint64_t magnetometer2_timestamp; /**< Magnetometer timestamp */
unsigned magnetometer2_errcount; /**< Error counter for mag 2 */
+ float magnetometer2_temp; /**< Temperature of mag 2 */
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
float baro_alt_meter; /**< Altitude, already temp. comp. */