AP_Vehicle: correct OSD horizon for VTOL modes and TRIM_PITCH_CD in FW modes

This commit is contained in:
Hwurzburg 2021-07-28 18:29:37 -05:00 committed by Andrew Tridgell
parent b2a100f41b
commit b69308858a
2 changed files with 12 additions and 0 deletions

View File

@ -403,6 +403,13 @@ void AP_Vehicle::publish_osd_info()
nav_info.wp_number = mission->get_current_nav_index();
osd->set_nav_info(nav_info);
}
void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const
{
roll = ahrs.roll;
pitch = ahrs.pitch;
}
#endif
AP_Vehicle *AP_Vehicle::_singleton = nullptr;

View File

@ -252,6 +252,11 @@ public:
*/
virtual bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const { return false; }
#if OSD_ENABLED
// Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH_CD
virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const;
#endif
protected:
virtual void init_ardupilot() = 0;