AP_Mount: remove set_mode overrides

The mode state is local to the driver and does not depend upon successful communication with the gimbal
This commit is contained in:
Randy Mackay 2022-09-17 09:28:12 +09:00 committed by Andrew Tridgell
parent a0311bd634
commit a22af31a08
7 changed files with 1 additions and 46 deletions

View File

@ -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

View File

@ -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)
{

View File

@ -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

View File

@ -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)
{

View File

@ -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

View File

@ -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)
{

View File

@ -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);