From a22af31a08b20fc36fe071ca5b9279f821862e9c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 17 Sep 2022 09:28:12 +0900 Subject: [PATCH] AP_Mount: remove set_mode overrides The mode state is local to the driver and does not depend upon successful communication with the gimbal --- libraries/AP_Mount/AP_Mount_Backend.h | 2 +- libraries/AP_Mount/AP_Mount_SToRM32.cpp | 12 ------------ libraries/AP_Mount/AP_Mount_SToRM32.h | 3 --- libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp | 12 ------------ libraries/AP_Mount/AP_Mount_SToRM32_serial.h | 3 --- libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 12 ------------ libraries/AP_Mount/AP_Mount_SoloGimbal.h | 3 --- 7 files changed, 1 insertion(+), 46 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index ba1a22d2c7..b9dedcaf88 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -53,7 +53,7 @@ public: enum MAV_MOUNT_MODE get_mode() const { return _mode; } // set mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode) { _mode = mode; } + void set_mode(enum MAV_MOUNT_MODE mode) { _mode = mode; } // set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index 03775f9cdc..52aa45616b 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -104,18 +104,6 @@ void AP_Mount_SToRM32::update() } } -// set_mode - sets mount's mode -void AP_Mount_SToRM32::set_mode(enum MAV_MOUNT_MODE mode) -{ - // exit immediately if not initialised - if (!_initialised) { - return; - } - - // record the mode change - _mode = mode; -} - // get attitude as a quaternion. returns true on success bool AP_Mount_SToRM32::get_attitude_quaternion(Quaternion& att_quat) { diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index d3baf8f168..a50ddb1d25 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -32,9 +32,6 @@ public: // has_pan_control - returns true if this mount can control it's pan (required for multicopters) bool has_pan_control() const override { return yaw_range_valid(); } - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; - protected: // get attitude as a quaternion. returns true on success diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 35bffb9c1c..e6502f878e 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -133,18 +133,6 @@ void AP_Mount_SToRM32_serial::update() } } -// set_mode - sets mount's mode -void AP_Mount_SToRM32_serial::set_mode(enum MAV_MOUNT_MODE mode) -{ - // exit immediately if not initialised - if (!_initialised) { - return; - } - - // record the mode change - _mode = mode; -} - // get attitude as a quaternion. returns true on success bool AP_Mount_SToRM32_serial::get_attitude_quaternion(Quaternion& att_quat) { diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index 67a779db4b..d1c1019034 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -35,9 +35,6 @@ public: // has_pan_control - returns true if this mount can control it's pan (required for multicopters) bool has_pan_control() const override { return yaw_range_valid(); }; - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; - protected: // get attitude as a quaternion. returns true on success diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 210ae8cdc7..df48ddf7cc 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -103,18 +103,6 @@ void AP_Mount_SoloGimbal::update() } } -// set_mode - sets mount's mode -void AP_Mount_SoloGimbal::set_mode(enum MAV_MOUNT_MODE mode) -{ - // exit immediately if not initialised - if (!_initialised) { - return; - } - - // record the mode change - _mode = mode; -} - // get attitude as a quaternion. returns true on success bool AP_Mount_SoloGimbal::get_attitude_quaternion(Quaternion& att_quat) { diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index 565355b746..0b9f07182d 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -32,9 +32,6 @@ public: // has_pan_control - returns true if this mount can control it's pan (required for multicopters) bool has_pan_control() const override { return false; } - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; - // handle a GIMBAL_REPORT message void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) override; void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg);