mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Copter: change make_safe_shut_down to make_safe_spool_down
This commit is contained in:
parent
f96da56ad6
commit
94738c3f86
@ -407,10 +407,10 @@ void Copter::Mode::zero_throttle_and_hold_attitude()
|
|||||||
attitude_control->set_throttle_out(0.0f, false, copter.g.throttle_filt);
|
attitude_control->set_throttle_out(0.0f, false, copter.g.throttle_filt);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Copter::Mode::make_safe_shut_down()
|
void Copter::Mode::make_safe_spool_down()
|
||||||
{
|
{
|
||||||
// command aircraft to initiate the shutdown process
|
// command aircraft to initiate the shutdown process
|
||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
switch (motors->get_spool_mode()) {
|
switch (motors->get_spool_mode()) {
|
||||||
|
|
||||||
case AP_Motors::SHUT_DOWN:
|
case AP_Motors::SHUT_DOWN:
|
||||||
|
@ -117,7 +117,7 @@ protected:
|
|||||||
// helper functions
|
// helper functions
|
||||||
void zero_throttle_and_relax_ac(bool spool_up = false);
|
void zero_throttle_and_relax_ac(bool spool_up = false);
|
||||||
void zero_throttle_and_hold_attitude();
|
void zero_throttle_and_hold_attitude();
|
||||||
void make_safe_shut_down();
|
void make_safe_spool_down();
|
||||||
|
|
||||||
// functions to control landing
|
// functions to control landing
|
||||||
// in modes that support landing
|
// in modes that support landing
|
||||||
|
@ -741,7 +741,7 @@ void Copter::ModeAuto::wp_run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
wp_nav->wp_and_spline_init();
|
wp_nav->wp_and_spline_init();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -771,7 +771,7 @@ void Copter::ModeAuto::spline_run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
wp_nav->wp_and_spline_init();
|
wp_nav->wp_and_spline_init();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -809,14 +809,10 @@ void Copter::ModeAuto::spline_run()
|
|||||||
// called by auto_run at 100hz or more
|
// called by auto_run at 100hz or more
|
||||||
void Copter::ModeAuto::land_run()
|
void Copter::ModeAuto::land_run()
|
||||||
{
|
{
|
||||||
// disarm when the landing detector says we've landed
|
|
||||||
if (ap.land_complete && motors->get_spool_mode() == AP_Motors::GROUND_IDLE) {
|
|
||||||
copter.init_disarm_motors();
|
|
||||||
}
|
|
||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
loiter_nav->init_target();
|
loiter_nav->init_target();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -871,7 +867,7 @@ void Copter::ModeAuto::loiter_run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
wp_nav->wp_and_spline_init();
|
wp_nav->wp_and_spline_init();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -1731,7 +1727,9 @@ bool Copter::ModeAuto::verify_loiter_to_alt()
|
|||||||
// returns true with RTL has completed successfully
|
// returns true with RTL has completed successfully
|
||||||
bool Copter::ModeAuto::verify_RTL()
|
bool Copter::ModeAuto::verify_RTL()
|
||||||
{
|
{
|
||||||
return (copter.mode_rtl.state_complete() && (copter.mode_rtl.state() == RTL_FinalDescent || copter.mode_rtl.state() == RTL_Land));
|
return (copter.mode_rtl.state_complete() &&
|
||||||
|
(copter.mode_rtl.state() == RTL_FinalDescent || copter.mode_rtl.state() == RTL_Land) &&
|
||||||
|
(motors->get_spool_mode() == AP_Motors::GROUND_IDLE));
|
||||||
}
|
}
|
||||||
|
|
||||||
/********************************************************************************/
|
/********************************************************************************/
|
||||||
|
@ -33,7 +33,7 @@ void Copter::ModeBrake::run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
wp_nav->init_brake_target(BRAKE_MODE_DECEL_RATE);
|
wp_nav->init_brake_target(BRAKE_MODE_DECEL_RATE);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -49,7 +49,7 @@ void Copter::ModeCircle::run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -28,7 +28,7 @@ void Copter::ModeFollow::run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -379,7 +379,7 @@ void Copter::Mode::auto_takeoff_run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed) {
|
if (!motors->armed() || !ap.auto_armed) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
wp_nav->shift_wp_origin_to_current_pos();
|
wp_nav->shift_wp_origin_to_current_pos();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -427,7 +427,7 @@ void Copter::ModeGuided::pos_control_run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -469,7 +469,7 @@ void Copter::ModeGuided::vel_control_run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -522,7 +522,7 @@ void Copter::ModeGuided::posvel_control_run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -606,7 +606,7 @@ void Copter::ModeGuided::angle_control_run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || (ap.land_complete && (guided_angle_state.climb_rate_cms <= 0.0f))) {
|
if (!motors->armed() || !ap.auto_armed || (ap.land_complete && (guided_angle_state.climb_rate_cms <= 0.0f))) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -60,7 +60,7 @@ void Copter::ModeLand::gps_run()
|
|||||||
|
|
||||||
// Land State Machine Determination
|
// Land State Machine Determination
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
loiter_nav->init_target();
|
loiter_nav->init_target();
|
||||||
} else {
|
} else {
|
||||||
// set motors to full range
|
// set motors to full range
|
||||||
@ -111,7 +111,7 @@ void Copter::ModeLand::nogps_run()
|
|||||||
|
|
||||||
// Land State Machine Determination
|
// Land State Machine Determination
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
} else {
|
} else {
|
||||||
// set motors to full range
|
// set motors to full range
|
||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
|
@ -129,7 +129,7 @@ void Copter::ModeRTL::climb_return_run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -186,7 +186,7 @@ void Copter::ModeRTL::loiterathome_run()
|
|||||||
{
|
{
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -258,7 +258,7 @@ void Copter::ModeRTL::descent_run()
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -363,7 +363,7 @@ void Copter::ModeRTL::land_run(bool disarm_on_land)
|
|||||||
|
|
||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
|
||||||
make_safe_shut_down();
|
make_safe_spool_down();
|
||||||
loiter_nav->init_target();
|
loiter_nav->init_target();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user