AP_Vehicle: use new pitch_trim in degrees in AP_FixedWing

This commit is contained in:
Tim Tuxworth 2023-12-14 11:47:40 -07:00 committed by Andrew Tridgell
parent b1c8511386
commit d749efb40d
2 changed files with 1 additions and 2 deletions

View File

@ -23,7 +23,6 @@ struct AP_FixedWing {
AP_Int32 autotune_options;
AP_Int8 stall_prevention;
AP_Int16 loiter_radius;
AP_Int16 pitch_trim_cd;
AP_Float takeoff_throttle_max_t;
struct Rangefinder_State {

View File

@ -268,7 +268,7 @@ public:
*/
virtual bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const { return false; }
// Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH_CD
// Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH
virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const;
/*