|
|
|
@ -335,7 +335,7 @@ void Plane::Log_Write_Status()
@@ -335,7 +335,7 @@ void Plane::Log_Write_Status()
|
|
|
|
|
struct PACKED log_Sonar { |
|
|
|
|
LOG_PACKET_HEADER; |
|
|
|
|
uint64_t time_us; |
|
|
|
|
uint16_t distance; |
|
|
|
|
float distance; |
|
|
|
|
float voltage; |
|
|
|
|
uint8_t count; |
|
|
|
|
float correction; |
|
|
|
@ -353,7 +353,7 @@ void Plane::Log_Write_Sonar()
@@ -353,7 +353,7 @@ void Plane::Log_Write_Sonar()
|
|
|
|
|
struct log_Sonar pkt = { |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG), |
|
|
|
|
time_us : AP_HAL::micros64(), |
|
|
|
|
distance : distance, |
|
|
|
|
distance : (float)distance*0.01f, |
|
|
|
|
voltage : rangefinder.voltage_mv()*0.001f, |
|
|
|
|
count : rangefinder_state.in_range_count, |
|
|
|
|
correction : rangefinder_state.correction |
|
|
|
@ -484,7 +484,7 @@ const struct LogStructure Plane::log_structure[] = {
@@ -484,7 +484,7 @@ const struct LogStructure Plane::log_structure[] = {
|
|
|
|
|
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
|
|
|
|
"NTUN", "Qfcccfff", "TimeUS,WpDist,TargBrg,NavBrg,AltErr,XT,XTi,ArspdErr" }, |
|
|
|
|
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
|
|
|
|
"SONR", "QHfBf", "TimeUS,DistCM,Volt,Cnt,Corr" }, |
|
|
|
|
"SONR", "QffBf", "TimeUS,Dist,Volt,Cnt,Corr" }, |
|
|
|
|
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm), |
|
|
|
|
"ARM", "QBH", "TimeUS,ArmState,ArmChecks" }, |
|
|
|
|
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP), |
|
|
|
|