mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Sub: Remove auto_disarm_check
There isn't a good set of conditions to determine if we should automatically disarm
This commit is contained in:
parent
4465d4ba69
commit
1a68fce2d0
@ -31,7 +31,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
||||
SCHED_TASK(update_optical_flow, 200, 160),
|
||||
#endif
|
||||
SCHED_TASK(update_batt_compass, 10, 120),
|
||||
SCHED_TASK(auto_disarm_check, 10, 50),
|
||||
SCHED_TASK(read_rangefinder, 20, 100),
|
||||
SCHED_TASK(update_altitude, 10, 100),
|
||||
SCHED_TASK(run_nav_updates, 50, 100),
|
||||
|
@ -272,14 +272,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
// @Param: DISARM_DELAY
|
||||
// @DisplayName: Disarm delay
|
||||
// @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.
|
||||
// @Units: Seconds
|
||||
// @Range: 0 127
|
||||
// @User: Advanced
|
||||
GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),
|
||||
|
||||
// @Param: ANGLE_MAX
|
||||
// @DisplayName: Angle Max
|
||||
// @Description: Maximum lean angle in all flight modes
|
||||
|
@ -199,8 +199,7 @@ public:
|
||||
k_param_gcs_pid_mask = 178,
|
||||
k_param_throttle_filt,
|
||||
k_param_throttle_deadzone, // Used in auto-throttle modes
|
||||
k_param_disarm_delay,
|
||||
k_param_terrain_follow,
|
||||
k_param_terrain_follow = 182,
|
||||
k_param_rc_feel_rp,
|
||||
k_param_throttle_gain,
|
||||
k_param_cam_tilt_center,
|
||||
@ -280,8 +279,6 @@ public:
|
||||
//
|
||||
AP_Int32 log_bitmask;
|
||||
|
||||
AP_Int8 disarm_delay;
|
||||
|
||||
AP_Int8 fs_ekf_action;
|
||||
AP_Int8 fs_crash_check;
|
||||
AP_Float fs_ekf_thresh;
|
||||
|
@ -656,7 +656,6 @@ private:
|
||||
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc);
|
||||
uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec);
|
||||
void motor_test_stop();
|
||||
void auto_disarm_check();
|
||||
bool init_arm_motors(bool arming_from_gcs);
|
||||
void init_disarm_motors();
|
||||
void motors_output();
|
||||
|
@ -1,39 +1,7 @@
|
||||
#include "Sub.h"
|
||||
|
||||
#define ARM_DELAY 20 // called at 10hz so 2 seconds
|
||||
#define DISARM_DELAY 20 // called at 10hz so 2 seconds
|
||||
#define AUTO_TRIM_DELAY 100 // called at 10hz so 10 seconds
|
||||
#define LOST_VEHICLE_DELAY 10 // called at 10hz so 1 second
|
||||
|
||||
//static uint32_t auto_disarm_begin;
|
||||
|
||||
// auto_disarm_check
|
||||
// Automatically disarm the vehicle under some set of conditions
|
||||
// What those conditions should be TBD
|
||||
void Sub::auto_disarm_check()
|
||||
{
|
||||
// Disable for now
|
||||
|
||||
// uint32_t tnow_ms = millis();
|
||||
// uint32_t disarm_delay_ms = 1000*constrain_int16(g.disarm_delay, 0, 127);
|
||||
//
|
||||
// // exit immediately if we are already disarmed, or if auto
|
||||
// // disarming is disabled
|
||||
// if (!motors.armed() || disarm_delay_ms == 0) {
|
||||
// auto_disarm_begin = tnow_ms;
|
||||
// return;
|
||||
// }
|
||||
//
|
||||
// if(!mode_has_manual_throttle(control_mode) || !ap.throttle_zero) {
|
||||
// auto_disarm_begin = tnow_ms;
|
||||
// }
|
||||
//
|
||||
// if(tnow > auto_disarm_begin + disarm_delay_ms) {
|
||||
// init_disarm_motors();
|
||||
// auto_disarm_begin = tnow_ms;
|
||||
// }
|
||||
}
|
||||
|
||||
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
||||
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
||||
bool Sub::init_arm_motors(bool arming_from_gcs)
|
||||
|
Loading…
Reference in New Issue
Block a user