mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: ModeGuided::do_user_takeoff_start arg rename
this makes it more consistent with the method it is overriding
This commit is contained in:
parent
d37efe1b38
commit
db2229f684
@ -796,7 +796,7 @@ public:
|
||||
|
||||
bool is_taking_off() const override;
|
||||
|
||||
bool do_user_takeoff_start(float final_alt_above_home) override;
|
||||
bool do_user_takeoff_start(float takeoff_alt_cm) override;
|
||||
|
||||
GuidedMode mode() const { return guided_mode; }
|
||||
|
||||
|
@ -47,13 +47,13 @@ bool ModeGuided::init(bool ignore_checks)
|
||||
|
||||
|
||||
// do_user_takeoff_start - initialises waypoint controller to implement take-off
|
||||
bool ModeGuided::do_user_takeoff_start(float final_alt_above_home)
|
||||
bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm)
|
||||
{
|
||||
guided_mode = Guided_TakeOff;
|
||||
|
||||
// initialise wpnav destination
|
||||
Location target_loc = copter.current_loc;
|
||||
target_loc.set_alt_cm(final_alt_above_home, Location::AltFrame::ABOVE_HOME);
|
||||
target_loc.set_alt_cm(takeoff_alt_cm, Location::AltFrame::ABOVE_HOME);
|
||||
|
||||
if (!wp_nav->set_wp_destination(target_loc)) {
|
||||
// failure to set destination can only be because of missing terrain data
|
||||
|
Loading…
Reference in New Issue
Block a user