Copter: publish navigation info to OSD

This commit is contained in:
Alexander Malishev 2018-07-26 03:47:06 +04:00 committed by Andrew Tridgell
parent eec34fc47d
commit f5c540a127
2 changed files with 19 additions and 0 deletions

View File

@ -190,6 +190,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if STATS_ENABLED == ENABLED
SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100),
#endif
#if OSD_ENABLED == ENABLED
SCHED_TASK(publish_osd_info, 1, 10),
#endif
};
void Copter::read_aux_all()
@ -580,4 +583,16 @@ void Copter::update_altitude()
}
}
#if OSD_ENABLED == ENABLED
void Copter::publish_osd_info()
{
AP_OSD::NavInfo nav_info;
nav_info.wp_distance = flightmode->wp_distance();
nav_info.wp_bearing = flightmode->wp_bearing();
nav_info.wp_xtrack_error = flightmode->crosstrack_error();
nav_info.wp_number = mission.get_current_nav_index();
osd.set_nav_info(nav_info);
}
#endif
AP_HAL_MAIN_CALLBACKS(&copter);

View File

@ -919,6 +919,10 @@ private:
void userhook_auxSwitch2(uint8_t ch_flag);
void userhook_auxSwitch3(uint8_t ch_flag);
#if OSD_ENABLED == ENABLED
void publish_osd_info();
#endif
#include "mode.h"
Mode *flightmode;