AP_Devo_Telem: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
38abec2133
commit
9264a25955
@ -96,7 +96,7 @@ void AP_DEVO_Telem::send_frames()
|
|||||||
const AP_GPS &gps = AP::gps();
|
const AP_GPS &gps = AP::gps();
|
||||||
Location loc;
|
Location loc;
|
||||||
|
|
||||||
if (_ahrs.get_position(loc)) {
|
if (_ahrs.get_location(loc)) {
|
||||||
devoPacket.lat = gpsDdToDmsFormat(loc.lat);
|
devoPacket.lat = gpsDdToDmsFormat(loc.lat);
|
||||||
devoPacket.lon = gpsDdToDmsFormat(loc.lng);
|
devoPacket.lon = gpsDdToDmsFormat(loc.lng);
|
||||||
devoPacket.speed = (int16_t)(gps.ground_speed() * DEVO_SPEED_FACTOR * 100.0f); // * 100 for cm
|
devoPacket.speed = (int16_t)(gps.ground_speed() * DEVO_SPEED_FACTOR * 100.0f); // * 100 for cm
|
||||||
|
Loading…
Reference in New Issue
Block a user