mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
GCS_MAVLink: avoid using struct Location
clang reports this could be a problem when compiling under some EABIs. Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
parent
517e42c678
commit
c871aaefb7
@ -993,7 +993,7 @@ private:
|
||||
|
||||
// we cache the current location and send it even if the AHRS has
|
||||
// no idea where we are:
|
||||
struct Location global_position_current_loc;
|
||||
Location global_position_current_loc;
|
||||
|
||||
uint8_t last_tx_seq;
|
||||
uint16_t send_packet_count;
|
||||
|
@ -541,7 +541,7 @@ void GCS_MAVLINK::send_ahrs2()
|
||||
{
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
Vector3f euler;
|
||||
struct Location loc {};
|
||||
Location loc {};
|
||||
// we want one or both of these, use | to avoid short-circuiting:
|
||||
if (ahrs.get_secondary_attitude(euler) |
|
||||
ahrs.get_secondary_position(loc)) {
|
||||
|
Loading…
Reference in New Issue
Block a user