From cafed85872b38030e35b9f23681fd6f0f1ce832c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 19 Oct 2022 12:42:50 +1100 Subject: [PATCH] AP_Mission: fixed climb_rate in ATTITUDE_TIME need to stay within 10 byte limit --- libraries/AP_Mission/AP_Mission.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index da20f5f9b9..cb62bb1a1c 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -235,7 +235,7 @@ public: int16_t roll_deg; int8_t pitch_deg; int16_t yaw_deg; - float climb_rate; + int16_t climb_rate; }; // MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW support