aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:36:25 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:36:25 +0200
commita1cf8801bb000e38d11b4573d7cde452f02abbc3 (patch)
tree283e319d78bec0209cf602311370a7888ee264b0 /src/modules
parent302233a34f23a57b67d4ebb8ba3e553ad9d8c445 (diff)
downloadpx4-firmware-a1cf8801bb000e38d11b4573d7cde452f02abbc3.tar.gz
px4-firmware-a1cf8801bb000e38d11b4573d7cde452f02abbc3.tar.bz2
px4-firmware-a1cf8801bb000e38d11b4573d7cde452f02abbc3.zip
sdlog2: add failsafe state logging
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/sdlog2/sdlog2.c1
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h3
2 files changed, 3 insertions, 1 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index e026753dc..1ca8cf8c5 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -960,6 +960,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.msg_type = LOG_STAT_MSG;
log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
+ log_msg.body.log_STAT.failsafe_state = (uint8_t) buf_status.failsafe_state;
log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 9a02fa2a6..753438d7b 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -154,6 +154,7 @@ struct log_ATTC_s {
struct log_STAT_s {
uint8_t main_state;
uint8_t arming_state;
+ uint8_t failsafe_state;
float battery_remaining;
uint8_t battery_warning;
uint8_t landed;
@@ -350,7 +351,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
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, "BBfBB", "MainState,ArmState,BatRem,BatWarn,Landed"),
+ LOG_FORMAT(STAT, "BBBfBB", "MainState,ArmState,FailsafeState,BatRem,BatWarn,Landed"),
LOG_FORMAT(RC, "ffffffffB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),