mirror of https://github.com/ArduPilot/ardupilot
Copter: move responsibility for parachute deployment up
This commit is contained in:
parent
9cd881b56c
commit
228d7b676d
|
@ -209,10 +209,6 @@ void Copter::parachute_check()
|
|||
// parachute_release - trigger the release of the parachute, disarm the motors and notify the user
|
||||
void Copter::parachute_release()
|
||||
{
|
||||
// send message to gcs and dataflash
|
||||
gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Released");
|
||||
Log_Write_Event(DATA_PARACHUTE_RELEASED);
|
||||
|
||||
// disarm motors
|
||||
init_disarm_motors();
|
||||
|
||||
|
|
|
@ -485,12 +485,6 @@ bool Copter::ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
#endif //AC_FENCE == ENABLED
|
||||
break;
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute
|
||||
do_parachute(cmd);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if NAV_GUIDED == ENABLED
|
||||
case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits
|
||||
do_guided_limits(cmd);
|
||||
|
@ -679,7 +673,6 @@ bool Copter::ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||
case MAV_CMD_DO_SET_HOME:
|
||||
case MAV_CMD_DO_SET_ROI:
|
||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||
case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully
|
||||
case MAV_CMD_DO_GUIDED_LIMITS:
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
case MAV_CMD_DO_WINCH:
|
||||
|
@ -1393,29 +1386,6 @@ void Copter::ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd)
|
|||
#endif
|
||||
}
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
// do_parachute - configure or release parachute
|
||||
void Copter::ModeAuto::do_parachute(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
switch (cmd.p1) {
|
||||
case PARACHUTE_DISABLE:
|
||||
copter.parachute.enabled(false);
|
||||
Log_Write_Event(DATA_PARACHUTE_DISABLED);
|
||||
break;
|
||||
case PARACHUTE_ENABLE:
|
||||
copter.parachute.enabled(true);
|
||||
Log_Write_Event(DATA_PARACHUTE_ENABLED);
|
||||
break;
|
||||
case PARACHUTE_RELEASE:
|
||||
copter.parachute_release();
|
||||
break;
|
||||
default:
|
||||
// do nothing
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
// control winch based on mission command
|
||||
void Copter::ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
|
||||
|
|
|
@ -19,7 +19,6 @@ def build(bld):
|
|||
'AP_IRLock',
|
||||
'AP_InertialNav',
|
||||
'AP_Motors',
|
||||
'AP_Parachute',
|
||||
'AP_RCMapper',
|
||||
'AP_Avoidance',
|
||||
'AP_AdvancedFailsafe',
|
||||
|
|
Loading…
Reference in New Issue