mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: remove unused location argument to control_auto
This commit is contained in:
parent
d2861f7db9
commit
286963ad16
@ -57,7 +57,7 @@ void ModeAuto::update()
|
||||
uint16_t nav_cmd_id = plane.mission.get_current_nav_cmd().id;
|
||||
|
||||
if (plane.quadplane.in_vtol_auto()) {
|
||||
plane.quadplane.control_auto(plane.next_WP_loc);
|
||||
plane.quadplane.control_auto();
|
||||
} else if (nav_cmd_id == MAV_CMD_NAV_TAKEOFF ||
|
||||
(nav_cmd_id == MAV_CMD_NAV_LAND && plane.flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)) {
|
||||
plane.takeoff_calc_roll();
|
||||
|
@ -2422,7 +2422,7 @@ void QuadPlane::waypoint_controller(void)
|
||||
/*
|
||||
handle auto-mode when auto_state.vtol_mode is true
|
||||
*/
|
||||
void QuadPlane::control_auto(const Location &loc)
|
||||
void QuadPlane::control_auto(void)
|
||||
{
|
||||
if (!setup()) {
|
||||
return;
|
||||
|
@ -44,7 +44,7 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info2[];
|
||||
|
||||
void control_run(void);
|
||||
void control_auto(const Location &loc);
|
||||
void control_auto(void);
|
||||
bool init_mode(void);
|
||||
bool setup(void);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user