Plane: move responsibility for parachute deployment up

This commit is contained in:
Peter Barker 2019-02-01 11:41:56 +11:00 committed by Randy Mackay
parent 228d7b676d
commit 4f249db8bc
2 changed files with 0 additions and 34 deletions

View File

@ -159,12 +159,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
autotune_enable(cmd.p1);
break;
#if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE:
do_parachute(cmd);
break;
#endif
#if MOUNT == ENABLED
// Sets the region of interest (ROI) for a sensor set or the
// vehicle itself. This can then be used by the vehicles control
@ -286,12 +280,6 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
#if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE:
// assume parachute was released successfully
return true;
#endif
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
@ -920,27 +908,6 @@ void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)
}
}
#if PARACHUTE == ENABLED
// do_parachute - configure or release parachute
void Plane::do_parachute(const AP_Mission::Mission_Command& cmd)
{
switch (cmd.p1) {
case PARACHUTE_DISABLE:
parachute.enabled(false);
break;
case PARACHUTE_ENABLE:
parachute.enabled(true);
break;
case PARACHUTE_RELEASE:
parachute_release();
break;
default:
// do nothing
break;
}
}
#endif
// start_command_callback - callback function called from ap-mission when it begins a new mission command
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
bool Plane::start_command_callback(const AP_Mission::Mission_Command &cmd)

View File

@ -16,7 +16,6 @@ def build(bld):
'AP_Camera',
'AP_L1_Control',
'AP_Navigation',
'AP_Parachute',
'AP_RCMapper',
'AP_SpdHgtControl',
'AP_TECS',