mavsdk::Gimbal Class Reference ​
#include: gimbal.h
Provide control over a gimbal.
Data Structures ​
struct AngularVelocityBody
struct Attitude
struct ControlStatus
struct EulerAngle
struct GimbalItem
struct GimbalList
struct Quaternion
Public Types ​
Type | Description |
---|---|
enum GimbalMode | Gimbal mode type. |
enum ControlMode | Control mode. |
enum SendMode | The send mode type. |
enum Result | Possible results returned for gimbal commands. |
std::function< void(Result)> ResultCallback | Callback type for asynchronous Gimbal calls. |
std::function< void(GimbalList)> GimbalListCallback | Callback type for subscribe_gimbal_list. |
Handle< GimbalList > GimbalListHandle | Handle type for subscribe_gimbal_list. |
std::function< void(ControlStatus)> ControlStatusCallback | Callback type for subscribe_control_status. |
Handle< ControlStatus > ControlStatusHandle | Handle type for subscribe_control_status. |
std::function< void(Attitude)> AttitudeCallback | Callback type for subscribe_attitude. |
Handle< Attitude > AttitudeHandle | Handle type for subscribe_attitude. |
Public Member Functions ​
Type | Name | Description |
---|---|---|
 | Gimbal (System & system) | Constructor. Creates the plugin for a specific System. |
 | Gimbal (std::shared_ptr< System > system) | Constructor. Creates the plugin for a specific System. |
 | ~Gimbal () override | Destructor (internal use only). |
 | Gimbal (const Gimbal & other) | Copy constructor. |
void | set_angles_async (int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, GimbalMode gimbal_mode, SendMode send_mode, const ResultCallback callback) | Set gimbal roll, pitch and yaw angles. |
Result | set_angles (int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, GimbalMode gimbal_mode, SendMode send_mode)const | Set gimbal roll, pitch and yaw angles. |
void | set_angular_rates_async (int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, GimbalMode gimbal_mode, SendMode send_mode, const ResultCallback callback) | Set gimbal angular rates. |
Result | set_angular_rates (int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, GimbalMode gimbal_mode, SendMode send_mode)const | Set gimbal angular rates. |
void | set_roi_location_async (int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback) | Set gimbal region of interest (ROI). |
Result | set_roi_location (int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m)const | Set gimbal region of interest (ROI). |
void | take_control_async (int32_t gimbal_id, ControlMode control_mode, const ResultCallback callback) | Take control. |
Result | take_control (int32_t gimbal_id, ControlMode control_mode)const | Take control. |
void | release_control_async (int32_t gimbal_id, const ResultCallback callback) | Release control. |
Result | release_control (int32_t gimbal_id)const | Release control. |
GimbalListHandle | subscribe_gimbal_list (const GimbalListCallback & callback) | Subscribe to list of gimbals. |
void | unsubscribe_gimbal_list (GimbalListHandle handle) | Unsubscribe from subscribe_gimbal_list. |
GimbalList | gimbal_list () const | Poll for 'GimbalList' (blocking). |
ControlStatusHandle | subscribe_control_status (const ControlStatusCallback & callback) | Subscribe to control status updates. |
void | unsubscribe_control_status (ControlStatusHandle handle) | Unsubscribe from subscribe_control_status. |
std::pair< Result, Gimbal::ControlStatus > | get_control_status (int32_t gimbal_id)const | Get control status for specific gimbal. |
AttitudeHandle | subscribe_attitude (const AttitudeCallback & callback) | Subscribe to attitude updates. |
void | unsubscribe_attitude (AttitudeHandle handle) | Unsubscribe from subscribe_attitude. |
std::pair< Result, Gimbal::Attitude > | get_attitude (int32_t gimbal_id)const | Get attitude for specific gimbal. |
const Gimbal & | operator= (const Gimbal &)=delete | Equality operator (object is not copyable). |
Constructor & Destructor Documentation ​
Gimbal() ​
mavsdk::Gimbal::Gimbal(System &system)
Constructor. Creates the plugin for a specific System.
The plugin is typically created as shown below:
auto gimbal = Gimbal(system);
Parameters
- System& system - The specific system associated with this plugin.
Gimbal() ​
mavsdk::Gimbal::Gimbal(std::shared_ptr< System > system)
Constructor. Creates the plugin for a specific System.
The plugin is typically created as shown below:
auto gimbal = Gimbal(system);
Parameters
- std::shared_ptr< System > system - The specific system associated with this plugin.
~Gimbal() ​
mavsdk::Gimbal::~Gimbal() override
Destructor (internal use only).
Gimbal() ​
mavsdk::Gimbal::Gimbal(const Gimbal &other)
Copy constructor.
Parameters
- const Gimbal& other -
Member Typdef Documentation ​
typedef ResultCallback ​
using mavsdk::Gimbal::ResultCallback = std::function<void(Result)>
Callback type for asynchronous Gimbal calls.
typedef GimbalListCallback ​
using mavsdk::Gimbal::GimbalListCallback = std::function<void(GimbalList)>
Callback type for subscribe_gimbal_list.
typedef GimbalListHandle ​
using mavsdk::Gimbal::GimbalListHandle = Handle<GimbalList>
Handle type for subscribe_gimbal_list.
typedef ControlStatusCallback ​
using mavsdk::Gimbal::ControlStatusCallback = std::function<void(ControlStatus)>
Callback type for subscribe_control_status.
typedef ControlStatusHandle ​
using mavsdk::Gimbal::ControlStatusHandle = Handle<ControlStatus>
Handle type for subscribe_control_status.
typedef AttitudeCallback ​
using mavsdk::Gimbal::AttitudeCallback = std::function<void(Attitude)>
Callback type for subscribe_attitude.
typedef AttitudeHandle ​
using mavsdk::Gimbal::AttitudeHandle = Handle<Attitude>
Handle type for subscribe_attitude.
Member Enumeration Documentation ​
enum GimbalMode ​
Gimbal mode type.
Value | Description |
---|---|
YawFollow | Yaw follow will point the gimbal to the vehicle heading. |
YawLock | Yaw lock will fix the gimbal pointing to an absolute direction. |
enum ControlMode ​
Control mode.
Value | Description |
---|---|
None | Indicates that the component does not have control over the gimbal. |
Primary | To take primary control over the gimbal. |
Secondary | To take secondary control over the gimbal. |
enum SendMode ​
The send mode type.
Value | Description |
---|---|
Once | Send command exactly once with quality of service (use for sporadic commands slower than 1 Hz). |
Stream | Stream setpoint without quality of service (use for setpoints faster than 1 Hz).. |
enum Result ​
Possible results returned for gimbal commands.
Value | Description |
---|---|
Unknown | Unknown result. |
Success | Command was accepted. |
Error | Error occurred sending the command. |
Timeout | Command timed out. |
Unsupported | Functionality not supported. |
NoSystem | No system connected. |
InvalidArgument | Invalid argument. |
Member Function Documentation ​
set_angles_async() ​
void mavsdk::Gimbal::set_angles_async(int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, GimbalMode gimbal_mode, SendMode send_mode, const ResultCallback callback)
Set gimbal roll, pitch and yaw angles.
This sets the desired roll, pitch and yaw angles of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.
Note that the roll angle needs to be set to 0 when send_mode is Once.
This function is non-blocking. See 'set_angles' for the blocking counterpart.
Parameters
- int32_t gimbal_id -
- float roll_deg -
- float pitch_deg -
- float yaw_deg -
- GimbalMode gimbal_mode -
- SendMode send_mode -
- const ResultCallback callback -
set_angles() ​
Result mavsdk::Gimbal::set_angles(int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, GimbalMode gimbal_mode, SendMode send_mode) const
Set gimbal roll, pitch and yaw angles.
This sets the desired roll, pitch and yaw angles of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually be set to the new angles.
Note that the roll angle needs to be set to 0 when send_mode is Once.
This function is blocking. See 'set_angles_async' for the non-blocking counterpart.
Parameters
- int32_t gimbal_id -
- float roll_deg -
- float pitch_deg -
- float yaw_deg -
- GimbalMode gimbal_mode -
- SendMode send_mode -
Returns
 Result - Result of request.
set_angular_rates_async() ​
void mavsdk::Gimbal::set_angular_rates_async(int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, GimbalMode gimbal_mode, SendMode send_mode, const ResultCallback callback)
Set gimbal angular rates.
This sets the desired angular rates around roll, pitch and yaw axes of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually reach the angular rate.
Note that the roll angle needs to be set to 0 when send_mode is Once.
This function is non-blocking. See 'set_angular_rates' for the blocking counterpart.
Parameters
- int32_t gimbal_id -
- float roll_rate_deg_s -
- float pitch_rate_deg_s -
- float yaw_rate_deg_s -
- GimbalMode gimbal_mode -
- SendMode send_mode -
- const ResultCallback callback -
set_angular_rates() ​
Result mavsdk::Gimbal::set_angular_rates(int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, GimbalMode gimbal_mode, SendMode send_mode) const
Set gimbal angular rates.
This sets the desired angular rates around roll, pitch and yaw axes of a gimbal. Will return when the command is accepted, however, it might take the gimbal longer to actually reach the angular rate.
Note that the roll angle needs to be set to 0 when send_mode is Once.
This function is blocking. See 'set_angular_rates_async' for the non-blocking counterpart.
Parameters
- int32_t gimbal_id -
- float roll_rate_deg_s -
- float pitch_rate_deg_s -
- float yaw_rate_deg_s -
- GimbalMode gimbal_mode -
- SendMode send_mode -
Returns
 Result - Result of request.
set_roi_location_async() ​
void mavsdk::Gimbal::set_roi_location_async(int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback)
Set gimbal region of interest (ROI).
This sets a region of interest that the gimbal will point to. The gimbal will continue to point to the specified region until it receives a new command. The function will return when the command is accepted, however, it might take the gimbal longer to actually rotate to the ROI.
This function is non-blocking. See 'set_roi_location' for the blocking counterpart.
Parameters
- int32_t gimbal_id -
- double latitude_deg -
- double longitude_deg -
- float altitude_m -
- const ResultCallback callback -
set_roi_location() ​
Result mavsdk::Gimbal::set_roi_location(int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m) const
Set gimbal region of interest (ROI).
This sets a region of interest that the gimbal will point to. The gimbal will continue to point to the specified region until it receives a new command. The function will return when the command is accepted, however, it might take the gimbal longer to actually rotate to the ROI.
This function is blocking. See 'set_roi_location_async' for the non-blocking counterpart.
Parameters
- int32_t gimbal_id -
- double latitude_deg -
- double longitude_deg -
- float altitude_m -
Returns
 Result - Result of request.
take_control_async() ​
void mavsdk::Gimbal::take_control_async(int32_t gimbal_id, ControlMode control_mode, const ResultCallback callback)
Take control.
There can be only two components in control of a gimbal at any given time. One with "primary" control, and one with "secondary" control. The way the secondary control is implemented is not specified and hence depends on the vehicle.
Components are expected to be cooperative, which means that they can override each other and should therefore do it carefully.
This function is non-blocking. See 'take_control' for the blocking counterpart.
Parameters
- int32_t gimbal_id -
- ControlMode control_mode -
- const ResultCallback callback -
take_control() ​
Result mavsdk::Gimbal::take_control(int32_t gimbal_id, ControlMode control_mode) const
Take control.
There can be only two components in control of a gimbal at any given time. One with "primary" control, and one with "secondary" control. The way the secondary control is implemented is not specified and hence depends on the vehicle.
Components are expected to be cooperative, which means that they can override each other and should therefore do it carefully.
This function is blocking. See 'take_control_async' for the non-blocking counterpart.
Parameters
- int32_t gimbal_id -
- ControlMode control_mode -
Returns
 Result - Result of request.
release_control_async() ​
void mavsdk::Gimbal::release_control_async(int32_t gimbal_id, const ResultCallback callback)
Release control.
Release control, such that other components can control the gimbal.
This function is non-blocking. See 'release_control' for the blocking counterpart.
Parameters
- int32_t gimbal_id -
- const ResultCallback callback -
release_control() ​
Result mavsdk::Gimbal::release_control(int32_t gimbal_id) const
Release control.
Release control, such that other components can control the gimbal.
This function is blocking. See 'release_control_async' for the non-blocking counterpart.
Parameters
- int32_t gimbal_id -
Returns
 Result - Result of request.
subscribe_gimbal_list() ​
GimbalListHandle mavsdk::Gimbal::subscribe_gimbal_list(const GimbalListCallback &callback)
Subscribe to list of gimbals.
This allows to find out what gimbals are connected to the system. Based on the gimbal ID, we can then address a specific gimbal.
Parameters
- const GimbalListCallback& callback -
Returns
 GimbalListHandle -
unsubscribe_gimbal_list() ​
void mavsdk::Gimbal::unsubscribe_gimbal_list(GimbalListHandle handle)
Unsubscribe from subscribe_gimbal_list.
Parameters
- GimbalListHandle handle -
gimbal_list() ​
GimbalList mavsdk::Gimbal::gimbal_list() const
Poll for 'GimbalList' (blocking).
Returns
 GimbalList - One GimbalList update.
subscribe_control_status() ​
ControlStatusHandle mavsdk::Gimbal::subscribe_control_status(const ControlStatusCallback &callback)
Subscribe to control status updates.
This allows a component to know if it has primary, secondary or no control over the gimbal. Also, it gives the system and component ids of the other components in control (if any).
Parameters
- const ControlStatusCallback& callback -
Returns
 ControlStatusHandle -
unsubscribe_control_status() ​
void mavsdk::Gimbal::unsubscribe_control_status(ControlStatusHandle handle)
Unsubscribe from subscribe_control_status.
Parameters
- ControlStatusHandle handle -
get_control_status() ​
std::pair< Result, Gimbal::ControlStatus > mavsdk::Gimbal::get_control_status(int32_t gimbal_id) const
Get control status for specific gimbal.
This function is blocking.
Parameters
- int32_t gimbal_id -
Returns
 std::pair< Result, Gimbal::ControlStatus > - Result of request.
subscribe_attitude() ​
AttitudeHandle mavsdk::Gimbal::subscribe_attitude(const AttitudeCallback &callback)
Subscribe to attitude updates.
This gets you the gimbal's attitude and angular rate.
Parameters
- const AttitudeCallback& callback -
Returns
 AttitudeHandle -
unsubscribe_attitude() ​
void mavsdk::Gimbal::unsubscribe_attitude(AttitudeHandle handle)
Unsubscribe from subscribe_attitude.
Parameters
- AttitudeHandle handle -
get_attitude() ​
std::pair< Result, Gimbal::Attitude > mavsdk::Gimbal::get_attitude(int32_t gimbal_id) const
Get attitude for specific gimbal.
This function is blocking.
Parameters
- int32_t gimbal_id -
Returns
 std::pair< Result, Gimbal::Attitude > - Result of request.
operator=() ​
const Gimbal & mavsdk::Gimbal::operator=(const Gimbal &)=delete
Equality operator (object is not copyable).
Parameters
- const Gimbal& -
Returns
 const Gimbal & -