Copter: remove unused ModeAuto::wp_start
this version accepts an offset from the ekf origin which is not required. All callers provide a Location
This commit is contained in:
parent
01b5337d91
commit
495c4ad6b6
@ -351,7 +351,6 @@ public:
|
||||
bool loiter_start();
|
||||
void rtl_start();
|
||||
void takeoff_start(const Location& dest_loc);
|
||||
void wp_start(const Vector3f& destination, bool terrain_alt);
|
||||
void wp_start(const Location& dest_loc);
|
||||
void land_start();
|
||||
void land_start(const Vector3f& destination);
|
||||
|
@ -188,21 +188,6 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
|
||||
auto_takeoff_set_start_alt();
|
||||
}
|
||||
|
||||
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
|
||||
void ModeAuto::wp_start(const Vector3f& destination, bool terrain_alt)
|
||||
{
|
||||
_mode = Auto_WP;
|
||||
|
||||
// initialise wpnav (no need to check return status because terrain data is not used)
|
||||
wp_nav->set_wp_destination(destination, terrain_alt);
|
||||
|
||||
// initialise yaw
|
||||
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
|
||||
if (auto_yaw.mode() != AUTO_YAW_ROI) {
|
||||
auto_yaw.set_mode_to_default(false);
|
||||
}
|
||||
}
|
||||
|
||||
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
|
||||
void ModeAuto::wp_start(const Location& dest_loc)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user