mirror of https://github.com/ArduPilot/ardupilot
AP_Beacon: adjust for Location_Class and Location unification
This commit is contained in:
parent
7406c5be37
commit
0b661e7872
|
@ -19,6 +19,8 @@
|
|||
#include "AP_Beacon_Marvelmind.h"
|
||||
#include "AP_Beacon_SITL.h"
|
||||
|
||||
#include <AP_Common/Location.h>
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
// table of user settable parameters
|
||||
|
@ -137,7 +139,7 @@ bool AP_Beacon::get_origin(Location &origin_loc) const
|
|||
}
|
||||
|
||||
// return origin
|
||||
memset(&origin_loc, 0, sizeof(origin_loc));
|
||||
origin_loc = {};
|
||||
origin_loc.lat = origin_lat * 1.0e7;
|
||||
origin_loc.lng = origin_lon * 1.0e7;
|
||||
origin_loc.alt = origin_alt * 100;
|
||||
|
|
Loading…
Reference in New Issue