aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-08-25 23:48:26 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-08-25 23:48:26 +0200
commit19fa79dcb1b3b34176341b3edb7187b6bb117aff (patch)
tree7737dc6a9866ddc679e3f9dcf07ba8bcf5bcfec7 /src/modules
parent21e3ca6c999fa85a2f4c394ab2141971fd8edc76 (diff)
parentd6810ae1f8e2b8c86d54acfe80094265e97a3232 (diff)
downloadpx4-firmware-19fa79dcb1b3b34176341b3edb7187b6bb117aff.tar.gz
px4-firmware-19fa79dcb1b3b34176341b3edb7187b6bb117aff.tar.bz2
px4-firmware-19fa79dcb1b3b34176341b3edb7187b6bb117aff.zip
Merge pull request #1317 from TSC21/sdlog2_vision
Sdlog2: add vision estimation logging
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/sdlog2/sdlog2.c21
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h15
2 files changed, 36 insertions, 0 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 6c4b49452..dbda8ea6f 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -76,6 +76,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>
#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/battery_status.h>
@@ -934,6 +935,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_global_position_s global_pos;
struct position_setpoint_triplet_s triplet;
struct vehicle_vicon_position_s vicon_pos;
+ struct vision_position_estimate vision_pos;
struct optical_flow_s flow;
struct rc_channels_s rc;
struct differential_pressure_s diff_pres;
@@ -984,6 +986,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_EST1_s log_EST1;
struct log_PWR_s log_PWR;
struct log_VICN_s log_VICN;
+ struct log_VISN_s log_VISN;
struct log_GS0A_s log_GS0A;
struct log_GS0B_s log_GS0B;
struct log_GS1A_s log_GS1A;
@@ -1013,6 +1016,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int gps_pos_sub;
int sat_info_sub;
int vicon_pos_sub;
+ int vision_pos_sub;
int flow_sub;
int rc_sub;
int airspeed_sub;
@@ -1043,6 +1047,7 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
subs.triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
+ subs.vision_pos_sub = orb_subscribe(ORB_ID(vision_position_estimate));
subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
subs.rc_sub = orb_subscribe(ORB_ID(rc_channels));
subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
@@ -1459,6 +1464,22 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_VICN.yaw = buf.vicon_pos.yaw;
LOGBUFFER_WRITE_AND_COUNT(VICN);
}
+
+ /* --- VISION POSITION --- */
+ if (copy_if_updated(ORB_ID(vision_position_estimate), subs.vision_pos_sub, &buf.vision_pos)) {
+ log_msg.msg_type = LOG_VISN_MSG;
+ log_msg.body.log_VISN.x = buf.vision_pos.x;
+ log_msg.body.log_VISN.y = buf.vision_pos.y;
+ log_msg.body.log_VISN.z = buf.vision_pos.z;
+ log_msg.body.log_VISN.vx = buf.vision_pos.vx;
+ log_msg.body.log_VISN.vy = buf.vision_pos.vy;
+ log_msg.body.log_VISN.vz = buf.vision_pos.vz;
+ log_msg.body.log_VISN.qx = buf.vision_pos.q[0];
+ log_msg.body.log_VISN.qy = buf.vision_pos.q[1];
+ log_msg.body.log_VISN.qz = buf.vision_pos.q[2];
+ log_msg.body.log_VISN.qw = buf.vision_pos.q[3];
+ LOGBUFFER_WRITE_AND_COUNT(VISN);
+ }
/* --- FLOW --- */
if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index fb7609435..6741c7e25 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -391,6 +391,20 @@ struct log_TEL_s {
uint64_t heartbeat_time;
};
+/* --- VISN - VISION POSITION --- */
+#define LOG_VISN_MSG 38
+struct log_VISN_s {
+ float x;
+ float y;
+ float z;
+ float vx;
+ float vy;
+ float vz;
+ float qx;
+ float qy;
+ float qz;
+ float qw;
+};
/********** SYSTEM MESSAGES, ID > 0x80 **********/
@@ -449,6 +463,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(EST1, "ffffffffffffffff", "s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27"),
LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
LOG_FORMAT(VICN, "ffffff", "X,Y,Z,Roll,Pitch,Yaw"),
+ LOG_FORMAT(VISN, "ffffffffff", "X,Y,Z,VX,VY,VZ,QuatX,QuatY,QuatZ,QuatW"),
LOG_FORMAT(GS0A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),