Browse Source

ArduPlane: Correct OSD horizon for VTOL modes and TRIM_PITCH_CD in Fixed Wing

gps-1.3.1
Hwurzburg 4 years ago committed by Andrew Tridgell
parent
commit
1e4a6c9236
  1. 15
      ArduPlane/ArduPlane.cpp
  2. 3
      ArduPlane/Plane.h

15
ArduPlane/ArduPlane.cpp

@ -689,4 +689,19 @@ bool Plane::get_target_location(Location& target_loc) @@ -689,4 +689,19 @@ bool Plane::get_target_location(Location& target_loc)
}
#endif // ENABLE_SCRIPTING
#if OSD_ENABLED
// correct AHRS pitch for TRIM_PITCH_CD in non-VTOL modes, and return VTOL view in VTOL
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
{
pitch = ahrs.pitch;
roll = ahrs.roll;
if (!quadplane.show_vtol_view()) { // correct for TRIM_PITCH_CD
pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD;
} else {
pitch = quadplane.ahrs_view->pitch;
roll = quadplane.ahrs_view->roll;
}
}
#endif
AP_HAL_MAIN_CALLBACKS(&plane);

3
ArduPlane/Plane.h

@ -950,6 +950,9 @@ private: @@ -950,6 +950,9 @@ private:
// ArduPlane.cpp
void disarm_if_autoland_complete();
# if OSD_ENABLED
void get_osd_roll_pitch_rad(float &roll, float &pitch) const override;
#endif
float tecs_hgt_afe(void);
void efi_update(void);
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,

Loading…
Cancel
Save