From 3cfdcb1f2ccd2a053148ef5a58ea9420d8972ee2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Jun 2018 12:06:17 +1000 Subject: [PATCH] ArduSub: use ArmingMethod enumeration --- ArduSub/GCS_Mavlink.cpp | 2 +- ArduSub/Sub.h | 2 +- ArduSub/joystick.cpp | 4 ++-- ArduSub/motors.cpp | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index a040bfbdd2..c8cced8f89 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -928,7 +928,7 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) case MAV_CMD_COMPONENT_ARM_DISARM: if (is_equal(packet.param1,1.0f)) { // attempt to arm and return success or failure - if (sub.init_arm_motors(true)) { + if (sub.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK)) { result = MAV_RESULT_ACCEPTED; } } else if (is_zero(packet.param1)) { diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 622d9c749b..6c3674a220 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -601,7 +601,7 @@ private: void update_surface_and_bottom_detector(); void set_surfaced(bool at_surface); void set_bottomed(bool at_bottom); - bool init_arm_motors(bool arming_from_gcs); + bool init_arm_motors(AP_Arming::ArmingMethod method); void init_disarm_motors(); void motors_output(); Vector3f pv_location_to_vector(const Location& loc); diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index c7f03b89b4..2ec6bc13e9 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -130,11 +130,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held) if (motors.armed()) { init_disarm_motors(); } else { - init_arm_motors(true); + init_arm_motors(AP_Arming::ArmingMethod::MAVLINK); } break; case JSButton::button_function_t::k_arm: - init_arm_motors(true); + init_arm_motors(AP_Arming::ArmingMethod::MAVLINK); break; case JSButton::button_function_t::k_disarm: init_disarm_motors(); diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 4a7cf1b915..ca32b8c841 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -8,7 +8,7 @@ void Sub::enable_motor_output() // 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) +bool Sub::init_arm_motors(AP_Arming::ArmingMethod method) { static bool in_arm_motors = false;