Browse Source

ArduPlane: Log isFlying status

Log is_flying() status and its float probability in new STAT msg
and piggyback on MODE bitmask flag.
master
Tom Pittenger 10 years ago committed by Andrew Tridgell
parent
commit
f5dfe7c650
  1. 4
      ArduPlane/ArduPlane.pde
  2. 22
      ArduPlane/Log.pde
  3. 3
      ArduPlane/defines.h

4
ArduPlane/ArduPlane.pde

@ -1041,6 +1041,10 @@ static void one_second_loop()
terrain.log_terrain_data(DataFlash); terrain.log_terrain_data(DataFlash);
} }
#endif #endif
// piggyback the status log entry on the MODE log entry flag
if (should_log(MASK_LOG_MODE)) {
Log_Write_Status();
}
} }
static void log_perf_info() static void log_perf_info()

22
ArduPlane/Log.pde

@ -320,6 +320,25 @@ static void Log_Write_Nav_Tuning()
DataFlash.WriteBlock(&pkt, sizeof(pkt)); DataFlash.WriteBlock(&pkt, sizeof(pkt));
} }
struct PACKED log_Status {
LOG_PACKET_HEADER;
uint32_t timestamp;
uint8_t is_flying;
float is_flying_probability;
};
static void Log_Write_Status()
{
struct log_Status pkt = {
LOG_PACKET_HEADER_INIT(LOG_STATUS_MSG)
,timestamp : hal.scheduler->millis()
,is_flying : is_flying()
,is_flying_probability : isFlyingProbability
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
struct PACKED log_Sonar { struct PACKED log_Sonar {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t timestamp; uint32_t timestamp;
@ -450,6 +469,8 @@ static const struct LogStructure log_structure[] PROGMEM = {
"ARM", "IHB", "TimeMS,ArmState,ArmChecks" }, "ARM", "IHB", "TimeMS,ArmState,ArmChecks" },
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP), { LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
"ATRP", "IBBcfff", "TimeMS,Type,State,Servo,Demanded,Achieved,P" }, "ATRP", "IBBcfff", "TimeMS,Type,State,Servo,Demanded,Achieved,P" },
{ LOG_STATUS_MSG, sizeof(log_Status),
"STAT", "IBf", "TimeMS,isFlying,isFlyProb" },
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), { LOG_OPTFLOW_MSG, sizeof(log_Optflow),
"OF", "IBffff", "TimeMS,Qual,flowX,flowY,bodyX,bodyY" }, "OF", "IBffff", "TimeMS,Qual,flowX,flowY,bodyX,bodyY" },
@ -505,6 +526,7 @@ static void Log_Write_IMU() {}
static void Log_Write_RC() {} static void Log_Write_RC() {}
static void Log_Write_Airspeed(void) {} static void Log_Write_Airspeed(void) {}
static void Log_Write_Baro(void) {} static void Log_Write_Baro(void) {}
static void Log_Write_Status() {}
static void Log_Write_Sonar() {} static void Log_Write_Sonar() {}
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
static void Log_Write_Optflow() {} static void Log_Write_Optflow() {}

3
ArduPlane/defines.h

@ -121,7 +121,8 @@ enum log_messages {
LOG_COMPASS2_MSG_DEPRECATED, LOG_COMPASS2_MSG_DEPRECATED,
LOG_ARM_DISARM_MSG, LOG_ARM_DISARM_MSG,
LOG_AIRSPEED_MSG_DEPRECATED, // deprecated LOG_AIRSPEED_MSG_DEPRECATED, // deprecated
LOG_COMPASS3_MSG_DEPRECATED LOG_COMPASS3_MSG_DEPRECATED,
LOG_STATUS_MSG
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
,LOG_OPTFLOW_MSG ,LOG_OPTFLOW_MSG
#endif #endif

Loading…
Cancel
Save