mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: move get_bearing_cd to Location and rename to get_bearing_to
This commit is contained in:
parent
92be1780ac
commit
492c7532eb
|
@ -29,6 +29,7 @@
|
|||
#include <AP_RSSI/AP_RSSI.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_Stats/AP_Stats.h>
|
||||
#include <AP_Common/Location.h>
|
||||
|
||||
#include <ctype.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
@ -630,7 +631,7 @@ void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
|
|||
if (ahrs.get_position(loc) && ahrs.home_is_set()) {
|
||||
const Location &home_loc = ahrs.get_home();
|
||||
float distance = home_loc.get_distance(loc);
|
||||
int32_t angle = wrap_360_cd(get_bearing_cd(loc, home_loc) - ahrs.yaw_sensor);
|
||||
int32_t angle = wrap_360_cd(loc.get_bearing_to(home_loc) - ahrs.yaw_sensor);
|
||||
int32_t interval = 36000 / SYM_ARROW_COUNT;
|
||||
if (distance < 2.0f) {
|
||||
//avoid fast rotating arrow at small distances
|
||||
|
|
Loading…
Reference in New Issue