Sub: Remove unused auto_armed flag

This commit is contained in:
Jacob Walser 2017-04-13 15:34:58 -04:00
parent 8ebfcdec6e
commit 84527d6e66
10 changed files with 17 additions and 62 deletions

View File

@ -22,17 +22,3 @@ bool Sub::home_is_set()
{
return (ap.home_state == HOME_SET_NOT_LOCKED || ap.home_state == HOME_SET_AND_LOCKED);
}
// ---------------------------------------------
void Sub::set_auto_armed(bool b)
{
// if no change, exit immediately
if (ap.auto_armed == b) {
return;
}
ap.auto_armed = b;
if (b) {
Log_Write_Event(DATA_AUTO_ARMED);
}
}

View File

@ -212,9 +212,6 @@ void Sub::fast_loop()
// 50 Hz tasks
void Sub::fifty_hz_loop()
{
// check auto_armed status
update_auto_armed();
// check pilot input failsafe
failsafe_manual_control_check();

View File

@ -1242,7 +1242,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
case MAV_CMD_MISSION_START:
if (sub.motors.armed() && sub.set_mode(AUTO, MODE_REASON_GCS_COMMAND)) {
sub.set_auto_armed(true);
if (sub.mission.state() != AP_Mission::MISSION_RUNNING) {
sub.mission.start_or_resume();
}

View File

@ -232,7 +232,6 @@ private:
union {
struct {
uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
uint8_t auto_armed : 1; // stops auto missions from beginning until throttle is raised
uint8_t logging_started : 1; // true if dataflash logging has started
uint8_t usb_connected : 1; // true if APM is powered from USB connection
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
@ -467,7 +466,6 @@ private:
void update_altitude();
void set_home_state(enum HomeState new_home_state);
bool home_is_set();
void set_auto_armed(bool b);
float get_smoothing_gain();
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);
float get_pilot_desired_yaw_rate(int16_t stick_angle);
@ -674,7 +672,6 @@ private:
bool position_ok();
bool ekf_position_ok();
bool optflow_position_ok();
void update_auto_armed();
void check_usb_mux(void);
bool should_log(uint32_t mask);
void gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...);

View File

@ -111,7 +111,7 @@ void Sub::auto_wp_start(const Location_Class& dest_loc)
// called by auto_run at 100hz or more
void Sub::auto_wp_run()
{
// if not auto armed set throttle to zero and exit immediately
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
// To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
// (of course it would be better if people just used take-off)
@ -198,8 +198,8 @@ void Sub::auto_spline_start(const Location_Class& destination, bool stopped_at_s
// called by auto_run at 100hz or more
void Sub::auto_spline_run()
{
// if not auto armed set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
// To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
// (of course it would be better if people just used take-off)
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
@ -376,7 +376,7 @@ bool Sub::auto_loiter_start()
// called by auto_run at 100hz or more
void Sub::auto_loiter_run()
{
// if not auto armed set throttle to zero and exit immediately
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed

View File

@ -39,8 +39,8 @@ void Sub::circle_run()
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);
// if not auto armed set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
// To-Do: add some initialisation of position controllers
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed

View File

@ -277,8 +277,8 @@ void Sub::guided_run()
// called from guided_run
void Sub::guided_pos_control_run()
{
// if not auto armed or motors not enabled set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// if motors not enabled set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
@ -326,8 +326,8 @@ void Sub::guided_pos_control_run()
// called from guided_run
void Sub::guided_vel_control_run()
{
// if not auto armed or motors not enabled set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// ifmotors not enabled set throttle to zero and exit immediately
if (!motors.armed()) {
// initialise velocity controller
pos_control.init_vel_controller_xyz();
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
@ -380,8 +380,8 @@ void Sub::guided_vel_control_run()
// called from guided_run
void Sub::guided_posvel_control_run()
{
// if not auto armed or motors not enabled set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// if motors not enabled set throttle to zero and exit immediately
if (!motors.armed()) {
// set target position and velocity to current position and velocity
pos_control.set_pos_target(inertial_nav.get_position());
pos_control.set_desired_velocity(Vector3f(0,0,0));
@ -456,8 +456,8 @@ void Sub::guided_posvel_control_run()
// called from guided_run
void Sub::guided_angle_control_run()
{
// if not auto armed or motors not enabled set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// if motors not enabled set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt);

View File

@ -36,9 +36,9 @@ bool Sub::poshold_init(bool ignore_checks)
void Sub::poshold_run()
{
uint32_t tnow = AP_HAL::millis();
// if not auto armed set throttle to zero and exit immediately
if (!motors.armed() || !ap.auto_armed) {
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
wp_nav.init_loiter_target();
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);

View File

@ -150,7 +150,6 @@ enum RTLState {
#define DATA_SYSTEM_TIME_SET 8
#define DATA_ARMED 10
#define DATA_DISARMED 11
#define DATA_AUTO_ARMED 15
#define DATA_LOST_GPS 19
#define DATA_SET_HOME 25
#define DATA_SAVE_TRIM 38

View File

@ -283,29 +283,6 @@ bool Sub::optflow_position_ok()
#endif
}
// update_auto_armed - update status of auto_armed flag
void Sub::update_auto_armed()
{
// disarm checks
if (ap.auto_armed) {
// if motors are disarmed, auto_armed should also be false
if (!motors.armed()) {
set_auto_armed(false);
return;
}
// if in stabilize or acro flight mode auto-armed should become false
if (mode_has_manual_throttle(control_mode) && !failsafe.manual_control) {
set_auto_armed(false);
}
} else {
// arm checks
// if motors are armed and throttle is above zero auto_armed should be true
if (motors.armed()) {
set_auto_armed(true);
}
}
}
void Sub::check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();