From 826a613deb527a8d14e5881f665b46ee22ec69dc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 24 Dec 2024 08:24:26 +1100 Subject: [PATCH] Sub: log desired rangefinder alt (DSAlt) in metres not cm --- ArduSub/Log.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index ebea3c3569e5c6..18e08c577dc3e5 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -15,7 +15,7 @@ struct PACKED log_Control_Tuning { float desired_alt; float inav_alt; float baro_alt; - int16_t desired_rangefinder_alt; + float desired_rangefinder_alt; float rangefinder_alt; float terr_alt; int16_t target_climb_rate; @@ -47,7 +47,7 @@ void Sub::Log_Write_Control_Tuning() desired_alt : pos_control.get_pos_target_z_cm() / 100.0f, inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f, baro_alt : barometer.get_altitude(), - desired_rangefinder_alt : (int16_t)mode_surftrak.get_rangefinder_target_cm(), + desired_rangefinder_alt : mode_surftrak.get_rangefinder_target_cm() * 0.01, rangefinder_alt : rangefinder_state.alt, terr_alt : terr_alt, target_climb_rate : (int16_t)pos_control.get_vel_target_z_cms(), @@ -264,7 +264,7 @@ void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target const struct LogStructure Sub::log_structure[] = { LOG_COMMON_STRUCTURES, { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), - "CTUN", "Qffffffffcfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BB0BBB" }, + "CTUN", "Qffffffffffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B00BBB" }, { LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t), "D16", "QBh", "TimeUS,Id,Value", "s--", "F--" }, { LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),