mirror of https://github.com/ArduPilot/ardupilot
Copter: auto's wp_start accepts terrain alts
This commit is contained in:
parent
ee079a50dc
commit
b7a748df88
|
@ -313,7 +313,7 @@ public:
|
|||
bool loiter_start();
|
||||
void rtl_start();
|
||||
void takeoff_start(const Location& dest_loc);
|
||||
void wp_start(const Vector3f& destination);
|
||||
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);
|
||||
|
|
|
@ -189,12 +189,12 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
|
|||
}
|
||||
|
||||
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
|
||||
void ModeAuto::wp_start(const Vector3f& 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, false);
|
||||
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
|
||||
|
@ -741,7 +741,7 @@ void ModeAuto::takeoff_run()
|
|||
auto_takeoff_run();
|
||||
if (wp_nav->reached_wp_destination()) {
|
||||
const Vector3f target = wp_nav->get_wp_destination();
|
||||
wp_start(target);
|
||||
wp_start(target, wp_nav->origin_and_destination_are_terrain_alt());
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue