diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index dcf06e7188..b612db1171 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -97,6 +97,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #if GRIPPER_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75), #endif +#if OSD_ENABLED == ENABLED + SCHED_TASK(publish_osd_info, 1, 10), +#endif }; constexpr int8_t Plane::_failsafe_priorities[5]; @@ -952,4 +955,16 @@ float Plane::tecs_hgt_afe(void) return hgt_afe; } +#if OSD_ENABLED == ENABLED +void Plane::publish_osd_info() +{ + AP_OSD::NavInfo nav_info; + nav_info.wp_distance = auto_state.wp_distance; + nav_info.wp_bearing = nav_controller->target_bearing_cd(); + nav_info.wp_xtrack_error = nav_controller->crosstrack_error(); + nav_info.wp_number = mission.get_current_nav_index(); + osd.set_nav_info(nav_info); +} +#endif + AP_HAL_MAIN_CALLBACKS(&plane); diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 8bbdff3400..9b8530c85f 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1026,6 +1026,9 @@ private: void do_parachute(const AP_Mission::Mission_Command& cmd); void parachute_release(); bool parachute_manual_release(); +#endif +#if OSD_ENABLED == ENABLED + void publish_osd_info(); #endif void accel_cal_update(void); void update_soft_armed();