AP_Mount: allow users to disable yaw on 3-axis gimbals

Also fixes 3-axis gimbal support for SToRM32 serial and MAVLink gimbals
This commit is contained in:
Randy Mackay 2022-08-26 12:42:17 +09:00 committed by Andrew Tridgell
parent a560d1f2cc
commit 2bcb503170
8 changed files with 10 additions and 20 deletions

View File

@ -99,7 +99,7 @@ void AP_Mount_Alexmos::update()
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
bool AP_Mount_Alexmos::has_pan_control() const
{
return _gimbal_3axis;
return _gimbal_3axis && yaw_range_valid();
}
// get attitude as a quaternion. returns true on success

View File

@ -46,7 +46,7 @@ public:
// return true if healthy
virtual bool healthy() const { return true; }
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
// returns true if this mount can control its pan (required for multicopters)
virtual bool has_pan_control() const = 0;
// get mount's mode
@ -115,6 +115,10 @@ protected:
bool yaw_is_ef;
};
// returns true if user has configured a valid yaw angle range
// allows user to disable yaw even on 3-axis gimbal
bool yaw_range_valid() const { return (_state._pan_angle_min < _state._pan_angle_max); }
// returns true if mavlink heartbeat should be suppressed for this gimbal (only used by Solo gimbal)
virtual bool suppress_heartbeat() const { return false; }

View File

@ -34,7 +34,7 @@ public:
bool healthy() const override;
// has_pan_control
bool has_pan_control() const override { return true; }
bool has_pan_control() const override { return yaw_range_valid(); }
// handle GIMBAL_DEVICE_INFORMATION message
void handle_gimbal_device_information(const mavlink_message_t &msg) override;

View File

@ -104,13 +104,6 @@ void AP_Mount_SToRM32::update()
}
}
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
bool AP_Mount_SToRM32::has_pan_control() const
{
// we do not have yaw control
return false;
}
// set_mode - sets mount's mode
void AP_Mount_SToRM32::set_mode(enum MAV_MOUNT_MODE mode)
{

View File

@ -30,7 +30,7 @@ public:
void update() override;
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
bool has_pan_control() const override;
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;

View File

@ -133,13 +133,6 @@ void AP_Mount_SToRM32_serial::update()
}
}
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
bool AP_Mount_SToRM32_serial::has_pan_control() const
{
// we do not have yaw control
return false;
}
// set_mode - sets mount's mode
void AP_Mount_SToRM32_serial::set_mode(enum MAV_MOUNT_MODE mode)
{

View File

@ -33,7 +33,7 @@ public:
void update() override;
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
bool has_pan_control() const override;
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;

View File

@ -117,7 +117,7 @@ void AP_Mount_Servo::update()
// returns true if this mount can control its pan (required for multicopters)
bool AP_Mount_Servo::has_pan_control() const
{
return SRV_Channels::function_assigned(_pan_idx);
return SRV_Channels::function_assigned(_pan_idx) && yaw_range_valid();
}
// get attitude as a quaternion. returns true on success