mirror of https://github.com/ArduPilot/ardupilot
AP_L1_Control: 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
ffa43c1b71
commit
787dc5ccf1
|
@ -193,10 +193,10 @@ void AP_L1_Control::_prevent_indecision(float &Nu)
|
|||
}
|
||||
|
||||
// update L1 control for waypoint navigation
|
||||
void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min)
|
||||
void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &next_WP, float dist_min)
|
||||
{
|
||||
|
||||
struct Location _current_loc;
|
||||
Location _current_loc;
|
||||
float Nu;
|
||||
float xtrackVel;
|
||||
float ltrackVel;
|
||||
|
@ -332,9 +332,9 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
|||
}
|
||||
|
||||
// update L1 control for loitering
|
||||
void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius, int8_t loiter_direction)
|
||||
void AP_L1_Control::update_loiter(const Location ¢er_WP, float radius, int8_t loiter_direction)
|
||||
{
|
||||
struct Location _current_loc;
|
||||
Location _current_loc;
|
||||
|
||||
// scale loiter radius with square of EAS2TAS to allow us to stay
|
||||
// stable at high altitude
|
||||
|
|
|
@ -50,8 +50,8 @@ public:
|
|||
float turn_distance(float wp_radius) const override;
|
||||
float turn_distance(float wp_radius, float turn_angle) const override;
|
||||
float loiter_radius (const float loiter_radius) const override;
|
||||
void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min = 0.0f) override;
|
||||
void update_loiter(const struct Location ¢er_WP, float radius, int8_t loiter_direction) override;
|
||||
void update_waypoint(const class Location &prev_WP, const class Location &next_WP, float dist_min = 0.0f) override;
|
||||
void update_loiter(const class Location ¢er_WP, float radius, int8_t loiter_direction) override;
|
||||
void update_heading_hold(int32_t navigation_heading_cd) override;
|
||||
void update_level_flight(void) override;
|
||||
bool reached_loiter_target(void) override;
|
||||
|
|
Loading…
Reference in New Issue