mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AP_Mission: move responsibility for parachute deployment up
This commit is contained in:
parent
005ec5cd4d
commit
9cd881b56c
@ -269,6 +269,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
|
|||||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||||
|
case MAV_CMD_DO_PARACHUTE:
|
||||||
return true;
|
return true;
|
||||||
default:
|
default:
|
||||||
return _cmd_verify_fn(cmd);
|
return _cmd_verify_fn(cmd);
|
||||||
@ -290,6 +291,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
|
|||||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||||
return start_command_camera(cmd);
|
return start_command_camera(cmd);
|
||||||
|
case MAV_CMD_DO_PARACHUTE:
|
||||||
|
return start_command_parachute(cmd);
|
||||||
default:
|
default:
|
||||||
return _cmd_start_fn(cmd);
|
return _cmd_start_fn(cmd);
|
||||||
}
|
}
|
||||||
|
@ -583,6 +583,7 @@ private:
|
|||||||
bool start_command_do_gripper(const AP_Mission::Mission_Command& cmd);
|
bool start_command_do_gripper(const AP_Mission::Mission_Command& cmd);
|
||||||
bool start_command_do_servorelayevents(const AP_Mission::Mission_Command& cmd);
|
bool start_command_do_servorelayevents(const AP_Mission::Mission_Command& cmd);
|
||||||
bool start_command_camera(const AP_Mission::Mission_Command& cmd);
|
bool start_command_camera(const AP_Mission::Mission_Command& cmd);
|
||||||
|
bool start_command_parachute(const AP_Mission::Mission_Command& cmd);
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Gripper/AP_Gripper.h>
|
#include <AP_Gripper/AP_Gripper.h>
|
||||||
|
#include <AP_Parachute/AP_Parachute.h>
|
||||||
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
||||||
|
|
||||||
bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
|
bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
|
||||||
@ -110,3 +111,27 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Mission::start_command_parachute(const AP_Mission::Mission_Command& cmd)
|
||||||
|
{
|
||||||
|
AP_Parachute *parachute = AP::parachute();
|
||||||
|
if (parachute == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
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
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user