Plane: Log height of zero instead of old value

This commit is contained in:
Tom Pittenger 2015-05-27 16:51:29 -07:00 committed by Andrew Tridgell
parent e24b6c6342
commit 4e167689b0

View File

@ -337,7 +337,7 @@ void Plane::Log_Write_Status()
struct PACKED log_Sonar { struct PACKED log_Sonar {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us; uint64_t time_us;
float distance; uint16_t distance;
float voltage; float voltage;
float baro_alt; float baro_alt;
float groundspeed; float groundspeed;
@ -350,10 +350,15 @@ struct PACKED log_Sonar {
void Plane::Log_Write_Sonar() void Plane::Log_Write_Sonar()
{ {
#if RANGEFINDER_ENABLED == ENABLED #if RANGEFINDER_ENABLED == ENABLED
uint16_t distance = 0;
if (rangefinder.status() == RangeFinder::RangeFinder_Good) {
distance = rangefinder.distance_cm();
}
struct log_Sonar pkt = { struct log_Sonar pkt = {
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG), LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
time_us : hal.scheduler->micros64(), time_us : hal.scheduler->micros64(),
distance : (float)rangefinder.distance_cm(), distance : distance,
voltage : rangefinder.voltage_mv()*0.001f, voltage : rangefinder.voltage_mv()*0.001f,
baro_alt : barometer.get_altitude(), baro_alt : barometer.get_altitude(),
groundspeed : gps.ground_speed(), groundspeed : gps.ground_speed(),
@ -478,7 +483,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning), { LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "QCfccccfI", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" }, "NTUN", "QCfccccfI", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" },
{ LOG_SONAR_MSG, sizeof(log_Sonar), { LOG_SONAR_MSG, sizeof(log_Sonar),
"SONR", "QffffBBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" }, "SONR", "QHfffBBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" },
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm), { LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
"ARM", "QBH", "TimeUS,ArmState,ArmChecks" }, "ARM", "QBH", "TimeUS,ArmState,ArmChecks" },
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP), { LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),