mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: factor out auto_takeoff_run from auto and guided
This code was identical.
This commit is contained in:
parent
ccc1170c8c
commit
11aeec6dd1
@ -157,6 +157,10 @@ protected:
|
||||
// takeoff support
|
||||
virtual bool do_user_takeoff_start(float takeoff_alt_cm);
|
||||
|
||||
// method shared by both Guided and Auto for takeoff. This is
|
||||
// waypoint navigation but the user can control the yaw.
|
||||
void auto_takeoff_run();
|
||||
|
||||
// gnd speed limit required to observe optical flow sensor limits
|
||||
float &ekfGndSpdLimit;
|
||||
|
||||
|
@ -728,46 +728,7 @@ bool Copter::ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
|
||||
// called by auto_run at 100hz or more
|
||||
void Copter::ModeAuto::takeoff_run()
|
||||
{
|
||||
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
|
||||
// initialise wpnav targets
|
||||
wp_nav->shift_wp_origin_to_current_pos();
|
||||
zero_throttle_and_relax_ac();
|
||||
// clear i term when we're taking off
|
||||
set_throttle_takeoff();
|
||||
return;
|
||||
}
|
||||
|
||||
// process pilot's yaw input
|
||||
float target_yaw_rate = 0;
|
||||
if (!copter.failsafe.radio) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters stay in landed state until rotor speed runup has finished
|
||||
if (motors->rotor_runup_complete()) {
|
||||
set_land_complete(false);
|
||||
} else {
|
||||
// initialise wpnav targets
|
||||
wp_nav->shift_wp_origin_to_current_pos();
|
||||
}
|
||||
#else
|
||||
set_land_complete(false);
|
||||
#endif
|
||||
|
||||
// set motors to full range
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// run waypoint controller
|
||||
copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
|
||||
|
||||
// call z-axis position controller (wpnav should have already updated it's alt target)
|
||||
pos_control->update_z_controller();
|
||||
|
||||
// call attitude controller
|
||||
copter.auto_takeoff_attitude_run(target_yaw_rate);
|
||||
auto_takeoff_run();
|
||||
}
|
||||
|
||||
// auto_wp_run - runs the auto waypoint controller
|
||||
|
@ -364,6 +364,11 @@ void Copter::ModeGuided::run()
|
||||
// guided_takeoff_run - takeoff in guided mode
|
||||
// called by guided_run at 100hz or more
|
||||
void Copter::ModeGuided::takeoff_run()
|
||||
{
|
||||
auto_takeoff_run();
|
||||
}
|
||||
|
||||
void Copter::Mode::auto_takeoff_run()
|
||||
{
|
||||
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
|
||||
|
Loading…
Reference in New Issue
Block a user