ArduPlane: 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
1f13fd35e3
commit
f0e17957f4
@ -1383,7 +1383,7 @@ uint64_t GCS_MAVLINK_Plane::capabilities() const
|
||||
int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const
|
||||
{
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
struct Location global_position_current;
|
||||
Location global_position_current;
|
||||
UNUSED_RESULT(ahrs.get_location(global_position_current));
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
|
@ -705,13 +705,13 @@ private:
|
||||
|
||||
// 3D Location vectors
|
||||
// Location structure defined in AP_Common
|
||||
const struct Location &home = ahrs.get_home();
|
||||
const Location &home = ahrs.get_home();
|
||||
|
||||
// The location of the previous waypoint. Used for track following and altitude ramp calculations
|
||||
Location prev_WP_loc {};
|
||||
|
||||
// The plane's current location
|
||||
struct Location current_loc {};
|
||||
Location current_loc {};
|
||||
|
||||
// The location of the current/active waypoint. Used for altitude ramp, track following and loiter calculations.
|
||||
Location next_WP_loc {};
|
||||
@ -889,7 +889,7 @@ private:
|
||||
void load_parameters(void) override;
|
||||
|
||||
// commands_logic.cpp
|
||||
void set_next_WP(const struct Location &loc);
|
||||
void set_next_WP(const Location &loc);
|
||||
void do_RTL(int32_t alt);
|
||||
bool verify_takeoff();
|
||||
bool verify_loiter_unlim(const AP_Mission::Mission_Command &cmd);
|
||||
|
@ -7,7 +7,7 @@
|
||||
/*
|
||||
* set_next_WP - sets the target location the vehicle should fly to
|
||||
*/
|
||||
void Plane::set_next_WP(const struct Location &loc)
|
||||
void Plane::set_next_WP(const Location &loc)
|
||||
{
|
||||
if (auto_state.next_wp_crosstrack) {
|
||||
// copy the current WP into the OldWP slot
|
||||
|
Loading…
Reference in New Issue
Block a user