mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Mission: fixed climb_rate in ATTITUDE_TIME
need to stay within 10 byte limit
This commit is contained in:
parent
2b69124229
commit
cafed85872
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user