aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorJohan Jansen <jnsn.johan@gmail.com>2015-01-07 22:12:48 +0100
committerJohan Jansen <jnsn.johan@gmail.com>2015-01-15 14:37:51 +0100
commit784fa9f4699c434671edfd1e4fb48897bea54d8f (patch)
tree46d38c5760bcfe1a513fb3034f95c19404208ffa /src
parent2da6439f742f7743adca22ad3a887e936e6c2277 (diff)
downloadpx4-firmware-784fa9f4699c434671edfd1e4fb48897bea54d8f.tar.gz
px4-firmware-784fa9f4699c434671edfd1e4fb48897bea54d8f.tar.bz2
px4-firmware-784fa9f4699c434671edfd1e4fb48897bea54d8f.zip
sdlog2: Removed vehicle_land_detected topic from logging
Diffstat (limited to 'src')
-rw-r--r--src/modules/sdlog2/sdlog2.c10
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h9
2 files changed, 1 insertions, 18 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index b470eefac..7b7949239 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -72,7 +72,6 @@
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_command.h>
-#include <uORB/topics/vehicle_land_detected.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -982,7 +981,6 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_local_position_s local_pos;
struct vehicle_local_position_setpoint_s local_pos_sp;
struct vehicle_global_position_s global_pos;
- struct vehicle_land_detected_s land_detector;
struct position_setpoint_triplet_s triplet;
struct vehicle_vicon_position_s vicon_pos;
struct vision_position_estimate vision_pos;
@@ -1018,7 +1016,6 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_SENS_s log_SENS;
struct log_LPOS_s log_LPOS;
struct log_LPSP_s log_LPSP;
- struct log_LAND_s log_LAND;
struct log_GPS_s log_GPS;
struct log_ATTC_s log_ATTC;
struct log_STAT_s log_STAT;
@@ -1085,7 +1082,6 @@ int sdlog2_thread_main(int argc, char *argv[])
int servorail_status_sub;
int wind_sub;
int encoders_sub;
- int land_detector_sub;
} subs;
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
@@ -1116,7 +1112,6 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.system_power_sub = orb_subscribe(ORB_ID(system_power));
subs.servorail_status_sub = orb_subscribe(ORB_ID(servorail_status));
subs.wind_sub = orb_subscribe(ORB_ID(wind_estimate));
- subs.land_detector_sub = orb_subscribe(ORB_ID(vehicle_land_detected));
/* we need to rate-limit wind, as we do not need the full update rate */
orb_set_interval(subs.wind_sub, 90);
@@ -1526,11 +1521,6 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(LPOS);
}
- /* --- LAND DETECTED --- */
- if (copy_if_updated(ORB_ID(vehicle_land_detected), subs.land_detector_sub, &buf.land_detector)) {
- log_msg.body.log_LAND.landed = buf.land_detector.landed;
- }
-
/* --- LOCAL POSITION SETPOINT --- */
if (copy_if_updated(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp)) {
log_msg.msg_type = LOG_LPSP_MSG;
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 246f5129f..99f70a948 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -113,7 +113,6 @@ struct log_LPOS_s {
int32_t ref_lon;
float ref_alt;
uint8_t pos_flags;
- uint8_t landed;
uint8_t ground_dist_flags;
float eph;
float epv;
@@ -427,11 +426,6 @@ struct log_ENCD_s {
/* --- AIR SPEED SENSORS - DIFF. PRESSURE --- */
#define LOG_AIR1_MSG 40
-/* --- LAND - LAND DETECTOR --- */
-#define LOG_LAND_MSG 41
-struct log_LAND_s {
- uint8_t landed;
-};
/********** SYSTEM MESSAGES, ID > 0x80 **********/
@@ -468,7 +462,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT_S(IMU2, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
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, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
+ LOG_FORMAT(LPOS, "ffffffffLLfBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,GFlg,EPH,EPV"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
LOG_FORMAT(GPS, "QBffLLfffffBHHH", "GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog,nSat,SNR,N,J"),
LOG_FORMAT_S(ATTC, ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
@@ -501,7 +495,6 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(TECS, "fffffffffffffB", "ASP,AF,FSP,F,FF,AsSP,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"),
LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"),
LOG_FORMAT(ENCD, "qfqf", "cnt0,vel0,cnt1,vel1"),
- LOG_FORMAT(LAND, "B", "landed"),
/* system-level messages, ID >= 0x80 */
/* FMT: don't write format of format message, it's useless */