From e7e6e58fadad6751ead541b0290cbc0a95aa624d Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 10 Jan 2019 08:36:43 +1100 Subject: [PATCH] ApiRef for Info:Identification and Offboard:AttidueRate --- en/SUMMARY.md | 2 + en/api_reference/README.md | 2 + .../classdronecode__sdk_1_1_calibration.md | 10 +++ .../classdronecode__sdk_1_1_info.md | 82 +++++++++++++------ .../classdronecode__sdk_1_1_mission.md | 23 ++++++ .../classdronecode__sdk_1_1_offboard.md | 16 ++++ ...uctdronecode__sdk_1_1_camera_1_1_option.md | 8 +- ...ctdronecode__sdk_1_1_camera_1_1_setting.md | 12 +-- ...ode__sdk_1_1_camera_1_1_setting_options.md | 12 +-- ...necode__sdk_1_1_info_1_1_identification.md | 27 ++++++ ...tdronecode__sdk_1_1_log_files_1_1_entry.md | 12 +-- ...ode__sdk_1_1_offboard_1_1_attitude_rate.md | 63 ++++++++++++++ 12 files changed, 224 insertions(+), 45 deletions(-) create mode 100644 en/api_reference/structdronecode__sdk_1_1_info_1_1_identification.md create mode 100644 en/api_reference/structdronecode__sdk_1_1_offboard_1_1_attitude_rate.md diff --git a/en/SUMMARY.md b/en/SUMMARY.md index 0189319..5a46863 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -31,6 +31,7 @@ * [class Info](api_reference/classdronecode__sdk_1_1_info.md) * [struct Version](api_reference/structdronecode__sdk_1_1_info_1_1_version.md) * [struct Product](api_reference/structdronecode__sdk_1_1_info_1_1_product.md) + * [struct Identification](api_reference/structdronecode__sdk_1_1_info_1_1_identification.md) * [class Telemetry](api_reference/classdronecode__sdk_1_1_telemetry.md) * [struct Battery](api_reference/structdronecode__sdk_1_1_telemetry_1_1_battery.md) * [struct EulerAngle](api_reference/structdronecode__sdk_1_1_telemetry_1_1_euler_angle.md) @@ -47,6 +48,7 @@ * [class Mission](api_reference/classdronecode__sdk_1_1_mission.md) * [class MissionItem](api_reference/classdronecode__sdk_1_1_mission_item.md) * [class Offboard](api_reference/classdronecode__sdk_1_1_offboard.md) + * [struct AltitudeRate](api_reference/structdronecode__sdk_1_1_offboard_1_1_attitude_rate.md) * [struct VelocityBodyYawspeed](api_reference/structdronecode__sdk_1_1_offboard_1_1_velocity_body_yawspeed.md) * [struct VelocityNEDYaw](api_reference/structdronecode__sdk_1_1_offboard_1_1_velocity_n_e_d_yaw.md) * [class Gimbal](api_reference/classdronecode__sdk_1_1_gimbal.md) diff --git a/en/api_reference/README.md b/en/api_reference/README.md index 1d06d54..6312172 100644 --- a/en/api_reference/README.md +++ b/en/api_reference/README.md @@ -5,6 +5,7 @@ * [class Info](classdronecode__sdk_1_1_info.md) * [struct Version](structdronecode__sdk_1_1_info_1_1_version.md) * [struct Product](structdronecode__sdk_1_1_info_1_1_product.md) + * [struct Identification](structdronecode__sdk_1_1_info_1_1_identification.md) * [class Telemetry](classdronecode__sdk_1_1_telemetry.md) * [struct Battery](structdronecode__sdk_1_1_telemetry_1_1_battery.md) * [struct EulerAngle](structdronecode__sdk_1_1_telemetry_1_1_euler_angle.md) @@ -23,6 +24,7 @@ * [class Offboard](classdronecode__sdk_1_1_offboard.md) * [struct VelocityBodyYawspeed](structdronecode__sdk_1_1_offboard_1_1_velocity_body_yawspeed.md) * [struct VelocityNEDYaw](structdronecode__sdk_1_1_offboard_1_1_velocity_n_e_d_yaw.md) + * [struct AltitudeRate](structdronecode__sdk_1_1_offboard_1_1_attitude_rate.md) * [class Gimbal](classdronecode__sdk_1_1_gimbal.md) * [class Camera](classdronecode__sdk_1_1_camera.md) * [struct Information](structdronecode__sdk_1_1_camera_1_1_information.md) diff --git a/en/api_reference/classdronecode__sdk_1_1_calibration.md b/en/api_reference/classdronecode__sdk_1_1_calibration.md index 34ff80a..f3f309d 100644 --- a/en/api_reference/classdronecode__sdk_1_1_calibration.md +++ b/en/api_reference/classdronecode__sdk_1_1_calibration.md @@ -32,6 +32,7 @@ void | [calibrate_gyro_async](#classdronecode__sdk_1_1_calibration_1aa7ec9bc9ed6 void | [calibrate_accelerometer_async](#classdronecode__sdk_1_1_calibration_1ac82675b0235bc7ed8c0a3259739e0bea) ([calibration_callback_t](classdronecode__sdk_1_1_calibration.md#classdronecode__sdk_1_1_calibration_1a80de297cc0a8a77d81902cf765aa77a1) callback) | Perform accelerometer calibration (asynchronous call). void | [calibrate_magnetometer_async](#classdronecode__sdk_1_1_calibration_1ae69b7a5e7308f7f9176152a30ff9049f) ([calibration_callback_t](classdronecode__sdk_1_1_calibration.md#classdronecode__sdk_1_1_calibration_1a80de297cc0a8a77d81902cf765aa77a1) callback) | Perform magnetometer calibration (asynchronous call). void | [calibrate_gimbal_accelerometer_async](#classdronecode__sdk_1_1_calibration_1a1a5fe007db8e548b1305126a94f441af) ([calibration_callback_t](classdronecode__sdk_1_1_calibration.md#classdronecode__sdk_1_1_calibration_1a80de297cc0a8a77d81902cf765aa77a1) callback) | Perform gimbal accelerometer calibration (asynchronous call). +void | [cancel_calibration](#classdronecode__sdk_1_1_calibration_1af92b4f38751e701f68dfeca454e15737) () | Cancel ongoing calibration. const [Calibration](classdronecode__sdk_1_1_calibration.md) & | [operator=](#classdronecode__sdk_1_1_calibration_1a347cb2bc05828fc1cbb40bebfc50cabc) (const [Calibration](classdronecode__sdk_1_1_calibration.md) &)=delete | Equality operator (object is not copyable). ## Static Public Member Functions @@ -176,6 +177,15 @@ Perform gimbal accelerometer calibration (asynchronous call). * [calibration_callback_t](classdronecode__sdk_1_1_calibration.md#classdronecode__sdk_1_1_calibration_1a80de297cc0a8a77d81902cf765aa77a1) **callback** - Function to receive result and progress of calibration. +### cancel_calibration() {#classdronecode__sdk_1_1_calibration_1af92b4f38751e701f68dfeca454e15737} +```cpp +void dronecode_sdk::Calibration::cancel_calibration() +``` + + +Cancel ongoing calibration. + + ### operator=() {#classdronecode__sdk_1_1_calibration_1a347cb2bc05828fc1cbb40bebfc50cabc} ```cpp const Calibration& dronecode_sdk::Calibration::operator=(const Calibration &)=delete diff --git a/en/api_reference/classdronecode__sdk_1_1_info.md b/en/api_reference/classdronecode__sdk_1_1_info.md index b46f581..0c6b4b6 100644 --- a/en/api_reference/classdronecode__sdk_1_1_info.md +++ b/en/api_reference/classdronecode__sdk_1_1_info.md @@ -10,10 +10,19 @@ The [Info](classdronecode__sdk_1_1_info.md) class provides basic infomation abou ## Data Structures +struct [Identification](structdronecode__sdk_1_1_info_1_1_identification.md) + struct [Product](structdronecode__sdk_1_1_info_1_1_product.md) struct [Version](structdronecode__sdk_1_1_info_1_1_version.md) +## Public Types + + +Type | Description +--- | --- +enum [Result](#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9) | Possible results returned for requests. + ## Public Member Functions @@ -22,10 +31,9 @@ Type | Name | Description   | [Info](#classdronecode__sdk_1_1_info_1ae943f4e7d0ca0bfd07a9eeb51f70dc31) ([System](classdronecode__sdk_1_1_system.md) & system) | Constructor. Creates the plugin for a specific [System](classdronecode__sdk_1_1_system.md).   | [~Info](#classdronecode__sdk_1_1_info_1a65fa131293c5a567ad8c410bae6b8c25) () | Destructor (internal use only).   | [Info](#classdronecode__sdk_1_1_info_1a157860dd0494775070965393a4dbf40a) (const [Info](classdronecode__sdk_1_1_info.md) &)=delete | Copy Constructor (object is not copyable). -uint64_t | [uuid](#classdronecode__sdk_1_1_info_1a38f1b08ee69a4dbfc22a79ddf6a20ce4) () const | Gets the UUID of the system. -bool | [is_complete](#classdronecode__sdk_1_1_info_1ae62c038fbdc9745a30d4a74954ed5e2d) () const | Tests if the [Version](structdronecode__sdk_1_1_info_1_1_version.md) and [Product](structdronecode__sdk_1_1_info_1_1_product.md) objects are fully populated from hardware. -[Version](structdronecode__sdk_1_1_info_1_1_version.md) | [get_version](#classdronecode__sdk_1_1_info_1aa6a391957d79965ee6ac98b94f189655) () const | Get system version information. -[Product](structdronecode__sdk_1_1_info_1_1_product.md) | [get_product](#classdronecode__sdk_1_1_info_1a219585dff33dd305fd22ee7f741a7f2a) () const | Get system product information. +std::pair< [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9), [Identification](structdronecode__sdk_1_1_info_1_1_identification.md) > | [get_identification](#classdronecode__sdk_1_1_info_1aedebb22d4c5951f80d68b3c99457fc67) () const | Gets the identification of the system. +std::pair< [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9), [Version](structdronecode__sdk_1_1_info_1_1_version.md) > | [get_version](#classdronecode__sdk_1_1_info_1ac61216d58d9f806b2f0c86061a449a55) () const | Get system version information. +std::pair< [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9), [Product](structdronecode__sdk_1_1_info_1_1_product.md) > | [get_product](#classdronecode__sdk_1_1_info_1aa1102ede7d9b6edaf33396ee17e12859) () const | Get system product information. const [Info](classdronecode__sdk_1_1_info.md) & | [operator=](#classdronecode__sdk_1_1_info_1a7b19c97d51e77ac7eafa69418677b578) (const [Info](classdronecode__sdk_1_1_info.md) &)=delete | Equality operator (object is not copyable). ## Static Public Attributes @@ -34,6 +42,14 @@ const [Info](classdronecode__sdk_1_1_info.md) & | [operator=](#classdronecode__s static const unsigned [GIT_HASH_STR_LEN](#classdronecode__sdk_1_1_info_1aa708e5ebc77ebce409a1c4c3bef7cc98) = 17 - Length of git hash strings. +## Static Public Member Functions + + +Type | Name | Description +---: | --- | --- +std::string | [result_str](#classdronecode__sdk_1_1_info_1ac28cc1d3d0f2715f5209106b327a5c9f) ([Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9) result) | Returns a human-readable English string for an Result. + + ## Constructor & Destructor Documentation @@ -77,39 +93,42 @@ Copy Constructor (object is not copyable). * const [Info](classdronecode__sdk_1_1_info.md)& - -## Member Function Documentation +## Member Enumeration Documentation -### uuid() {#classdronecode__sdk_1_1_info_1a38f1b08ee69a4dbfc22a79ddf6a20ce4} -```cpp -uint64_t dronecode_sdk::Info::uuid() const -``` +### enum Result {#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9} -Gets the UUID of the system. +Possible results returned for requests. -If possible this will be a unique identifier provided by hardware. +> **Note** [DronecodeSDK](classdronecode__sdk_1_1_dronecode_s_d_k.md) does not throw exceptions. Instead a result of this type will be returned. -**Returns** +Value | Description +--- | --- + `UNKNOWN` | Unspecified error. + `SUCCESS` | The request was successful. + `INFORMATION_NOT_RECEIVED_YET` | The information has not been received yet. + +## Member Function Documentation - uint64_t - The UUID of the system. -### is_complete() {#classdronecode__sdk_1_1_info_1ae62c038fbdc9745a30d4a74954ed5e2d} +### get_identification() {#classdronecode__sdk_1_1_info_1aedebb22d4c5951f80d68b3c99457fc67} ```cpp -bool dronecode_sdk::Info::is_complete() const +std::pair dronecode_sdk::Info::get_identification() const ``` -Tests if the [Version](structdronecode__sdk_1_1_info_1_1_version.md) and [Product](structdronecode__sdk_1_1_info_1_1_product.md) objects are fully populated from hardware. +Gets the identification of the system. +If possible this will be a unique identifier provided by hardware. **Returns** - bool - `true` if [Version](structdronecode__sdk_1_1_info_1_1_version.md) and [Product](structdronecode__sdk_1_1_info_1_1_product.md) objects are fully populated from system. + std::pair< [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9), [Identification](structdronecode__sdk_1_1_info_1_1_identification.md) > - a pair containing the result of the request and if successful, the identification information of the system. -### get_version() {#classdronecode__sdk_1_1_info_1aa6a391957d79965ee6ac98b94f189655} +### get_version() {#classdronecode__sdk_1_1_info_1ac61216d58d9f806b2f0c86061a449a55} ```cpp -Version dronecode_sdk::Info::get_version() const +std::pair dronecode_sdk::Info::get_version() const ``` @@ -118,11 +137,11 @@ Get system version information. **Returns** - [Version](structdronecode__sdk_1_1_info_1_1_version.md) - The version object for the system. + std::pair< [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9), [Version](structdronecode__sdk_1_1_info_1_1_version.md) > - a pair containing the result of the request and if successful, the version information about the system. -### get_product() {#classdronecode__sdk_1_1_info_1a219585dff33dd305fd22ee7f741a7f2a} +### get_product() {#classdronecode__sdk_1_1_info_1aa1102ede7d9b6edaf33396ee17e12859} ```cpp -Product dronecode_sdk::Info::get_product() const +std::pair dronecode_sdk::Info::get_product() const ``` @@ -131,7 +150,7 @@ Get system product information. **Returns** - [Product](structdronecode__sdk_1_1_info_1_1_product.md) - The product object for the system. + std::pair< [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9), [Product](structdronecode__sdk_1_1_info_1_1_product.md) > - a pair containing the result of the request and if successful, the product information about the system. ### operator=() {#classdronecode__sdk_1_1_info_1a7b19c97d51e77ac7eafa69418677b578} ```cpp @@ -150,6 +169,23 @@ Equality operator (object is not copyable).  const [Info](classdronecode__sdk_1_1_info.md) & - +### result_str() {#classdronecode__sdk_1_1_info_1ac28cc1d3d0f2715f5209106b327a5c9f} +```cpp +static std::string dronecode_sdk::Info::result_str(Result result) +``` + + +Returns a human-readable English string for an Result. + + +**Parameters** + +* [Result](classdronecode__sdk_1_1_info.md#classdronecode__sdk_1_1_info_1ae09075d43cda9c7b617dbcb01102eee9) **result** - The enum value for which a human readable string is required. + +**Returns** + + std::string - Human readable string for the Result. + ## Field Documentation diff --git a/en/api_reference/classdronecode__sdk_1_1_mission.md b/en/api_reference/classdronecode__sdk_1_1_mission.md index c93043c..a918cdc 100644 --- a/en/api_reference/classdronecode__sdk_1_1_mission.md +++ b/en/api_reference/classdronecode__sdk_1_1_mission.md @@ -27,7 +27,9 @@ Type | Name | Description   | [~Mission](#classdronecode__sdk_1_1_mission_1a21637e7a71c29a95f573a5c44ee0bd26) () | Destructor (internal use only).   | [Mission](#classdronecode__sdk_1_1_mission_1a1fbfbebf4812b806af482188490f12a1) (const [Mission](classdronecode__sdk_1_1_mission.md) &)=delete | Copy constructor (object is not copyable). void | [upload_mission_async](#classdronecode__sdk_1_1_mission_1abe18ceecd0afba9c109ed216c77212f0) (const std::vector< std::shared_ptr< [MissionItem](classdronecode__sdk_1_1_mission_item.md) >> & mission_items, [result_callback_t](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1adab3125b28a8d7b7ed90a81ea56b0115) callback) | Uploads a vector of mission items to the system (asynchronous). +void | [upload_mission_cancel](#classdronecode__sdk_1_1_mission_1a86cfb102df0d17c57bc5a6d1a3fdfdd0) () | Cancel a mission upload (asynchronous). void | [download_mission_async](#classdronecode__sdk_1_1_mission_1a786b73a354af0b45b75caa36d197c336) ([mission_items_and_result_callback_t](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1a319a5311e997cf351557e8663abc7d84) callback) | Downloads a vector of mission items from the system (asynchronous). +void | [download_mission_cancel](#classdronecode__sdk_1_1_mission_1af60c8a7f3f8bea6abe77e3986d85d11b) () | Cancel a mission download (asynchronous). void | [set_return_to_launch_after_mission](#classdronecode__sdk_1_1_mission_1af7059e3e2ea1b7ee86591815c28922e7) (bool enable) | Set whether to trigger Return-to-Launch (RTL) after mission is complete. bool | [get_return_to_launch_after_mission](#classdronecode__sdk_1_1_mission_1a891af41a68131c5e5053cbdc1606edd4) () | Get whether to trigger Return-to-Launch (RTL) after mission is complete. void | [start_mission_async](#classdronecode__sdk_1_1_mission_1aa4bfbd0e5e06692a96f0301fbe7bbbc3) ([result_callback_t](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1adab3125b28a8d7b7ed90a81ea56b0115) callback) | Starts the mission (asynchronous). @@ -163,6 +165,7 @@ Value | Description `FAILED_TO_OPEN_QGC_PLAN` | Failed to open QGroundControl plan. `FAILED_TO_PARSE_QGC_PLAN` | Failed to parse QGroundControl plan. `UNSUPPORTED_MISSION_CMD` | Unsupported mission command. + `CANCELLED` | [Mission](classdronecode__sdk_1_1_mission.md) upload or download has been cancelled. ## Member Function Documentation @@ -182,6 +185,16 @@ The mission items are uploaded to a drone. Once uploaded the mission can be star * const std::vector< std::shared_ptr< [MissionItem](classdronecode__sdk_1_1_mission_item.md) >>& **mission_items** - Reference to vector of mission items. * [result_callback_t](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1adab3125b28a8d7b7ed90a81ea56b0115) **callback** - Callback to receive result of this request. +### upload_mission_cancel() {#classdronecode__sdk_1_1_mission_1a86cfb102df0d17c57bc5a6d1a3fdfdd0} +```cpp +void dronecode_sdk::Mission::upload_mission_cancel() +``` + + +Cancel a mission upload (asynchronous). + +This cancels an ongoing mission upload. The mission upload will fail with the result [Result::CANCELLED](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1a819b8fdcf5a49f76e690c2c16adf572da9f935beb31030ad0d4d26126c0f39bf2). + ### download_mission_async() {#classdronecode__sdk_1_1_mission_1a786b73a354af0b45b75caa36d197c336} ```cpp void dronecode_sdk::Mission::download_mission_async(mission_items_and_result_callback_t callback) @@ -196,6 +209,16 @@ The method will fail if any of the downloaded mission items are not supported by * [mission_items_and_result_callback_t](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1a319a5311e997cf351557e8663abc7d84) **callback** - Callback to receive mission items and result of this request. +### download_mission_cancel() {#classdronecode__sdk_1_1_mission_1af60c8a7f3f8bea6abe77e3986d85d11b} +```cpp +void dronecode_sdk::Mission::download_mission_cancel() +``` + + +Cancel a mission download (asynchronous). + +This cancels an ongoing mission download. The mission download will fail with the result [Result::CANCELLED](classdronecode__sdk_1_1_mission.md#classdronecode__sdk_1_1_mission_1a819b8fdcf5a49f76e690c2c16adf572da9f935beb31030ad0d4d26126c0f39bf2). + ### set_return_to_launch_after_mission() {#classdronecode__sdk_1_1_mission_1af7059e3e2ea1b7ee86591815c28922e7} ```cpp void dronecode_sdk::Mission::set_return_to_launch_after_mission(bool enable) diff --git a/en/api_reference/classdronecode__sdk_1_1_offboard.md b/en/api_reference/classdronecode__sdk_1_1_offboard.md index e4cb5df..3793850 100644 --- a/en/api_reference/classdronecode__sdk_1_1_offboard.md +++ b/en/api_reference/classdronecode__sdk_1_1_offboard.md @@ -19,6 +19,8 @@ Client code must specify a setpoint before starting offboard mode. [DronecodeSDK ## Data Structures +struct [AttitudeRate](structdronecode__sdk_1_1_offboard_1_1_attitude_rate.md) + struct [VelocityBodyYawspeed](structdronecode__sdk_1_1_offboard_1_1_velocity_body_yawspeed.md) struct [VelocityNEDYaw](structdronecode__sdk_1_1_offboard_1_1_velocity_n_e_d_yaw.md) @@ -46,6 +48,7 @@ void | [stop_async](#classdronecode__sdk_1_1_offboard_1a2ff3262dbc6194def28bb9b3 bool | [is_active](#classdronecode__sdk_1_1_offboard_1ac3c75fcd1ae1e6b00090eccd03696479) () const | Check if offboard control is active. void | [set_velocity_ned](#classdronecode__sdk_1_1_offboard_1a95dfbe096a363e21bfd035258e786350) ([VelocityNEDYaw](structdronecode__sdk_1_1_offboard_1_1_velocity_n_e_d_yaw.md) velocity_ned_yaw) | Set the velocity in NED coordinates and yaw. void | [set_velocity_body](#classdronecode__sdk_1_1_offboard_1ad87778386509911269b87766c0f1830f) ([VelocityBodyYawspeed](structdronecode__sdk_1_1_offboard_1_1_velocity_body_yawspeed.md) velocity_body_yawspeed) | Set the velocity body coordinates and yaw angular rate. +void | [set_attitude_rate](#classdronecode__sdk_1_1_offboard_1a511ba0314a4217c3ac3020ab2b0dfd23) ([AttitudeRate](structdronecode__sdk_1_1_offboard_1_1_attitude_rate.md) attitude_rate) | Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust in percentage. const [Offboard](classdronecode__sdk_1_1_offboard.md) & | [operator=](#classdronecode__sdk_1_1_offboard_1a8cfbf6cbcb4fbdcf1574f0455632a372) (const [Offboard](classdronecode__sdk_1_1_offboard.md) &)=delete | Equality operator (object is not copyable). ## Static Public Member Functions @@ -231,6 +234,19 @@ Set the velocity body coordinates and yaw angular rate. * [VelocityBodyYawspeed](structdronecode__sdk_1_1_offboard_1_1_velocity_body_yawspeed.md) **velocity_body_yawspeed** - Velocity and yaw angular rate `struct`. +### set_attitude_rate() {#classdronecode__sdk_1_1_offboard_1a511ba0314a4217c3ac3020ab2b0dfd23} +```cpp +void dronecode_sdk::Offboard::set_attitude_rate(AttitudeRate attitude_rate) +``` + + +Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust in percentage. + + +**Parameters** + +* [AttitudeRate](structdronecode__sdk_1_1_offboard_1_1_attitude_rate.md) **attitude_rate** - roll, pitch and yaw angular rate along with thrust in percentage. + ### operator=() {#classdronecode__sdk_1_1_offboard_1a8cfbf6cbcb4fbdcf1574f0455632a372} ```cpp const Offboard& dronecode_sdk::Offboard::operator=(const Offboard &)=delete diff --git a/en/api_reference/structdronecode__sdk_1_1_camera_1_1_option.md b/en/api_reference/structdronecode__sdk_1_1_camera_1_1_option.md index 470e816..15cf4ae 100644 --- a/en/api_reference/structdronecode__sdk_1_1_camera_1_1_option.md +++ b/en/api_reference/structdronecode__sdk_1_1_camera_1_1_option.md @@ -13,9 +13,9 @@ This can be e.g. a color mode option such as "enhanced" or a shutter speed value ## Data Fields -std::string [option_id](#structdronecode__sdk_1_1_camera_1_1_option_1a23d684bc8348a9b2bdcbfe9902ff0ec6) - +std::string [option_id](#structdronecode__sdk_1_1_camera_1_1_option_1a23d684bc8348a9b2bdcbfe9902ff0ec6) {} - -std::string [option_description](#structdronecode__sdk_1_1_camera_1_1_option_1a5f2f77d74a3bbc7e0c890b0289720973) - +std::string [option_description](#structdronecode__sdk_1_1_camera_1_1_option_1a5f2f77d74a3bbc7e0c890b0289720973) {} - ## Field Documentation @@ -24,7 +24,7 @@ std::string [option_description](#structdronecode__sdk_1_1_camera_1_1_option_1a5 ### option_id {#structdronecode__sdk_1_1_camera_1_1_option_1a23d684bc8348a9b2bdcbfe9902ff0ec6} ```cpp -std::string dronecode_sdk::Camera::Option::option_id +std::string dronecode_sdk::Camera::Option::option_id {} ``` @@ -33,7 +33,7 @@ Name of the option (machine readable). ### option_description {#structdronecode__sdk_1_1_camera_1_1_option_1a5f2f77d74a3bbc7e0c890b0289720973} ```cpp -std::string dronecode_sdk::Camera::Option::option_description +std::string dronecode_sdk::Camera::Option::option_description {} ``` diff --git a/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting.md b/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting.md index d919ffb..7f50bde 100644 --- a/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting.md +++ b/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting.md @@ -10,11 +10,11 @@ Type to represent a setting with a selected option. ## Data Fields -std::string [setting_id](#structdronecode__sdk_1_1_camera_1_1_setting_1a4c21b05f03f7dccc961e79d016cfd818) - +std::string [setting_id](#structdronecode__sdk_1_1_camera_1_1_setting_1a4c21b05f03f7dccc961e79d016cfd818) {} - -std::string [setting_description](#structdronecode__sdk_1_1_camera_1_1_setting_1ace77f5c2a4d2494b42beb05bfb74961f) - +std::string [setting_description](#structdronecode__sdk_1_1_camera_1_1_setting_1ace77f5c2a4d2494b42beb05bfb74961f) {} - -[Option](structdronecode__sdk_1_1_camera_1_1_option.md) [option](#structdronecode__sdk_1_1_camera_1_1_setting_1a1c115fa196f39762e8f6fb6c0326629c) - +[Option](structdronecode__sdk_1_1_camera_1_1_option.md) [option](#structdronecode__sdk_1_1_camera_1_1_setting_1a1c115fa196f39762e8f6fb6c0326629c) {} - ## Field Documentation @@ -23,7 +23,7 @@ std::string [setting_description](#structdronecode__sdk_1_1_camera_1_1_setting_1 ### setting_id {#structdronecode__sdk_1_1_camera_1_1_setting_1a4c21b05f03f7dccc961e79d016cfd818} ```cpp -std::string dronecode_sdk::Camera::Setting::setting_id +std::string dronecode_sdk::Camera::Setting::setting_id {} ``` @@ -32,7 +32,7 @@ Name of the setting (machine readable). ### setting_description {#structdronecode__sdk_1_1_camera_1_1_setting_1ace77f5c2a4d2494b42beb05bfb74961f} ```cpp -std::string dronecode_sdk::Camera::Setting::setting_description +std::string dronecode_sdk::Camera::Setting::setting_description {} ``` @@ -41,7 +41,7 @@ Description of the setting (human readable). ### option {#structdronecode__sdk_1_1_camera_1_1_setting_1a1c115fa196f39762e8f6fb6c0326629c} ```cpp -Option dronecode_sdk::Camera::Setting::option +Option dronecode_sdk::Camera::Setting::option {} ``` diff --git a/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting_options.md b/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting_options.md index 905eff8..e2c16ae 100644 --- a/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting_options.md +++ b/en/api_reference/structdronecode__sdk_1_1_camera_1_1_setting_options.md @@ -10,11 +10,11 @@ Type to represent a setting with a list of options to choose from. ## Data Fields -std::string [setting_id](#structdronecode__sdk_1_1_camera_1_1_setting_options_1a96c7ddf5a335f0ac08cdb1c7e3ebb8cc) - +std::string [setting_id](#structdronecode__sdk_1_1_camera_1_1_setting_options_1a96c7ddf5a335f0ac08cdb1c7e3ebb8cc) {} - -std::string [setting_description](#structdronecode__sdk_1_1_camera_1_1_setting_options_1ad6e0999aebaab4f12e944742bd668dcb) - +std::string [setting_description](#structdronecode__sdk_1_1_camera_1_1_setting_options_1ad6e0999aebaab4f12e944742bd668dcb) {} - -std::vector< [Option](structdronecode__sdk_1_1_camera_1_1_option.md) > [options](#structdronecode__sdk_1_1_camera_1_1_setting_options_1a143768fc2ac553119141e293f736eb9f) - +std::vector< [Option](structdronecode__sdk_1_1_camera_1_1_option.md) > [options](#structdronecode__sdk_1_1_camera_1_1_setting_options_1a143768fc2ac553119141e293f736eb9f) {} - ## Field Documentation @@ -23,7 +23,7 @@ std::vector< [Option](structdronecode__sdk_1_1_camera_1_1_option.md) > [options] ### setting_id {#structdronecode__sdk_1_1_camera_1_1_setting_options_1a96c7ddf5a335f0ac08cdb1c7e3ebb8cc} ```cpp -std::string dronecode_sdk::Camera::SettingOptions::setting_id +std::string dronecode_sdk::Camera::SettingOptions::setting_id {} ``` @@ -32,7 +32,7 @@ Name of the setting (machine readable). ### setting_description {#structdronecode__sdk_1_1_camera_1_1_setting_options_1ad6e0999aebaab4f12e944742bd668dcb} ```cpp -std::string dronecode_sdk::Camera::SettingOptions::setting_description +std::string dronecode_sdk::Camera::SettingOptions::setting_description {} ``` @@ -41,7 +41,7 @@ Description of the setting (human readable). ### options {#structdronecode__sdk_1_1_camera_1_1_setting_options_1a143768fc2ac553119141e293f736eb9f} ```cpp -std::vector