Copter: fix guided takeoff altitude
This commit is contained in:
parent
920ac12214
commit
301d4cc4a6
@ -39,13 +39,13 @@ static bool guided_init(bool ignore_checks)
|
||||
|
||||
|
||||
// guided_takeoff_start - initialises waypoint controller to implement take-off
|
||||
static void guided_takeoff_start(float final_alt)
|
||||
static void guided_takeoff_start(float final_alt_above_home)
|
||||
{
|
||||
guided_mode = Guided_TakeOff;
|
||||
|
||||
// initialise wpnav destination
|
||||
Vector3f target_pos = inertial_nav.get_position();
|
||||
target_pos.z = final_alt;
|
||||
target_pos.z = pv_alt_above_origin(final_alt_above_home);
|
||||
wp_nav.set_wp_destination(target_pos);
|
||||
|
||||
// initialise yaw
|
||||
|
Loading…
Reference in New Issue
Block a user