mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: log signal quality
This commit is contained in:
parent
88dd8130f6
commit
fd4da61067
|
@ -467,6 +467,7 @@ struct PACKED log_RFND {
|
|||
uint16_t dist;
|
||||
uint8_t status;
|
||||
uint8_t orient;
|
||||
int8_t quality;
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -1046,6 +1047,7 @@ struct PACKED log_VER {
|
|||
// @Field: Stat: Sensor state
|
||||
// @FieldValueEnum: Stat: RangeFinder::Status
|
||||
// @Field: Orient: Sensor orientation
|
||||
// @Field: Quality: Signal quality. -1 means invalid, 0 is no signal, 100 is perfect signal
|
||||
|
||||
// @LoggerMessage: RSSI
|
||||
// @Description: Received Signal Strength Indicator for RC receiver
|
||||
|
@ -1239,7 +1241,7 @@ LOG_STRUCTURE_FROM_MOUNT \
|
|||
{ LOG_MODE_MSG, sizeof(log_Mode), \
|
||||
"MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn", "s---", "F---" }, \
|
||||
{ LOG_RFND_MSG, sizeof(log_RFND), \
|
||||
"RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--", true }, \
|
||||
"RFND", "QBCBBb", "TimeUS,Instance,Dist,Stat,Orient,Quality", "s#m--%", "F-B---", true }, \
|
||||
{ LOG_MAV_STATS, sizeof(log_MAV_Stats), \
|
||||
"DMS", "QIIIIBBBBBBBBB", "TimeUS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "F-------------" }, \
|
||||
LOG_STRUCTURE_FROM_BEACON \
|
||||
|
|
|
@ -768,6 +768,10 @@ void RangeFinder::Log_RFND() const
|
|||
continue;
|
||||
}
|
||||
|
||||
int8_t signal_quality;
|
||||
if (!s->get_signal_quality_pct(signal_quality)) {
|
||||
signal_quality = -1;
|
||||
}
|
||||
const struct log_RFND pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_RFND_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
|
@ -775,6 +779,7 @@ void RangeFinder::Log_RFND() const
|
|||
dist : s->distance_cm(),
|
||||
status : (uint8_t)s->status(),
|
||||
orient : s->orientation(),
|
||||
quality : signal_quality,
|
||||
};
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue