aboutsummaryrefslogtreecommitdiff
path: root/src/modules/sdlog2
diff options
context:
space:
mode:
authordominiho <dominik.honegger@inf.ethz.ch>2014-10-30 16:39:02 +0100
committerdominiho <dominik.honegger@inf.ethz.ch>2014-10-30 16:39:02 +0100
commit9f64953bb9f7a51042922f30ad15a367d82fb4d5 (patch)
tree3c82c31c18f23703127f5e89ac7fc0b2937c8805 /src/modules/sdlog2
parentaba77d062f414f4a1760bc9b4f267f099206b8df (diff)
downloadpx4-firmware-9f64953bb9f7a51042922f30ad15a367d82fb4d5.tar.gz
px4-firmware-9f64953bb9f7a51042922f30ad15a367d82fb4d5.tar.bz2
px4-firmware-9f64953bb9f7a51042922f30ad15a367d82fb4d5.zip
replaced optical_flow mavlink message with optical_flow_rad, added gyro_temperature, adapted sd2log for px4flow integral frame
Diffstat (limited to 'src/modules/sdlog2')
-rw-r--r--src/modules/sdlog2/sdlog2.c13
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h18
2 files changed, 20 insertions, 11 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 9bde37432..54c7b0c83 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -1507,11 +1507,14 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- FLOW --- */
if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
log_msg.msg_type = LOG_FLOW_MSG;
- log_msg.body.log_FLOW.flow_raw_x = buf.flow.flow_raw_x;
- log_msg.body.log_FLOW.flow_raw_y = buf.flow.flow_raw_y;
- log_msg.body.log_FLOW.flow_comp_x = buf.flow.flow_comp_x_m;
- log_msg.body.log_FLOW.flow_comp_y = buf.flow.flow_comp_y_m;
- log_msg.body.log_FLOW.distance = buf.flow.ground_distance_m;
+ log_msg.body.log_FLOW.ground_distance_m = buf.flow.ground_distance_m;
+ log_msg.body.log_FLOW.gyro_temperature = buf.flow.gyro_temperature;
+ log_msg.body.log_FLOW.gyro_x_rate_integral = buf.flow.gyro_x_rate_integral;
+ log_msg.body.log_FLOW.gyro_y_rate_integral = buf.flow.gyro_y_rate_integral;
+ log_msg.body.log_FLOW.gyro_z_rate_integral = buf.flow.gyro_z_rate_integral;
+ log_msg.body.log_FLOW.integration_timespan = buf.flow.integration_timespan;
+ log_msg.body.log_FLOW.pixel_flow_x_integral = buf.flow.pixel_flow_x_integral;
+ log_msg.body.log_FLOW.pixel_flow_y_integral = buf.flow.pixel_flow_y_integral;
log_msg.body.log_FLOW.quality = buf.flow.quality;
log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
LOGBUFFER_WRITE_AND_COUNT(FLOW);
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index d49fc0c79..5264ff1c8 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -200,13 +200,19 @@ struct log_ARSP_s {
/* --- FLOW - OPTICAL FLOW --- */
#define LOG_FLOW_MSG 15
struct log_FLOW_s {
- int16_t flow_raw_x;
- int16_t flow_raw_y;
- float flow_comp_x;
- float flow_comp_y;
- float distance;
- uint8_t quality;
+ uint64_t timestamp;
uint8_t sensor_id;
+ float pixel_flow_x_integral;
+ float pixel_flow_y_integral;
+ float gyro_x_rate_integral;
+ float gyro_y_rate_integral;
+ float gyro_z_rate_integral;
+ float ground_distance_m;
+ uint32_t integration_timespan;
+ uint32_t time_since_last_sonar_update;
+ uint16_t frame_count_since_last_readout;
+ int16_t gyro_temperature;
+ uint8_t quality;
};
/* --- GPOS - GLOBAL POSITION ESTIMATE --- */