aboutsummaryrefslogtreecommitdiff
path: root/src/modules/sdlog2
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-06-16 12:59:50 +0200
committerJulian Oes <julian@oes.ch>2013-06-16 12:59:50 +0200
commitb52d561b11298abb2982b786676f49eea96259d8 (patch)
treee9bbf4abba99871b291ca1a2f8f90f1ca750564e /src/modules/sdlog2
parent562253c508d1a758207d21e116cbbc194d7e0721 (diff)
downloadpx4-firmware-b52d561b11298abb2982b786676f49eea96259d8.tar.gz
px4-firmware-b52d561b11298abb2982b786676f49eea96259d8.tar.bz2
px4-firmware-b52d561b11298abb2982b786676f49eea96259d8.zip
Added ctrl debugging values
Diffstat (limited to 'src/modules/sdlog2')
-rw-r--r--src/modules/sdlog2/sdlog2.c36
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h33
2 files changed, 66 insertions, 3 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 940f30a46..844e02268 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -74,6 +74,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vehicle_control_debug.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/differential_pressure.h>
@@ -613,7 +614,7 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
/* number of messages */
- const ssize_t fdsc = 16;
+ const ssize_t fdsc = 17;
/* Sanity check variable and index */
ssize_t fdsc_count = 0;
/* file descriptors to wait for */
@@ -639,6 +640,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_global_position_s global_pos;
struct vehicle_gps_position_s gps_pos;
struct vehicle_vicon_position_s vicon_pos;
+ struct vehicle_control_debug_s control_debug;
struct optical_flow_s flow;
struct rc_channels_s rc;
struct differential_pressure_s diff_pres;
@@ -661,6 +663,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int global_pos_sub;
int gps_pos_sub;
int vicon_pos_sub;
+ int control_debug_sub;
int flow_sub;
int rc_sub;
} subs;
@@ -680,6 +683,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_GPS_s log_GPS;
struct log_ATTC_s log_ATTC;
struct log_STAT_s log_STAT;
+ struct log_CTRL_s log_CTRL;
struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0;
} body;
@@ -773,6 +777,12 @@ int sdlog2_thread_main(int argc, char *argv[])
fds[fdsc_count].events = POLLIN;
fdsc_count++;
+ /* --- CONTROL DEBUG --- */
+ subs.control_debug_sub = orb_subscribe(ORB_ID(vehicle_control_debug));
+ fds[fdsc_count].fd = subs.control_debug_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
/* --- OPTICAL FLOW --- */
subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
fds[fdsc_count].fd = subs.flow_sub;
@@ -1058,6 +1068,30 @@ int sdlog2_thread_main(int argc, char *argv[])
// TODO not implemented yet
}
+ /* --- CONTROL DEBUG --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_control_debug), subs.control_debug_sub, &buf.control_debug);
+
+ log_msg.body.log_CTRL.roll_p = buf.control_debug.roll_p;
+ log_msg.body.log_CTRL.roll_i = buf.control_debug.roll_i;
+ log_msg.body.log_CTRL.roll_d = buf.control_debug.roll_d;
+ log_msg.body.log_CTRL.roll_rate_p = buf.control_debug.roll_rate_p;
+ log_msg.body.log_CTRL.roll_rate_i = buf.control_debug.roll_rate_i;
+ log_msg.body.log_CTRL.roll_rate_d = buf.control_debug.roll_rate_d;
+ log_msg.body.log_CTRL.pitch_p = buf.control_debug.pitch_p;
+ log_msg.body.log_CTRL.pitch_i = buf.control_debug.pitch_i;
+ log_msg.body.log_CTRL.pitch_d = buf.control_debug.pitch_d;
+ log_msg.body.log_CTRL.pitch_rate_p = buf.control_debug.pitch_rate_p;
+ log_msg.body.log_CTRL.pitch_rate_i = buf.control_debug.pitch_rate_i;
+ log_msg.body.log_CTRL.pitch_rate_d = buf.control_debug.pitch_rate_d;
+ log_msg.body.log_CTRL.yaw_p = buf.control_debug.yaw_p;
+ log_msg.body.log_CTRL.yaw_i = buf.control_debug.yaw_i;
+ log_msg.body.log_CTRL.yaw_d = buf.control_debug.yaw_d;
+ log_msg.body.log_CTRL.yaw_rate_p = buf.control_debug.yaw_rate_p;
+ log_msg.body.log_CTRL.yaw_rate_i = buf.control_debug.yaw_rate_i;
+ log_msg.body.log_CTRL.yaw_rate_d = buf.control_debug.yaw_rate_d;
+ }
+
/* --- FLOW --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(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 40763ee1e..a80af33ef 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -156,14 +156,42 @@ struct log_STAT_s {
unsigned char battery_warning;
};
+/* --- CTRL - CONTROL DEBUG --- */
+#define LOG_CTRL_MSG 11
+struct log_CTRL_s {
+ float roll_p;
+ float roll_i;
+ float roll_d;
+
+ float roll_rate_p;
+ float roll_rate_i;
+ float roll_rate_d;
+
+ float pitch_p;
+ float pitch_i;
+ float pitch_d;
+
+ float pitch_rate_p;
+ float pitch_rate_i;
+ float pitch_rate_d;
+
+ float yaw_p;
+ float yaw_i;
+ float yaw_d;
+
+ float yaw_rate_p;
+ float yaw_rate_i;
+ float yaw_rate_d;
+};
+
/* --- RC - RC INPUT CHANNELS --- */
-#define LOG_RC_MSG 11
+#define LOG_RC_MSG 12
struct log_RC_s {
float channel[8];
};
/* --- OUT0 - ACTUATOR_0 OUTPUT --- */
-#define LOG_OUT0_MSG 12
+#define LOG_OUT0_MSG 13
struct log_OUT0_s {
float output[8];
};
@@ -182,6 +210,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"),
+ LOG_FORMAT(CTRL, "ffffffffffffffffff", "RollP,RollI,RollD,RollRateP,RollRateI,RollRateD,PitchP,PitchI,PitchD,PitchRateP,PitchRateI,PitchRateD,YawP,YawI,YawD,YawRateP,YawRateI,YawRateD"),
LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
};