mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Sub: Remove parachute
This commit is contained in:
parent
d75919eadc
commit
7b5d209aba
@ -25,7 +25,6 @@
|
||||
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash
|
||||
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
|
||||
#define AC_TERRAIN DISABLED // disable terrain library
|
||||
#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
|
||||
#define GRIPPER_ENABLED DISABLED // disable gripper to save 500bytes of flash
|
||||
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
||||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||
|
@ -1546,30 +1546,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
#endif
|
||||
break;
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
case MAV_CMD_DO_PARACHUTE:
|
||||
// configure or release parachute
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
switch ((uint16_t)packet.param1) {
|
||||
case PARACHUTE_DISABLE:
|
||||
sub.parachute.enabled(false);
|
||||
sub.Log_Write_Event(DATA_PARACHUTE_DISABLED);
|
||||
break;
|
||||
case PARACHUTE_ENABLE:
|
||||
sub.parachute.enabled(true);
|
||||
sub.Log_Write_Event(DATA_PARACHUTE_ENABLED);
|
||||
break;
|
||||
case PARACHUTE_RELEASE:
|
||||
// treat as a manual release which performs some additional check of altitude
|
||||
sub.parachute_manual_release();
|
||||
break;
|
||||
default:
|
||||
result = MAV_RESULT_FAILED;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_DO_MOTOR_TEST:
|
||||
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
|
||||
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
|
||||
|
@ -860,12 +860,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
||||
GOBJECT(relay, "RELAY_", AP_Relay),
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
// @Group: CHUTE_
|
||||
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
|
||||
GOBJECT(parachute, "CHUTE_", AP_Parachute),
|
||||
#endif
|
||||
|
||||
// @Group: LGR_
|
||||
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
||||
GOBJECT(landinggear, "LGR_", AP_LandingGear),
|
||||
|
@ -73,9 +73,6 @@ public:
|
||||
// GPS object
|
||||
k_param_gps,
|
||||
|
||||
// Parachute object
|
||||
k_param_parachute,
|
||||
|
||||
// Landing gear object
|
||||
k_param_landinggear, // 18
|
||||
|
||||
|
@ -91,9 +91,6 @@ Sub::Sub(void) :
|
||||
#if SPRAYER == ENABLED
|
||||
sprayer(&inertial_nav),
|
||||
#endif
|
||||
#if PARACHUTE == ENABLED
|
||||
parachute(relay),
|
||||
#endif
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
terrain(ahrs, mission, rally),
|
||||
#endif
|
||||
|
@ -105,9 +105,6 @@
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
|
||||
#endif
|
||||
#if PARACHUTE == ENABLED
|
||||
#include <AP_Parachute/AP_Parachute.h> // Parachute release library
|
||||
#endif
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
#include <AC_PrecLand/AC_PrecLand.h>
|
||||
#include <AP_IRLock/AP_IRLock.h>
|
||||
@ -500,11 +497,6 @@ private:
|
||||
AC_Sprayer sprayer;
|
||||
#endif
|
||||
|
||||
// Parachute release
|
||||
#if PARACHUTE == ENABLED
|
||||
AP_Parachute parachute;
|
||||
#endif
|
||||
|
||||
// Landing Gear Controller
|
||||
AP_LandingGear landinggear;
|
||||
|
||||
@ -766,9 +758,6 @@ private:
|
||||
bool manual_init(bool ignore_checks);
|
||||
void manual_run();
|
||||
void crash_check();
|
||||
void parachute_check();
|
||||
void parachute_release();
|
||||
void parachute_manual_release();
|
||||
void ekf_check();
|
||||
bool ekf_over_threshold();
|
||||
void failsafe_ekf_event();
|
||||
@ -936,9 +925,6 @@ private:
|
||||
void do_digicam_configure(const AP_Mission::Mission_Command& cmd);
|
||||
void do_digicam_control(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
#if PARACHUTE == ENABLED
|
||||
void do_parachute(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
void do_gripper(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
|
@ -124,12 +124,6 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute
|
||||
do_parachute(cmd);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
case MAV_CMD_DO_GRIPPER: // Mission command to control gripper
|
||||
do_gripper(cmd);
|
||||
@ -234,7 +228,6 @@ bool Sub::verify_command(const AP_Mission::Mission_Command& cmd)
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully
|
||||
case MAV_CMD_DO_GRIPPER:
|
||||
case MAV_CMD_DO_GUIDED_LIMITS:
|
||||
return true;
|
||||
@ -529,30 +522,6 @@ void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Delaying %u sec",(unsigned int)(nav_delay_time_max/1000));
|
||||
}
|
||||
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
// do_parachute - configure or release parachute
|
||||
void Sub::do_parachute(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
switch (cmd.p1) {
|
||||
case PARACHUTE_DISABLE:
|
||||
parachute.enabled(false);
|
||||
Log_Write_Event(DATA_PARACHUTE_DISABLED);
|
||||
break;
|
||||
case PARACHUTE_ENABLE:
|
||||
parachute.enabled(true);
|
||||
Log_Write_Event(DATA_PARACHUTE_ENABLED);
|
||||
break;
|
||||
case PARACHUTE_RELEASE:
|
||||
parachute_release();
|
||||
break;
|
||||
default:
|
||||
// do nothing
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
// do_gripper - control gripper
|
||||
void Sub::do_gripper(const AP_Mission::Mission_Command& cmd)
|
||||
|
@ -255,12 +255,6 @@
|
||||
# define EPM_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Parachute release
|
||||
#ifndef PARACHUTE
|
||||
# define PARACHUTE ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Nav-Guided - allows external nav computer to control vehicle
|
||||
#ifndef NAV_GUIDED
|
||||
|
@ -56,9 +56,12 @@ enum aux_sw_func {
|
||||
AUXSW_AUTOTUNE = 17, // auto tune
|
||||
AUXSW_LAND = 18, // change to LAND flight mode
|
||||
AUXSW_GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
|
||||
AUXSW_PARACHUTE_ENABLE = 21, // Parachute enable/disable
|
||||
AUXSW_PARACHUTE_RELEASE = 22, // Parachute release
|
||||
AUXSW_PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
|
||||
|
||||
// No parachute for Sub, remove
|
||||
// AUXSW_PARACHUTE_ENABLE = 21, // Parachute enable/disable
|
||||
// AUXSW_PARACHUTE_RELEASE = 22, // Parachute release
|
||||
// AUXSW_PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
|
||||
|
||||
AUXSW_MISSION_RESET = 24, // Reset auto mission to start from first command
|
||||
AUXSW_ATTCON_FEEDFWD = 25, // enable/disable the roll and pitch rate feed forward
|
||||
AUXSW_ATTCON_ACCEL_LIM = 26, // enable/disable the roll, pitch and yaw accel limiting
|
||||
@ -340,9 +343,9 @@ enum ThrowModeState {
|
||||
#define DATA_ACRO_TRAINER_LIMITED 45
|
||||
#define DATA_GRIPPER_GRAB 46
|
||||
#define DATA_GRIPPER_RELEASE 47
|
||||
#define DATA_PARACHUTE_DISABLED 49
|
||||
#define DATA_PARACHUTE_ENABLED 50
|
||||
#define DATA_PARACHUTE_RELEASED 51
|
||||
//#define DATA_PARACHUTE_DISABLED 49 // Remove
|
||||
//#define DATA_PARACHUTE_ENABLED 50 // Remove
|
||||
//#define DATA_PARACHUTE_RELEASED 51 // Remove
|
||||
#define DATA_LANDING_GEAR_DEPLOYED 52
|
||||
#define DATA_LANDING_GEAR_RETRACTED 53
|
||||
#define DATA_MOTORS_EMERGENCY_STOPPED 54
|
||||
@ -377,7 +380,7 @@ enum ThrowModeState {
|
||||
#define ERROR_SUBSYSTEM_CRASH_CHECK 12
|
||||
//#define ERROR_SUBSYSTEM_FLIP 13
|
||||
#define ERROR_SUBSYSTEM_AUTOTUNE 14
|
||||
#define ERROR_SUBSYSTEM_PARACHUTE 15
|
||||
//#define ERROR_SUBSYSTEM_PARACHUTE 15 // Remove
|
||||
#define ERROR_SUBSYSTEM_EKFCHECK 16
|
||||
#define ERROR_SUBSYSTEM_FAILSAFE_EKFINAV 17
|
||||
#define ERROR_SUBSYSTEM_BARO 18
|
||||
@ -411,9 +414,6 @@ enum ThrowModeState {
|
||||
#define ERROR_CODE_FAILED_CIRCLE_INIT 4
|
||||
#define ERROR_CODE_DEST_OUTSIDE_FENCE 5
|
||||
|
||||
// parachute failed to deploy because of low altitude or landed
|
||||
#define ERROR_CODE_PARACHUTE_TOO_LOW 2
|
||||
#define ERROR_CODE_PARACHUTE_LANDED 3
|
||||
// EKF check definitions
|
||||
#define ERROR_CODE_EKFCHECK_BAD_VARIANCE 2
|
||||
#define ERROR_CODE_EKFCHECK_VARIANCE_CLEARED 0
|
||||
|
@ -52,7 +52,6 @@ LIBRARIES += AP_BattMonitor
|
||||
LIBRARIES += AP_BoardConfig
|
||||
LIBRARIES += AP_Frsky_Telem
|
||||
LIBRARIES += AC_Sprayer
|
||||
LIBRARIES += AP_Parachute
|
||||
LIBRARIES += AP_LandingGear
|
||||
LIBRARIES += AP_Terrain
|
||||
LIBRARIES += AP_RPM
|
||||
|
@ -235,8 +235,6 @@ void Sub::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
|
||||
case AUXSW_ACRO_TRAINER:
|
||||
case AUXSW_GRIPPER:
|
||||
case AUXSW_SPRAYER:
|
||||
case AUXSW_PARACHUTE_ENABLE:
|
||||
case AUXSW_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
|
||||
case AUXSW_RETRACT_MOUNT:
|
||||
case AUXSW_MISSION_RESET:
|
||||
case AUXSW_ATTCON_FEEDFWD:
|
||||
@ -441,37 +439,6 @@ void Sub::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
// }
|
||||
break;
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
case AUXSW_PARACHUTE_ENABLE:
|
||||
// Parachute enable/disable
|
||||
parachute.enabled(ch_flag == AUX_SWITCH_HIGH);
|
||||
break;
|
||||
|
||||
case AUXSW_PARACHUTE_RELEASE:
|
||||
if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
parachute_manual_release();
|
||||
}
|
||||
break;
|
||||
|
||||
case AUXSW_PARACHUTE_3POS:
|
||||
// Parachute disable, enable, release with 3 position switch
|
||||
switch (ch_flag) {
|
||||
case AUX_SWITCH_LOW:
|
||||
parachute.enabled(false);
|
||||
Log_Write_Event(DATA_PARACHUTE_DISABLED);
|
||||
break;
|
||||
case AUX_SWITCH_MIDDLE:
|
||||
parachute.enabled(true);
|
||||
Log_Write_Event(DATA_PARACHUTE_ENABLED);
|
||||
break;
|
||||
case AUX_SWITCH_HIGH:
|
||||
parachute.enabled(true);
|
||||
parachute_manual_release();
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case AUXSW_MISSION_RESET:
|
||||
if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
mission.reset();
|
||||
|
Loading…
Reference in New Issue
Block a user