mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
54cf46b8e9
commit
21caa8c686
@ -2765,7 +2765,7 @@ void GCS_MAVLINK::send_vfr_hud()
|
|||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
// return values ignored; we send stale data
|
// return values ignored; we send stale data
|
||||||
UNUSED_RESULT(ahrs.get_position(global_position_current_loc));
|
UNUSED_RESULT(ahrs.get_location(global_position_current_loc));
|
||||||
|
|
||||||
mavlink_msg_vfr_hud_send(
|
mavlink_msg_vfr_hud_send(
|
||||||
chan,
|
chan,
|
||||||
@ -4900,7 +4900,7 @@ void GCS_MAVLINK::send_global_position_int()
|
|||||||
{
|
{
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
UNUSED_RESULT(ahrs.get_position(global_position_current_loc)); // return value ignored; we send stale data
|
UNUSED_RESULT(ahrs.get_location(global_position_current_loc)); // return value ignored; we send stale data
|
||||||
|
|
||||||
Vector3f vel;
|
Vector3f vel;
|
||||||
if (!ahrs.get_velocity_NED(vel)) {
|
if (!ahrs.get_velocity_NED(vel)) {
|
||||||
@ -4997,7 +4997,7 @@ void GCS_MAVLINK::send_water_depth() const
|
|||||||
// get position
|
// get position
|
||||||
const AP_AHRS &ahrs = AP::ahrs();
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
Location loc;
|
Location loc;
|
||||||
IGNORE_RETURN(ahrs.get_position(loc));
|
IGNORE_RETURN(ahrs.get_location(loc));
|
||||||
|
|
||||||
for (uint8_t i=0; i<rangefinder->num_sensors(); i++) {
|
for (uint8_t i=0; i<rangefinder->num_sensors(); i++) {
|
||||||
const AP_RangeFinder_Backend *s = rangefinder->get_backend(i);
|
const AP_RangeFinder_Backend *s = rangefinder->get_backend(i);
|
||||||
@ -5917,7 +5917,7 @@ void GCS_MAVLINK::send_high_latency2() const
|
|||||||
{
|
{
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
Location global_position_current;
|
Location global_position_current;
|
||||||
UNUSED_RESULT(ahrs.get_position(global_position_current));
|
UNUSED_RESULT(ahrs.get_location(global_position_current));
|
||||||
#if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY)
|
#if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY)
|
||||||
const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE);
|
const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE);
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user