Browse Source

Sub: Remove unused pre_arm_check()

This is performed by AP_Arming now
mission-4.1.18
Jacob Walser 8 years ago
parent
commit
2fac49a163
  1. 10
      ArduSub/AP_State.cpp
  2. 4
      ArduSub/ArduSub.cpp
  3. 1
      ArduSub/Sub.h

10
ArduSub/AP_State.cpp

@ -37,16 +37,6 @@ void Sub::set_auto_armed(bool b) @@ -37,16 +37,6 @@ void Sub::set_auto_armed(bool b)
}
}
// ---------------------------------------------
void Sub::set_pre_arm_check(bool b)
{
if (ap.pre_arm_check != b) {
ap.pre_arm_check = b;
AP_Notify::flags.pre_arm_check = b;
}
}
void Sub::set_motor_emergency_stop(bool b)
{
if (ap.motor_emergency_stop != b) {

4
ArduSub/ArduSub.cpp

@ -363,7 +363,9 @@ void Sub::three_hz_loop() @@ -363,7 +363,9 @@ void Sub::three_hz_loop()
// one_hz_loop - runs at 1Hz
void Sub::one_hz_loop()
{
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
bool arm_check = arming.pre_arm_checks(false);
ap.pre_arm_check = arm_check;
AP_Notify::flags.pre_arm_check = arm_check;
AP_Notify::flags.pre_arm_gps_check = position_ok();
if (should_log(MASK_LOG_ANY)) {

1
ArduSub/Sub.h

@ -470,7 +470,6 @@ private: @@ -470,7 +470,6 @@ private:
void set_home_state(enum HomeState new_home_state);
bool home_is_set();
void set_auto_armed(bool b);
void set_pre_arm_check(bool b);
void set_motor_emergency_stop(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);

Loading…
Cancel
Save