diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 51c86451ad..76ecb779d3 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -229,6 +229,22 @@ jobs: - name: check for diff run: git diff --exit-code + ubuntu24-docs-check: + name: ubuntu-24.04 (docs check) + runs-on: ubuntu-24.04 + steps: + - uses: actions/checkout@v4 + with: + submodules: recursive + - name: Install doxygen + run: | + sudo apt-get update + sudo apt-get install -y doxygen + - name: generate docs + run: tools/generate_docs.sh --overwrite + - name: check for diff + run: git diff --exit-code + deb-package: name: ${{ matrix.container_name }} (package, non-mavsdk_server) runs-on: ${{ matrix.container_name }} diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 43d27797f5..2d403b6a27 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -35,47 +35,74 @@ * [API Reference](cpp/api_reference/index.md) * [class Action](cpp/api_reference/classmavsdk_1_1_action.md) * [class ActionServer](cpp/api_reference/classmavsdk_1_1_action_server.md) - * [struct AllowableFlightModes](cpp/api_reference/structmavsdk_1_1_action_server_1_1_allowable_flight_modes.md) - * [struct ArmDisarm](cpp/api_reference/structmavsdk_1_1_action_server_1_1_arm_disarm.md) + * [struct AllowableFlightModes](cpp/api_reference/structmavsdk_1_1_action_server_1_1_allowable_flight_modes.md) + * [struct ArmDisarm](cpp/api_reference/structmavsdk_1_1_action_server_1_1_arm_disarm.md) + * [class ArmAuthorizerServer](cpp/api_reference/classmavsdk_1_1_arm_authorizer_server.md) * [class Calibration](cpp/api_reference/classmavsdk_1_1_calibration.md) * [struct ProgressData](cpp/api_reference/structmavsdk_1_1_calibration_1_1_progress_data.md) * [class Camera](cpp/api_reference/classmavsdk_1_1_camera.md) - * [struct Information](cpp/api_reference/structmavsdk_1_1_camera_1_1_information.md) + * [struct CameraList](cpp/api_reference/structmavsdk_1_1_camera_1_1_camera_list.md) * [struct CaptureInfo](cpp/api_reference/structmavsdk_1_1_camera_1_1_capture_info.md) - * [struct Position](cpp/api_reference/structmavsdk_1_1_camera_1_1_position.md) - * [struct Quaternion](cpp/api_reference/structmavsdk_1_1_camera_1_1_quaternion.md) + * [struct CurrentSettingsUpdate](structmavsdk_1_1_camera_1_1_current_settings_update.md) * [struct EulerAngle](cpp/api_reference/structmavsdk_1_1_camera_1_1_euler_angle.md) - * [struct Status](cpp/api_reference/structmavsdk_1_1_camera_1_1_status.md) - * [struct VideoStreamInfo](cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_info.md) - * [struct VideoStreamSettings](cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_settings.md) + * [struct Information](cpp/api_reference/structmavsdk_1_1_camera_1_1_information.md) + * [struct ModeUpdate](cpp/api_reference/structmavsdk_1_1_camera_1_1_mode_update.md) * [struct Option](cpp/api_reference/structmavsdk_1_1_camera_1_1_option.md) + * [struct Position](cpp/api_reference/structmavsdk_1_1_camera_1_1_position.md) + * [struct PossibleSettingOptionsUpdate](cpp/api_reference/structmavsdk_1_1_camera_1_1_possible_setting_options_update.md) + * [struct Quaternion](cpp/api_reference/structmavsdk_1_1_camera_1_1_quaternion.md) * [struct Setting](cpp/api_reference/structmavsdk_1_1_camera_1_1_setting.md) * [struct SettingOptions](cpp/api_reference/structmavsdk_1_1_camera_1_1_setting_options.md) - * [class CameraServer](cpp/api_reference/classmavsdk_1_1_camera_server.md) - * [struct CaptureInfo](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_info.md) - * [struct Information](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_information.md) - * [struct Position](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_position.md) - * [struct Quaternion](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_quaternion.md) - * [class ComponentInformation](cpp/api_reference/classmavsdk_1_1_component_information.md) - * [struct FloatParam](cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param.md) - * [struct FloatParamUpdate](cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param_update.md) - * [class ComponentInformationServer](cpp/api_reference/classmavsdk_1_1_component_information_server.md) - * [struct FloatParam](cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param.md) - * [struct FloatParamUpdate](cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param_update.md) + * [struct Storage](cpp/api_reference/structmavsdk_1_1_camera_1_1_storage.md) + * [struct StorageUpdate](cpp/api_reference/structmavsdk_1_1_camera_1_1_storage_update.md) + * [struct VideoStreamInfo](cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_info.md) + * [struct VideoStreamSettings](cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_settings.md) + * [struct VideoStreamUpdate](cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_update.md) + * [class CameraServer](cpp/api_reference/classmavsdk_1_1_camera_server.md) + * [struct CaptureInfo](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_info.md) + * [struct CaptureStatus](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_status.md) + * [struct Information](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_information.md) + * [struct Position](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_position.md) + * [struct Quaternion](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_quaternion.md) + * [struct StorageInformation](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_storage_information.md) + * [struct TrackPoint](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_point.md) + * [struct TrackRectangle](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_rectangle.md) + * [struct VideoStreaming](cpp/api_reference/structmavsdk_1_1_camera_server_1_1_video_streaming.md) + * [class ComponentMetadata](cpp/api_reference/classmavsdk_1_1_component_metadata.md) + * [struct MetadataData](cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_data.md) + * [struct MetadataUpdate](cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_update.md) + * [class ComponentMetadataServer](cpp/api_reference/classmavsdk_1_1_component_metadata_server.md) + * [struct Metadata](cpp/api_reference/structmavsdk_1_1_component_metadata_server_1_1_metadata.md) + * [class Events](cpp/api_reference/classmavsdk_1_1_events.md) + * [struct Event](cpp/api_reference/structmavsdk_1_1_events_1_1_event.md) + * [struct HealthArmingCheckMode](cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_mode.md) + * [struct HealthArmingCheckProblem](cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md) + * [struct HealthArmingCheckReport](cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_report.md) + * [struct HealthComponentReport](cpp/api_reference/structmavsdk_1_1_events_1_1_health_component_report.md) * [class Failure](cpp/api_reference/classmavsdk_1_1_failure.md) * [class FollowMe](cpp/api_reference/classmavsdk_1_1_follow_me.md) * [struct Config](cpp/api_reference/structmavsdk_1_1_follow_me_1_1_config.md) * [struct TargetLocation](cpp/api_reference/structmavsdk_1_1_follow_me_1_1_target_location.md) * [class Ftp](cpp/api_reference/classmavsdk_1_1_ftp.md) + * [struct ListDirectoryData](cpp/api_reference/structmavsdk_1_1_ftp_1_1_list_directory_data.md) + * [struct ProgressData](cpp/api_reference/structmavsdk_1_1_ftp_1_1_progress_data.md) + * [class FtpServer](cpp/api_reference/classmavsdk_1_1_ftp_server.md) * [class Geofence](cpp/api_reference/classmavsdk_1_1_geofence.md) - * [struct Polygon](cpp/api_reference/structmavsdk_1_1_geofence_1_1_polygon.md) + * [struct Circle](cpp/api_reference/structmavsdk_1_1_geofence_1_1_circle.md) + * [struct GeofenceData](cpp/api_reference/structmavsdk_1_1_geofence_1_1_geofence_data.md) * [struct Point](cpp/api_reference/structmavsdk_1_1_geofence_1_1_point.md) - * [struct ProgressData](cpp/api_reference/structmavsdk_1_1_ftp_1_1_progress_data.md) + * [struct Polygon](cpp/api_reference/structmavsdk_1_1_geofence_1_1_polygon.md) * [class geometry::CoordinateTransformation](cpp/api_reference/classmavsdk_1_1geometry_1_1_coordinate_transformation.md) * [struct GlobalCoordinate](cpp/api_reference/structmavsdk_1_1geometry_1_1_coordinate_transformation_1_1_global_coordinate.md) * [struct LocalCoordinate](cpp/api_reference/structmavsdk_1_1geometry_1_1_coordinate_transformation_1_1_local_coordinate.md) * [class Gimbal](cpp/api_reference/classmavsdk_1_1_gimbal.md) + * [struct AngularVelocityBody](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_angular_velocity_body.md) + * [struct Attitude](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_attitude.md) * [struct ControlStatus](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_control_status.md) + * [struct EulerAngle](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_euler_angle.md) + * [struct GimbalItem](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_item.md) + * [struct GimbalList](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_list.md) + * [struct Quaternion](cpp/api_reference/structmavsdk_1_1_gimbal_1_1_quaternion.md) * [class Info](cpp/api_reference/classmavsdk_1_1_info.md) * [struct FlightInfo](cpp/api_reference/structmavsdk_1_1_info_1_1_flight_info.md) * [struct Identification](cpp/api_reference/structmavsdk_1_1_info_1_1_identification.md) @@ -84,12 +111,15 @@ * [class LogFiles](cpp/api_reference/classmavsdk_1_1_log_files.md) * [struct Entry](cpp/api_reference/structmavsdk_1_1_log_files_1_1_entry.md) * [struct ProgressData](cpp/api_reference/structmavsdk_1_1_log_files_1_1_progress_data.md) + * [class LogStreaming](cpp/api_reference/classmavsdk_1_1_log_streaming.md) + * [struct LogStreamingRaw](cpp/api_reference/structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md) * [class ManualControl](cpp/api_reference/classmavsdk_1_1_manual_control.md) * [class MavlinkPassthrough](cpp/api_reference/classmavsdk_1_1_mavlink_passthrough.md) * [struct CommandInt](cpp/api_reference/structmavsdk_1_1_mavlink_passthrough_1_1_command_int.md) * [struct CommandLong](cpp/api_reference/structmavsdk_1_1_mavlink_passthrough_1_1_command_long.md) * [class Mavsdk](cpp/api_reference/classmavsdk_1_1_mavsdk.md) * [class Mavsdk::Configuration](cpp/api_reference/classmavsdk_1_1_mavsdk_1_1_configuration.md) + * [struct Mavsdk::ConnectionError](cpp/api_reference/structmavsdk_1_1_mavsdk_1_1_connection_error.md) * [class Mission](cpp/api_reference/classmavsdk_1_1_mission.md) * [struct MissionItem](cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_item.md) * [struct MissionPlan](cpp/api_reference/structmavsdk_1_1_mission_1_1_mission_plan.md) @@ -116,14 +146,14 @@ * [struct VisionPositionEstimate](cpp/api_reference/structmavsdk_1_1_mocap_1_1_vision_position_estimate.md) * [class Offboard](cpp/api_reference/classmavsdk_1_1_offboard.md) * [struct AccelerationNed](cpp/api_reference/structmavsdk_1_1_offboard_1_1_acceleration_ned.md) - * [struct ActuatorControl](cpp/api_reference/structmavsdk_1_1_offboard_1_1_actuator_control.md) * [struct ActuatorControlGroup](cpp/api_reference/structmavsdk_1_1_offboard_1_1_actuator_control_group.md) + * [struct ActuatorControl](cpp/api_reference/structmavsdk_1_1_offboard_1_1_actuator_control.md) * [struct Attitude](cpp/api_reference/structmavsdk_1_1_offboard_1_1_attitude.md) * [struct AttitudeRate](cpp/api_reference/structmavsdk_1_1_offboard_1_1_attitude_rate.md) + * [struct PositionGlobalYaw](cpp/api_reference/structmavsdk_1_1_offboard_1_1_position_global_yaw.md) + * [struct PositionNedYaw](cpp/api_reference/structmavsdk_1_1_offboard_1_1_position_ned_yaw.md) * [struct VelocityBodyYawspeed](cpp/api_reference/structmavsdk_1_1_offboard_1_1_velocity_body_yawspeed.md) * [struct VelocityNedYaw](cpp/api_reference/structmavsdk_1_1_offboard_1_1_velocity_ned_yaw.md) - * [struct PositionNedYaw](cpp/api_reference/structmavsdk_1_1_offboard_1_1_position_ned_yaw.md) - * [struct PositionGlobalYaw](cpp/api_reference/structmavsdk_1_1_offboard_1_1_position_global_yaw.md) * [class Param](cpp/api_reference/classmavsdk_1_1_param.md) * [struct AllParams](cpp/api_reference/structmavsdk_1_1_param_1_1_all_params.md) * [struct CustomParam](cpp/api_reference/structmavsdk_1_1_param_1_1_custom_param.md) @@ -134,16 +164,17 @@ * [struct CustomParam](cpp/api_reference/structmavsdk_1_1_param_server_1_1_custom_param.md) * [struct FloatParam](cpp/api_reference/structmavsdk_1_1_param_server_1_1_float_param.md) * [struct IntParam](cpp/api_reference/structmavsdk_1_1_param_server_1_1_int_param.md) - * [class Rtk](cpp/api_reference/classmavsdk_1_1_rtk.md) - * [struct RtcmData](cpp/api_reference/structmavsdk_1_1_rtk_1_1_rtcm_data.md) + * [class Rtk](cpp/api_reference/classmavsdk_1_1_rtk.md) + * [struct RtcmData](cpp/api_reference/structmavsdk_1_1_rtk_1_1_rtcm_data.md) + * [class ServerComponent](cpp/api_reference/classmavsdk_1_1_server_component.md) * [class ServerUtility](cpp/api_reference/classmavsdk_1_1_server_utility.md) * [class Shell](cpp/api_reference/classmavsdk_1_1_shell.md) * [class System](cpp/api_reference/classmavsdk_1_1_system.md) - * [struct AutopilotVersion](cpp/api_reference/structmavsdk_1_1_system_1_1_autopilot_version.md) * [class Telemetry](cpp/api_reference/classmavsdk_1_1_telemetry.md) * [struct AccelerationFrd](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_acceleration_frd.md) * [struct ActuatorControlTarget](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_actuator_control_target.md) * [struct ActuatorOutputStatus](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_actuator_output_status.md) + * [struct Altitude](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_altitude.md) * [struct AngularVelocityBody](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md) * [struct AngularVelocityNed](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_angular_velocity_frd.md) * [struct Battery](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_battery.md) @@ -151,8 +182,8 @@ * [struct DistanceSensor](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_distance_sensor.md) * [struct EulerAngle](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_euler_angle.md) * [struct FixedwingMetrics](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_fixedwing_metrics.md) - * [struct GpsInfo](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_gps_info.md) * [struct GpsGlobalOrigin](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_gps_global_origin.md) + * [struct GpsInfo](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_gps_info.md) * [struct GroundTruth](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_ground_truth.md) * [struct Heading](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_heading.md) * [struct Health](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_health.md) @@ -162,14 +193,14 @@ * [struct Position](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_position.md) * [struct PositionBody](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_position_body.md) * [struct PositionNed](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_position_ned.md) - * [struct VelocityNed](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_velocity_ned.md) - * [struct VelocityBody](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_velocity_body.md) * [struct PositionVelocityNed](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_position_velocity_ned.md) * [struct Quaternion](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_quaternion.md) - * [struct RawGps](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_raw_gps.md) + * [struct RawGps](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_raw_gps.md) * [struct RcStatus](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_rc_status.md) - * [struct ScaledPressure](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_scaled_pressure.md) + * [struct ScaledPressure](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_scaled_pressure.md) * [struct StatusText](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_status_text.md) + * [struct VelocityNed](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_velocity_ned.md) + * [struct VelocityBody](cpp/api_reference/structmavsdk_1_1_telemetry_1_1_velocity_body.md) * [class TelemetryServer](cpp/api_reference/classmavsdk_1_1_telemetry_server.md) * [struct AccelerationFrd](cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_acceleration_frd.md) * [struct ActuatorControlTarget](cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_actuator_control_target.md) @@ -198,16 +229,18 @@ * [struct StatusText](cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_status_text.md) * [struct VelocityBody](cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_velocity_body.md) * [struct VelocityNed](cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_velocity_ned.md) - * [class TrackingServer](cpp/api_reference/classmavsdk_1_1_tracking_server.md) - * [struct Point](cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_point.md) - * [struct Rectangle](cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_rectangle.md) * [class Transponder](cpp/api_reference/classmavsdk_1_1_transponder.md) * [struct AdsbVehicle](cpp/api_reference/structmavsdk_1_1_transponder_1_1_adsb_vehicle.md) * [class Tune](cpp/api_reference/classmavsdk_1_1_tune.md) * [struct TuneDescription](cpp/api_reference/structmavsdk_1_1_tune_1_1_tune_description.md) + * [class Winch](cpp/api_reference/classmavsdk_1_1_winch.md) + * [struct StatusFlags](cpp/api_reference/structmavsdk_1_1_winch_1_1_status_flags.md) + * [struct Status](cpp/api_reference/structmavsdk_1_1_winch_1_1_status.md) * [class PluginBase](cpp/api_reference/classmavsdk_1_1_plugin_base.md) * [class Overloaded](cpp/api_reference/structmavsdk_1_1overloaded.md) * [namespace mavsdk (globals)](cpp/api_reference/namespacemavsdk.md) + + * [Troubleshooting](cpp/troubleshooting.md) * [Contributing](cpp/contributing/index.md) * [Autogeneration](cpp/contributing/autogen.md) diff --git a/docs/en/cpp/api_changes.md b/docs/en/cpp/api_changes.md index 65df63fa19..db7e800d2a 100644 --- a/docs/en/cpp/api_changes.md +++ b/docs/en/cpp/api_changes.md @@ -4,6 +4,10 @@ This page tracks changes between versions. It covers both breaking (incompatible) and non-breaking changes. +::: info +All examples below are assuming `using namespace mavsdk`. +::: + ## Semantic Versioning MAVSDK follows [semver/Semantic Versioning](https://semver.org/) conventions where as possible. @@ -21,6 +25,108 @@ This means that breaking changes to the API result in a bump of the major versio Bumping of the major version is unrelated to the stability of the library. E.g. v2.0.0 is not by definition more stable than v1.4.18. It just means that the API has changed with v2. As development is carried on, stability is likely increasing whenever the minor or patch versions increase as incremental fixes are added. ::: +## v3 + +### Connections + +In the past the connection syntax has caused quite a bit of confusion. Therefore, we decided to adapt the syntax for UDP and TCP connections slightly, mostly adopting the syntax that's already used in other software such as for instance pymavlink and mavlink-router. + +The change makes it explicit whether we are listening on a port (think server), or connecting to a port (think client). + +The new syntax for the 3 connection methods are described below: + +#### UDP connections + +``` +- UDP in (server): udpin://our_ip:port +- UDP out (client): udpout://remote_ip:port +``` + +For `udpin`, where we bind locally to that port, the IP can be set to: +- `0.0.0.0` to listen on all network interfaces. +- `127.0.0.1` to listen on the local loopback interface only. +- to our IP which means we listen on this network interfaces only. + +#### TCP connections + +``` +- TCP in (server): tcpin://our_ip:port +- TCP out (client): tcpout://remote_ip:port +``` + +For `tcpin`, where we listen locally on that port, the IP can be set to: +- `0.0.0.0` to listen on all network interfaces. +- `127.0.0.1` to listen on the local loopback interface only. +- to our IP which means we listen on this network interfaces only. + +#### Serial connections + +``` +- Serial: serial://dev_node:baudrate +- Serial with flow control: serial_flowcontrol://dev_node:baudrate +``` + +This is unchanged apart from the one caveat that the baudrate is no longer optional. This is to avoid cases where the baudrate is omitted by mistake. + +### Mavsdk configuration + +`ComponentType` is moved out of `Mavsdk` to its own scope, so the instantiation changes as follows: + +Old instantiation: +``` +Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; +``` + +New instantiation: +``` +Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; +``` + +### Camera plugin: major redesign + +The camera plugin API and internals have changed considerably. The aim was to be able to address multiple cameras from one plugin which enables more than one camera to be used in language wrappers such as Python. This wasn't previously possible. + +Moreover, we now support MAVLink FTP and https to download the camera definition files, and not just http: + +The API has changed to include a camera ID. Below is an example how usage changes: + +``` + +auto camera = Camera{system}; +camera.select_camera(0); + +auto result = camera.zoom_range(component_id, 2.0f); +``` + +To: + +``` +auto camera = Camera{system}; + +// Assuming one camera is connected: +assert(camera.camera_list().cameras.size() == 1); +auto component_id = camera.camera_list().cameras[0].component_id; + +auto result = camera.zoom_range(component_id, 2.0f); +``` + +### Rtk and LogStreaming plugins: base64 for binary data + +With v2 it was hard or impossible to use APIs involving binary data in certain language wrappers, specifically Python. This meant that the RTK corrections and log streaming data were exposed as Python strings which didn't match the binary nature of the data. + +Therefore, we are now using base64 for the data. + +The assumption is that the performance hit of having to encode to and decode from base64 is negligible on platforms where MAVSDK is usually run. + +Mavsdk provides helper functions to help with encoding and decoding base64: + +``` +#include + +std::string encoded = ...; +std::vector binary_data = base64_decode(encoded); +``` + ## v2 ### Mavsdk configuration @@ -97,7 +203,7 @@ For instance a camera server plugin can be used as follows: ``` Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::Camera}}; -auto camera_server = mavsdk::CameraServer{mavsdk.server_component()}; +auto camera_server = CameraServer{mavsdk.server_component()}; ``` It's also possible to add more than one MAVLink component to one MAVSDK instance, e.g. a gimbal could be added like this: diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_action.md b/docs/en/cpp/api_reference/classmavsdk_1_1_action.md index ade97af305..6dd1a25fbd 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_action.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_action.md @@ -16,7 +16,6 @@ enum [OrbitYawBehavior](#classmavsdk_1_1_action_1ad9dd7c5e85dda1ae188df75998375c enum [Result](#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | Possible results returned for action requests. std::function< void([Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51))> [ResultCallback](#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) | Callback type for asynchronous [Action](classmavsdk_1_1_action.md) calls. std::function< void([Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float)> [GetTakeoffAltitudeCallback](#classmavsdk_1_1_action_1ad1ae6edb8ea375a3472ef14313b591e2) | Callback type for get_takeoff_altitude_async. -std::function< void([Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float)> [GetMaximumSpeedCallback](#classmavsdk_1_1_action_1a6993096d3e1424a817ad58ce8217a73c) | Callback type for get_maximum_speed_async. std::function< void([Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float)> [GetReturnToLaunchAltitudeCallback](#classmavsdk_1_1_action_1af28acf6f7cff11f3c583761edb7d7415) | Callback type for get_return_to_launch_altitude_async. ## Public Member Functions @@ -30,6 +29,8 @@ Type | Name | Description   | [Action](#classmavsdk_1_1_action_1a99fc1d6fc90af15a93bb270b0279a095) (const [Action](classmavsdk_1_1_action.md) & other) | Copy constructor. void | [arm_async](#classmavsdk_1_1_action_1a570a3799ca5dbbf8aab30ce465687796) (const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Send command to arm the drone. [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [arm](#classmavsdk_1_1_action_1a3ee123973982842f46a9f8b6cb952566) () const | Send command to arm the drone. +void | [arm_force_async](#classmavsdk_1_1_action_1afb89306c388181312fa23cf0b6816092) (const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Send command to force-arm the drone without any checks. +[Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [arm_force](#classmavsdk_1_1_action_1ac937ea633ff4e274d15ab8bb008d1a01) () const | Send command to force-arm the drone without any checks. void | [disarm_async](#classmavsdk_1_1_action_1a3107f7f5a2f4a478024667f187f8f2aa) (const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Send command to disarm the drone. [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [disarm](#classmavsdk_1_1_action_1a44c61110965bcdd3dfb90a08d3c6b6b9) () const | Send command to disarm the drone. void | [takeoff_async](#classmavsdk_1_1_action_1ab658d938970326db41709d83e02b41e6) (const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Send command to take off and hover. @@ -59,20 +60,16 @@ void | [transition_to_fixedwing_async](#classmavsdk_1_1_action_1aa56181441cd64e0 void | [transition_to_multicopter_async](#classmavsdk_1_1_action_1a8c109076641b5c9aa6dd78ea8b913529) (const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Send command to transition the drone to multicopter. [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [transition_to_multicopter](#classmavsdk_1_1_action_1aac94bfb8613a8e9869e3620b3dc9bb8e) () const | Send command to transition the drone to multicopter. void | [get_takeoff_altitude_async](#classmavsdk_1_1_action_1a0a600e6ef75a69341d8b21243e7b1a71) (const [GetTakeoffAltitudeCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1ad1ae6edb8ea375a3472ef14313b591e2) callback) | Get the takeoff altitude (in meters above ground). -std::pair< [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float > | [get_takeoff_altitude](#classmavsdk_1_1_action_1a85df48432c5ed2c6e23831409139ed39) () const | Get the takeoff altitude (in meters above ground). +std::pair< [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float > | [get_takeoff_altitude](#classmavsdk_1_1_action_1ad7596d6bb5e2f3b6b04e2b4ef12f5b8e) () const | Get the takeoff altitude (in meters above ground). void | [set_takeoff_altitude_async](#classmavsdk_1_1_action_1a9027c3e5f9eaf37cdfe8c426727c7693) (float altitude, const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Set takeoff altitude (in meters above ground). [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [set_takeoff_altitude](#classmavsdk_1_1_action_1ace2188fe367b3bb10b17b89c88d1f952) (float altitude)const | Set takeoff altitude (in meters above ground). -void | [get_maximum_speed_async](#classmavsdk_1_1_action_1a30aada232be0f805950a78e2005ade75) (const [GetMaximumSpeedCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a6993096d3e1424a817ad58ce8217a73c) callback) | Get the vehicle maximum speed (in metres/second). -std::pair< [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float > | [get_maximum_speed](#classmavsdk_1_1_action_1a128bf73fe8d0d359f36a3a9a327799ee) () const | Get the vehicle maximum speed (in metres/second). -void | [set_maximum_speed_async](#classmavsdk_1_1_action_1abc99f14481f0d961228c6535da9017a6) (float speed, const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Set vehicle maximum speed (in metres/second). -[Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [set_maximum_speed](#classmavsdk_1_1_action_1a5fccee1636215bccf8d77d9dca15134e) (float speed)const | Set vehicle maximum speed (in metres/second). void | [get_return_to_launch_altitude_async](#classmavsdk_1_1_action_1aa19935b55d80f63e06397b3ea4b51c22) (const [GetReturnToLaunchAltitudeCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1af28acf6f7cff11f3c583761edb7d7415) callback) | Get the return to launch minimum return altitude (in meters). -std::pair< [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float > | [get_return_to_launch_altitude](#classmavsdk_1_1_action_1aeffd084ea51c8a784e28b44b859b6586) () const | Get the return to launch minimum return altitude (in meters). +std::pair< [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float > | [get_return_to_launch_altitude](#classmavsdk_1_1_action_1a90e6a8fc7cd44c610c9a0a159c8e1a87) () const | Get the return to launch minimum return altitude (in meters). void | [set_return_to_launch_altitude_async](#classmavsdk_1_1_action_1acdc4360c21ec82c57125023c552b3410) (float relative_altitude_m, const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Set the return to launch minimum return altitude (in meters). [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [set_return_to_launch_altitude](#classmavsdk_1_1_action_1a5b05e84d35fad5b0ba2837aae1b3686e) (float relative_altitude_m)const | Set the return to launch minimum return altitude (in meters). void | [set_current_speed_async](#classmavsdk_1_1_action_1afd210be0eba436c81da79107562a0b6c) (float speed_m_s, const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) callback) | Set current speed. [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) | [set_current_speed](#classmavsdk_1_1_action_1af3b74cf3912411d9476b6eeac0984afb) (float speed_m_s)const | Set current speed. -const [Action](classmavsdk_1_1_action.md) & | [operator=](#classmavsdk_1_1_action_1a1ff7e178b7ededc41bd9ccab0ca07457) (const [Action](classmavsdk_1_1_action.md) &)=delete | Equality operator (object is not copyable). +const [Action](classmavsdk_1_1_action.md) & | [operator=](#classmavsdk_1_1_action_1a89482740f533e194fade200103b5adef) (const [Action](classmavsdk_1_1_action.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -159,16 +156,6 @@ using mavsdk::Action::GetTakeoffAltitudeCallback = std::function -``` - - -Callback type for get_maximum_speed_async. - - ### typedef GetReturnToLaunchAltitudeCallback {#classmavsdk_1_1_action_1af28acf6f7cff11f3c583761edb7d7415} ```cpp @@ -218,6 +205,7 @@ Value | Description `ParameterError` | Error getting or setting parameter. `Unsupported` | [Action](classmavsdk_1_1_action.md) not supported. `Failed` | [Action](classmavsdk_1_1_action.md) failed. + `InvalidArgument` | Invalid argument. ## Member Function Documentation @@ -256,6 +244,46 @@ This function is blocking. See 'arm_async' for the non-blocking counterpart.  [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) - Result of request. +### arm_force_async() {#classmavsdk_1_1_action_1afb89306c388181312fa23cf0b6816092} +```cpp +void mavsdk::Action::arm_force_async(const ResultCallback callback) +``` + + +Send command to force-arm the drone without any checks. + +Attention: this is not to be used for normal flying but only bench tests! + + +Arming a drone normally causes motors to spin at idle. Before arming take all safety precautions and stand clear of the drone! + + +This function is non-blocking. See 'arm_force' for the blocking counterpart. + +**Parameters** + +* const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) **callback** - + +### arm_force() {#classmavsdk_1_1_action_1ac937ea633ff4e274d15ab8bb008d1a01} +```cpp +Result mavsdk::Action::arm_force() const +``` + + +Send command to force-arm the drone without any checks. + +Attention: this is not to be used for normal flying but only bench tests! + + +Arming a drone normally causes motors to spin at idle. Before arming take all safety precautions and stand clear of the drone! + + +This function is blocking. See 'arm_force_async' for the non-blocking counterpart. + +**Returns** + + [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) - Result of request. + ### disarm_async() {#classmavsdk_1_1_action_1a3107f7f5a2f4a478024667f187f8f2aa} ```cpp void mavsdk::Action::disarm_async(const ResultCallback callback) @@ -682,6 +710,9 @@ void mavsdk::Action::set_actuator_async(int32_t index, float value, const Result Send command to set the value of an actuator. +Note that the index of the actuator starts at 1 and that the value goes from -1 to 1. + + This function is non-blocking. See 'set_actuator' for the blocking counterpart. **Parameters** @@ -698,6 +729,9 @@ Result mavsdk::Action::set_actuator(int32_t index, float value) const Send command to set the value of an actuator. +Note that the index of the actuator starts at 1 and that the value goes from -1 to 1. + + This function is blocking. See 'set_actuator_async' for the non-blocking counterpart. **Parameters** @@ -791,9 +825,9 @@ This function is non-blocking. See 'get_takeoff_altitude' for the blocking count * const [GetTakeoffAltitudeCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1ad1ae6edb8ea375a3472ef14313b591e2) **callback** - -### get_takeoff_altitude() {#classmavsdk_1_1_action_1a85df48432c5ed2c6e23831409139ed39} +### get_takeoff_altitude() {#classmavsdk_1_1_action_1ad7596d6bb5e2f3b6b04e2b4ef12f5b8e} ```cpp -std::pair mavsdk::Action::get_takeoff_altitude() const +std::pair< Result, float > mavsdk::Action::get_takeoff_altitude() const ``` @@ -838,67 +872,6 @@ This function is blocking. See 'set_takeoff_altitude_async' for the non-blocking  [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) - Result of request. -### get_maximum_speed_async() {#classmavsdk_1_1_action_1a30aada232be0f805950a78e2005ade75} -```cpp -void mavsdk::Action::get_maximum_speed_async(const GetMaximumSpeedCallback callback) -``` - - -Get the vehicle maximum speed (in metres/second). - -This function is non-blocking. See 'get_maximum_speed' for the blocking counterpart. - -**Parameters** - -* const [GetMaximumSpeedCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a6993096d3e1424a817ad58ce8217a73c) **callback** - - -### get_maximum_speed() {#classmavsdk_1_1_action_1a128bf73fe8d0d359f36a3a9a327799ee} -```cpp -std::pair mavsdk::Action::get_maximum_speed() const -``` - - -Get the vehicle maximum speed (in metres/second). - -This function is blocking. See 'get_maximum_speed_async' for the non-blocking counterpart. - -**Returns** - - std::pair< [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51), float > - Result of request. - -### set_maximum_speed_async() {#classmavsdk_1_1_action_1abc99f14481f0d961228c6535da9017a6} -```cpp -void mavsdk::Action::set_maximum_speed_async(float speed, const ResultCallback callback) -``` - - -Set vehicle maximum speed (in metres/second). - -This function is non-blocking. See 'set_maximum_speed' for the blocking counterpart. - -**Parameters** - -* float **speed** - -* const [ResultCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a70a7b6e742d0c86728dc2e1827dacccd) **callback** - - -### set_maximum_speed() {#classmavsdk_1_1_action_1a5fccee1636215bccf8d77d9dca15134e} -```cpp -Result mavsdk::Action::set_maximum_speed(float speed) const -``` - - -Set vehicle maximum speed (in metres/second). - -This function is blocking. See 'set_maximum_speed_async' for the non-blocking counterpart. - -**Parameters** - -* float **speed** - - -**Returns** - - [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) - Result of request. - ### get_return_to_launch_altitude_async() {#classmavsdk_1_1_action_1aa19935b55d80f63e06397b3ea4b51c22} ```cpp void mavsdk::Action::get_return_to_launch_altitude_async(const GetReturnToLaunchAltitudeCallback callback) @@ -913,9 +886,9 @@ This function is non-blocking. See 'get_return_to_launch_altitude' for the block * const [GetReturnToLaunchAltitudeCallback](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1af28acf6f7cff11f3c583761edb7d7415) **callback** - -### get_return_to_launch_altitude() {#classmavsdk_1_1_action_1aeffd084ea51c8a784e28b44b859b6586} +### get_return_to_launch_altitude() {#classmavsdk_1_1_action_1a90e6a8fc7cd44c610c9a0a159c8e1a87} ```cpp -std::pair mavsdk::Action::get_return_to_launch_altitude() const +std::pair< Result, float > mavsdk::Action::get_return_to_launch_altitude() const ``` @@ -999,9 +972,9 @@ This function is blocking. See 'set_current_speed_async' for the non-blocking co  [Result](classmavsdk_1_1_action.md#classmavsdk_1_1_action_1adc2e13257ef13de0e7610cf879a0ec51) - Result of request. -### operator=() {#classmavsdk_1_1_action_1a1ff7e178b7ededc41bd9ccab0ca07457} +### operator=() {#classmavsdk_1_1_action_1a89482740f533e194fade200103b5adef} ```cpp -const Action& mavsdk::Action::operator=(const Action &)=delete +const Action & mavsdk::Action::operator=(const Action &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_action_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_action_server.md index 91a56963fe..a13a342f91 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_action_server.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_action_server.md @@ -64,7 +64,7 @@ void | [unsubscribe_terminate](#classmavsdk_1_1_action_server_1a3e236694f1f0beae [Result](classmavsdk_1_1_action_server.md#classmavsdk_1_1_action_server_1a4a8eb4fe9d098a5b7891232fc5bf32f8) | [set_disarmable](#classmavsdk_1_1_action_server_1afae1336100d7a91a4f4521cee56a1ecb) (bool disarmable, bool force_disarmable)const | Can the vehicle disarm when requested. [Result](classmavsdk_1_1_action_server.md#classmavsdk_1_1_action_server_1a4a8eb4fe9d098a5b7891232fc5bf32f8) | [set_allowable_flight_modes](#classmavsdk_1_1_action_server_1a3041d1b923a3b01021433ad43ab93b3a) ([AllowableFlightModes](structmavsdk_1_1_action_server_1_1_allowable_flight_modes.md) flight_modes)const | Set which modes the vehicle can transition to (Manual always allowed) [ActionServer::AllowableFlightModes](structmavsdk_1_1_action_server_1_1_allowable_flight_modes.md) | [get_allowable_flight_modes](#classmavsdk_1_1_action_server_1a0960a6ec243823729a418a3c68feaf2a) () const | Get which modes the vehicle can transition to (Manual always allowed) -const [ActionServer](classmavsdk_1_1_action_server.md) & | [operator=](#classmavsdk_1_1_action_server_1a86d8bb24723ad8222669aec1f5c523ca) (const [ActionServer](classmavsdk_1_1_action_server.md) &)=delete | Equality operator (object is not copyable). +const [ActionServer](classmavsdk_1_1_action_server.md) & | [operator=](#classmavsdk_1_1_action_server_1aa80e34dd72d2e31005085c78892bab8c) (const [ActionServer](classmavsdk_1_1_action_server.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -613,9 +613,9 @@ This function is blocking.  [ActionServer::AllowableFlightModes](structmavsdk_1_1_action_server_1_1_allowable_flight_modes.md) - Result of request. -### operator=() {#classmavsdk_1_1_action_server_1a86d8bb24723ad8222669aec1f5c523ca} +### operator=() {#classmavsdk_1_1_action_server_1aa80e34dd72d2e31005085c78892bab8c} ```cpp -const ActionServer& mavsdk::ActionServer::operator=(const ActionServer &)=delete +const ActionServer & mavsdk::ActionServer::operator=(const ActionServer &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_arm_authorizer_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_arm_authorizer_server.md new file mode 100644 index 0000000000..897f8cc5cc --- /dev/null +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_arm_authorizer_server.md @@ -0,0 +1,228 @@ +# mavsdk::ArmAuthorizerServer Class Reference +`#include: arm_authorizer_server.h` + +---- + + +Use arm authorization. + + +## Public Types + + +Type | Description +--- | --- +enum [RejectionReason](#classmavsdk_1_1_arm_authorizer_server_1a8e2f877e83640591859db072cb26a6ee) | The rejection reason. +enum [Result](#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011) | The result. +std::function< void([Result](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011))> [ResultCallback](#classmavsdk_1_1_arm_authorizer_server_1ab4c5e8114b66740bd4382d0daa3052d9) | Callback type for asynchronous [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) calls. +std::function< void(uint32_t)> [ArmAuthorizationCallback](#classmavsdk_1_1_arm_authorizer_server_1ac608fecb1db7daea51078b1194c0ff86) | Callback type for subscribe_arm_authorization. +[Handle](classmavsdk_1_1_handle.md)< uint32_t > [ArmAuthorizationHandle](#classmavsdk_1_1_arm_authorizer_server_1af0c4f4d88ebf36ae6adeb7d2af163fa5) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_arm_authorization. + +## Public Member Functions + + +Type | Name | Description +---: | --- | --- +  | [ArmAuthorizerServer](#classmavsdk_1_1_arm_authorizer_server_1a7c43f4e97453fa762a233c766da48402) (std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > server_component) | Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. +  | [~ArmAuthorizerServer](#classmavsdk_1_1_arm_authorizer_server_1a5412419e4c6e16160928583551841e25) () override | Destructor (internal use only). +  | [ArmAuthorizerServer](#classmavsdk_1_1_arm_authorizer_server_1a209d19bdc496402350967da7fd6a827e) (const [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) & other) | Copy constructor. +[ArmAuthorizationHandle](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1af0c4f4d88ebf36ae6adeb7d2af163fa5) | [subscribe_arm_authorization](#classmavsdk_1_1_arm_authorizer_server_1a334ede8582f9dfe196df01cc73293ab2) (const [ArmAuthorizationCallback](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1ac608fecb1db7daea51078b1194c0ff86) & callback) | Subscribe to arm authorization request messages. Each request received should respond to using RespondArmAuthorization. +void | [unsubscribe_arm_authorization](#classmavsdk_1_1_arm_authorizer_server_1a07869a29c05428f346138016dd63dd22) ([ArmAuthorizationHandle](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1af0c4f4d88ebf36ae6adeb7d2af163fa5) handle) | Unsubscribe from subscribe_arm_authorization. +[Result](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011) | [accept_arm_authorization](#classmavsdk_1_1_arm_authorizer_server_1afd9dd0c6c1058c06773f63b220c24d39) (int32_t valid_time_s)const | Authorize arm for the specific time. +[Result](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011) | [reject_arm_authorization](#classmavsdk_1_1_arm_authorizer_server_1a99f8b59b8d6db4b074f4df5018c9d786) (bool temporarily, [RejectionReason](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1a8e2f877e83640591859db072cb26a6ee) reason, int32_t extra_info)const | Reject arm authorization request. +const [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) & | [operator=](#classmavsdk_1_1_arm_authorizer_server_1ae44588d79926001c8e33024ce2221b06) (const [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) &)=delete | Equality operator (object is not copyable). + + +## Constructor & Destructor Documentation + + +### ArmAuthorizerServer() {#classmavsdk_1_1_arm_authorizer_server_1a7c43f4e97453fa762a233c766da48402} +```cpp +mavsdk::ArmAuthorizerServer::ArmAuthorizerServer(std::shared_ptr< ServerComponent > server_component) +``` + + +Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. + +The plugin is typically created as shown below: + +```cpp +auto arm_authorizer_server = ArmAuthorizerServer(server_component); +``` + +**Parameters** + +* std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > **server_component** - The [ServerComponent](classmavsdk_1_1_server_component.md) instance associated with this server plugin. + +### ~ArmAuthorizerServer() {#classmavsdk_1_1_arm_authorizer_server_1a5412419e4c6e16160928583551841e25} +```cpp +mavsdk::ArmAuthorizerServer::~ArmAuthorizerServer() override +``` + + +Destructor (internal use only). + + +### ArmAuthorizerServer() {#classmavsdk_1_1_arm_authorizer_server_1a209d19bdc496402350967da7fd6a827e} +```cpp +mavsdk::ArmAuthorizerServer::ArmAuthorizerServer(const ArmAuthorizerServer &other) +``` + + +Copy constructor. + + +**Parameters** + +* const [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md)& **other** - + +## Member Typdef Documentation + + +### typedef ResultCallback {#classmavsdk_1_1_arm_authorizer_server_1ab4c5e8114b66740bd4382d0daa3052d9} + +```cpp +using mavsdk::ArmAuthorizerServer::ResultCallback = std::function +``` + + +Callback type for asynchronous [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) calls. + + +### typedef ArmAuthorizationCallback {#classmavsdk_1_1_arm_authorizer_server_1ac608fecb1db7daea51078b1194c0ff86} + +```cpp +using mavsdk::ArmAuthorizerServer::ArmAuthorizationCallback = std::function +``` + + +Callback type for subscribe_arm_authorization. + + +### typedef ArmAuthorizationHandle {#classmavsdk_1_1_arm_authorizer_server_1af0c4f4d88ebf36ae6adeb7d2af163fa5} + +```cpp +using mavsdk::ArmAuthorizerServer::ArmAuthorizationHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_arm_authorization. + + +## Member Enumeration Documentation + + +### enum RejectionReason {#classmavsdk_1_1_arm_authorizer_server_1a8e2f877e83640591859db072cb26a6ee} + + +The rejection reason. + + +Value | Description +--- | --- + `Generic` | Not a specific reason. + `None` | Authorizer will send the error as string to GCS. + `InvalidWaypoint` | At least one waypoint have a invalid value. + `Timeout` | Timeout in the authorizer process(in case it depends on network). + `AirspaceInUse` | Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied.. + `BadWeather` | Weather is not good to fly. + +### enum Result {#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011} + + +The result. + + +Value | Description +--- | --- + `Unknown` | Unknown result. + `Success` | Command accepted. + `Failed` | Command failed. + +## Member Function Documentation + + +### subscribe_arm_authorization() {#classmavsdk_1_1_arm_authorizer_server_1a334ede8582f9dfe196df01cc73293ab2} +```cpp +ArmAuthorizationHandle mavsdk::ArmAuthorizerServer::subscribe_arm_authorization(const ArmAuthorizationCallback &callback) +``` + + +Subscribe to arm authorization request messages. Each request received should respond to using RespondArmAuthorization. + + +**Parameters** + +* const [ArmAuthorizationCallback](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1ac608fecb1db7daea51078b1194c0ff86)& **callback** - + +**Returns** + + [ArmAuthorizationHandle](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1af0c4f4d88ebf36ae6adeb7d2af163fa5) - + +### unsubscribe_arm_authorization() {#classmavsdk_1_1_arm_authorizer_server_1a07869a29c05428f346138016dd63dd22} +```cpp +void mavsdk::ArmAuthorizerServer::unsubscribe_arm_authorization(ArmAuthorizationHandle handle) +``` + + +Unsubscribe from subscribe_arm_authorization. + + +**Parameters** + +* [ArmAuthorizationHandle](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1af0c4f4d88ebf36ae6adeb7d2af163fa5) **handle** - + +### accept_arm_authorization() {#classmavsdk_1_1_arm_authorizer_server_1afd9dd0c6c1058c06773f63b220c24d39} +```cpp +Result mavsdk::ArmAuthorizerServer::accept_arm_authorization(int32_t valid_time_s) const +``` + + +Authorize arm for the specific time. + +This function is blocking. + +**Parameters** + +* int32_t **valid_time_s** - + +**Returns** + + [Result](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011) - Result of request. + +### reject_arm_authorization() {#classmavsdk_1_1_arm_authorizer_server_1a99f8b59b8d6db4b074f4df5018c9d786} +```cpp +Result mavsdk::ArmAuthorizerServer::reject_arm_authorization(bool temporarily, RejectionReason reason, int32_t extra_info) const +``` + + +Reject arm authorization request. + +This function is blocking. + +**Parameters** + +* bool **temporarily** - +* [RejectionReason](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1a8e2f877e83640591859db072cb26a6ee) **reason** - +* int32_t **extra_info** - + +**Returns** + + [Result](classmavsdk_1_1_arm_authorizer_server.md#classmavsdk_1_1_arm_authorizer_server_1aa8139980ee55b72cf04b69c453e04011) - Result of request. + +### operator=() {#classmavsdk_1_1_arm_authorizer_server_1ae44588d79926001c8e33024ce2221b06} +```cpp +const ArmAuthorizerServer & mavsdk::ArmAuthorizerServer::operator=(const ArmAuthorizerServer &)=delete +``` + + +Equality operator (object is not copyable). + + +**Parameters** + +* const [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md)& - + +**Returns** + + const [ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_calibration.md b/docs/en/cpp/api_reference/classmavsdk_1_1_calibration.md index 9b349c3237..6720e85377 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_calibration.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_calibration.md @@ -40,7 +40,7 @@ void | [calibrate_magnetometer_async](#classmavsdk_1_1_calibration_1aa8a04e0f687 void | [calibrate_level_horizon_async](#classmavsdk_1_1_calibration_1a77dd4e73da90801d63da973e1736628d) (const [CalibrateLevelHorizonCallback](classmavsdk_1_1_calibration.md#classmavsdk_1_1_calibration_1a397475f5df5fd0e1a181437d4e146aa4) & callback) | Perform board level horizon calibration. void | [calibrate_gimbal_accelerometer_async](#classmavsdk_1_1_calibration_1a9b95e383527253c17cd0990653682cd6) (const [CalibrateGimbalAccelerometerCallback](classmavsdk_1_1_calibration.md#classmavsdk_1_1_calibration_1aa254e3a18042794e182fc7f3685aad01) & callback) | Perform gimbal accelerometer calibration. [Result](classmavsdk_1_1_calibration.md#classmavsdk_1_1_calibration_1a6e1ce7a3a07eb098edc06821d23a8ec1) | [cancel](#classmavsdk_1_1_calibration_1ae26f45164d36576d56a186ee69e32ffb) () const | Cancel ongoing calibration process. -const [Calibration](classmavsdk_1_1_calibration.md) & | [operator=](#classmavsdk_1_1_calibration_1ada12d974bb516745ea67f94c72abf59b) (const [Calibration](classmavsdk_1_1_calibration.md) &)=delete | Equality operator (object is not copyable). +const [Calibration](classmavsdk_1_1_calibration.md) & | [operator=](#classmavsdk_1_1_calibration_1a6153be06646326c736660560c9582610) (const [Calibration](classmavsdk_1_1_calibration.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -273,9 +273,9 @@ This function is blocking.  [Result](classmavsdk_1_1_calibration.md#classmavsdk_1_1_calibration_1a6e1ce7a3a07eb098edc06821d23a8ec1) - Result of request. -### operator=() {#classmavsdk_1_1_calibration_1ada12d974bb516745ea67f94c72abf59b} +### operator=() {#classmavsdk_1_1_calibration_1a6153be06646326c736660560c9582610} ```cpp -const Calibration& mavsdk::Calibration::operator=(const Calibration &)=delete +const Calibration & mavsdk::Calibration::operator=(const Calibration &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_callback_list.md b/docs/en/cpp/api_reference/classmavsdk_1_1_callback_list.md deleted file mode 100644 index 4bb6abfe73..0000000000 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_callback_list.md +++ /dev/null @@ -1,5 +0,0 @@ -# mavsdk::CallbackList Class Reference -`#include: UNKNOWN` - ----- - diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_callback_list_impl.md b/docs/en/cpp/api_reference/classmavsdk_1_1_callback_list_impl.md deleted file mode 100644 index f08af866f6..0000000000 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_callback_list_impl.md +++ /dev/null @@ -1,5 +0,0 @@ -# mavsdk::CallbackListImpl Class Reference -`#include: UNKNOWN` - ----- - diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_camera.md b/docs/en/cpp/api_reference/classmavsdk_1_1_camera.md index 32db3fc53b..5009e1a825 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_camera.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_camera.md @@ -13,28 +13,40 @@ Currently only a single camera is supported. When multiple cameras are supported ## Data Structures +struct [CameraList](structmavsdk_1_1_camera_1_1_camera_list.md) + struct [CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) +struct [CurrentSettingsUpdate](structmavsdk_1_1_camera_1_1_current_settings_update.md) + struct [EulerAngle](structmavsdk_1_1_camera_1_1_euler_angle.md) struct [Information](structmavsdk_1_1_camera_1_1_information.md) +struct [ModeUpdate](structmavsdk_1_1_camera_1_1_mode_update.md) + struct [Option](structmavsdk_1_1_camera_1_1_option.md) struct [Position](structmavsdk_1_1_camera_1_1_position.md) +struct [PossibleSettingOptionsUpdate](structmavsdk_1_1_camera_1_1_possible_setting_options_update.md) + struct [Quaternion](structmavsdk_1_1_camera_1_1_quaternion.md) struct [Setting](structmavsdk_1_1_camera_1_1_setting.md) struct [SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) -struct [Status](structmavsdk_1_1_camera_1_1_status.md) +struct [Storage](structmavsdk_1_1_camera_1_1_storage.md) + +struct [StorageUpdate](structmavsdk_1_1_camera_1_1_storage_update.md) struct [VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) struct [VideoStreamSettings](structmavsdk_1_1_camera_1_1_video_stream_settings.md) +struct [VideoStreamUpdate](structmavsdk_1_1_camera_1_1_video_stream_update.md) + ## Public Types @@ -45,20 +57,20 @@ enum [PhotosRange](#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) | enum [Result](#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | Possible results returned for camera commands. std::function< void([Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf))> [ResultCallback](#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) | Callback type for asynchronous [Camera](classmavsdk_1_1_camera.md) calls. std::function< void([Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) >)> [ListPhotosCallback](#classmavsdk_1_1_camera_1a23240233586f7673c3a1b48f07623fe4) | Callback type for list_photos_async. -std::function< void([Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65))> [ModeCallback](#classmavsdk_1_1_camera_1a33a7257ab95d9277b786e6de86604931) | Callback type for subscribe_mode. -[Handle](classmavsdk_1_1_handle.md)< [Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) > [ModeHandle](#classmavsdk_1_1_camera_1ac6759725ac9696f9572b05524fde2354) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_mode. -std::function< void([Information](structmavsdk_1_1_camera_1_1_information.md))> [InformationCallback](#classmavsdk_1_1_camera_1af13455249eebaf152a71d59e32fcbf65) | Callback type for subscribe_information. -[Handle](classmavsdk_1_1_handle.md)< [Information](structmavsdk_1_1_camera_1_1_information.md) > [InformationHandle](#classmavsdk_1_1_camera_1a0dcacb795da7de566fb6dce091ca4605) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_information. -std::function< void([VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md))> [VideoStreamInfoCallback](#classmavsdk_1_1_camera_1acd9baf073b816e46c22dbd6b599ece66) | Callback type for subscribe_video_stream_info. -[Handle](classmavsdk_1_1_handle.md)< [VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) > [VideoStreamInfoHandle](#classmavsdk_1_1_camera_1aebf91f740cc85682c6b7a0955635f848) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_video_stream_info. +std::function< void([CameraList](structmavsdk_1_1_camera_1_1_camera_list.md))> [CameraListCallback](#classmavsdk_1_1_camera_1ac853b9f8da070d22b1cfe2680f7785d3) | Callback type for subscribe_camera_list. +[Handle](classmavsdk_1_1_handle.md)< [CameraList](structmavsdk_1_1_camera_1_1_camera_list.md) > [CameraListHandle](#classmavsdk_1_1_camera_1aeb7f6082a8f08509e8c45f23768a5a64) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_camera_list. +std::function< void([ModeUpdate](structmavsdk_1_1_camera_1_1_mode_update.md))> [ModeCallback](#classmavsdk_1_1_camera_1af6649645c4056d797b42de9418dc4226) | Callback type for subscribe_mode. +[Handle](classmavsdk_1_1_handle.md)< [ModeUpdate](structmavsdk_1_1_camera_1_1_mode_update.md) > [ModeHandle](#classmavsdk_1_1_camera_1a71c4937ed9dcc1766561370cfe0f523f) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_mode. +std::function< void([VideoStreamUpdate](structmavsdk_1_1_camera_1_1_video_stream_update.md))> [VideoStreamInfoCallback](#classmavsdk_1_1_camera_1a5c9669b2652e37e067c6c5c300c9409b) | Callback type for subscribe_video_stream_info. +[Handle](classmavsdk_1_1_handle.md)< [VideoStreamUpdate](structmavsdk_1_1_camera_1_1_video_stream_update.md) > [VideoStreamInfoHandle](#classmavsdk_1_1_camera_1a093e5b2652791c703534f38ca329b198) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_video_stream_info. std::function< void([CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md))> [CaptureInfoCallback](#classmavsdk_1_1_camera_1a9bf5c20ea0b03ab019057829d1a3441e) | Callback type for subscribe_capture_info. [Handle](classmavsdk_1_1_handle.md)< [CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) > [CaptureInfoHandle](#classmavsdk_1_1_camera_1a789f1fccde8eb44bc07694751b3a1b40) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_capture_info. -std::function< void([Status](structmavsdk_1_1_camera_1_1_status.md))> [StatusCallback](#classmavsdk_1_1_camera_1aea925914ce854b81b67e3213840c97ad) | Callback type for subscribe_status. -[Handle](classmavsdk_1_1_handle.md)< [Status](structmavsdk_1_1_camera_1_1_status.md) > [StatusHandle](#classmavsdk_1_1_camera_1a902bc3a824040a37714bb2c1c41a9601) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_status. -std::function< void(std::vector< [Setting](structmavsdk_1_1_camera_1_1_setting.md) >)> [CurrentSettingsCallback](#classmavsdk_1_1_camera_1a77484487381b2579460c36d97d367fe6) | Callback type for subscribe_current_settings. -[Handle](classmavsdk_1_1_handle.md)< std::vector< [Setting](structmavsdk_1_1_camera_1_1_setting.md) > > [CurrentSettingsHandle](#classmavsdk_1_1_camera_1a19960e47f1c2b3fb5117ba2f7f3cfbe6) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_current_settings. -std::function< void(std::vector< [SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) >)> [PossibleSettingOptionsCallback](#classmavsdk_1_1_camera_1a78e25614c29cd8bc1bbf26adcf417c2a) | Callback type for subscribe_possible_setting_options. -[Handle](classmavsdk_1_1_handle.md)< std::vector< [SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) > > [PossibleSettingOptionsHandle](#classmavsdk_1_1_camera_1a1144be14cd9f15724397ad6b5253b8a9) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_possible_setting_options. +std::function< void([StorageUpdate](structmavsdk_1_1_camera_1_1_storage_update.md))> [StorageCallback](#classmavsdk_1_1_camera_1a7811502147e261b81f7f4ea2422fad03) | Callback type for subscribe_storage. +[Handle](classmavsdk_1_1_handle.md)< [StorageUpdate](structmavsdk_1_1_camera_1_1_storage_update.md) > [StorageHandle](#classmavsdk_1_1_camera_1a4707b885d81143f3cb24ca956c1f91c9) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_storage. +std::function< void([CurrentSettingsUpdate](structmavsdk_1_1_camera_1_1_current_settings_update.md))> [CurrentSettingsCallback](#classmavsdk_1_1_camera_1ac12104378b90908410ffe100e9fd264e) | Callback type for subscribe_current_settings. +[Handle](classmavsdk_1_1_handle.md)< [CurrentSettingsUpdate](structmavsdk_1_1_camera_1_1_current_settings_update.md) > [CurrentSettingsHandle](#classmavsdk_1_1_camera_1afa537975f7985f7f7697dc7b4477ccd9) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_current_settings. +std::function< void([PossibleSettingOptionsUpdate](structmavsdk_1_1_camera_1_1_possible_setting_options_update.md))> [PossibleSettingOptionsCallback](#classmavsdk_1_1_camera_1a7eec62e8cdab1a2a7e787bbfeb5205e2) | Callback type for subscribe_possible_setting_options. +[Handle](classmavsdk_1_1_handle.md)< [PossibleSettingOptionsUpdate](structmavsdk_1_1_camera_1_1_possible_setting_options_update.md) > [PossibleSettingOptionsHandle](#classmavsdk_1_1_camera_1a8ebb2da9f006cff11293e7e5a20d2f82) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_possible_setting_options. std::function< void([Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Setting](structmavsdk_1_1_camera_1_1_setting.md))> [GetSettingCallback](#classmavsdk_1_1_camera_1ac233f5688f0b7f1e712bb31dfaeadd85) | Callback type for get_setting_async. ## Public Member Functions @@ -70,53 +82,73 @@ Type | Name | Description   | [Camera](#classmavsdk_1_1_camera_1aecd55dc849bbb967a6b9dcfd36cc075e) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md).   | [~Camera](#classmavsdk_1_1_camera_1afc23a58baf97868b1d9a9b983d7c2087) () override | Destructor (internal use only).   | [Camera](#classmavsdk_1_1_camera_1a1b83c38c360d70b56222a94999d862fd) (const [Camera](classmavsdk_1_1_camera.md) & other) | Copy constructor. -void | [prepare_async](#classmavsdk_1_1_camera_1aba33f1f8302259a7d51a09b60ea29cbf) (const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Prepare the camera plugin (e.g. download the camera definition, etc). -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [prepare](#classmavsdk_1_1_camera_1af263d3ea4e24da262f935c56fb578444) () const | Prepare the camera plugin (e.g. download the camera definition, etc). -void | [take_photo_async](#classmavsdk_1_1_camera_1a343217bf38cc71cd258c7e81626dccb5) (const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Take one photo. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [take_photo](#classmavsdk_1_1_camera_1a44b86cfda6262652a1796661e595003c) () const | Take one photo. -void | [start_photo_interval_async](#classmavsdk_1_1_camera_1ae583f83e163e2b33a8dc4a6fcfebbac6) (float interval_s, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start photo timelapse with a given interval. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [start_photo_interval](#classmavsdk_1_1_camera_1adfa32eb338aabf19675a1218fc28d8bc) (float interval_s)const | Start photo timelapse with a given interval. -void | [stop_photo_interval_async](#classmavsdk_1_1_camera_1a540d94eb58efe02fdd3659994c778203) (const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop a running photo timelapse. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [stop_photo_interval](#classmavsdk_1_1_camera_1a287fa0fd3fcda1dee2cf40ad041d524a) () const | Stop a running photo timelapse. -void | [start_video_async](#classmavsdk_1_1_camera_1a2d5dff782ea3f8346bc53560be368531) (const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start a video recording. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [start_video](#classmavsdk_1_1_camera_1ac64e77dee9f5ff9b5c84100d8f007670) () const | Start a video recording. -void | [stop_video_async](#classmavsdk_1_1_camera_1a77d1b1a201164023c5eef3c91cdd4e54) (const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop a running video recording. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [stop_video](#classmavsdk_1_1_camera_1a6062ac1907bd10944d2ddb9655943ddc) () const | Stop a running video recording. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [start_video_streaming](#classmavsdk_1_1_camera_1a6e062242a02389e2fc839f5e9ec03d7d) (int32_t stream_id)const | Start video streaming. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [stop_video_streaming](#classmavsdk_1_1_camera_1ae495e8c52984ad76b27b72fc58987d9d) (int32_t stream_id)const | Stop current video streaming. -void | [set_mode_async](#classmavsdk_1_1_camera_1a76d98d04885d38d0438da7c8696ef6ab) ([Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) mode, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Set camera mode. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [set_mode](#classmavsdk_1_1_camera_1a249755db2eaa8fd3d202ac01ca52448d) ([Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) mode)const | Set camera mode. -void | [list_photos_async](#classmavsdk_1_1_camera_1aec1edfe505476d437d45ec2f0deec924) ([PhotosRange](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) photos_range, const [ListPhotosCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a23240233586f7673c3a1b48f07623fe4) callback) | List photos available on the camera. -std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) > > | [list_photos](#classmavsdk_1_1_camera_1a49dc17b74047049c386d88cd365de868) ([PhotosRange](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) photos_range)const | List photos available on the camera. -[ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac6759725ac9696f9572b05524fde2354) | [subscribe_mode](#classmavsdk_1_1_camera_1a1963bfcfcc8c9e96451648f96fd618cd) (const [ModeCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a33a7257ab95d9277b786e6de86604931) & callback) | Subscribe to camera mode updates. -void | [unsubscribe_mode](#classmavsdk_1_1_camera_1ab9437b41565d8957050e09cf4143f5d1) ([ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac6759725ac9696f9572b05524fde2354) handle) | Unsubscribe from subscribe_mode. -[Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) | [mode](#classmavsdk_1_1_camera_1a222bce91e70d1ca53bcf5d885bacd418) () const | Poll for 'Mode' (blocking). -[InformationHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a0dcacb795da7de566fb6dce091ca4605) | [subscribe_information](#classmavsdk_1_1_camera_1af4b5c713813df8c407a09963295c33a2) (const [InformationCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1af13455249eebaf152a71d59e32fcbf65) & callback) | Subscribe to camera information updates. -void | [unsubscribe_information](#classmavsdk_1_1_camera_1a90b70deaf25dff027714afb856653ea5) ([InformationHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a0dcacb795da7de566fb6dce091ca4605) handle) | Unsubscribe from subscribe_information. -[Information](structmavsdk_1_1_camera_1_1_information.md) | [information](#classmavsdk_1_1_camera_1a7feb16f3d913b91d05efc803ce4e396b) () const | Poll for '[Information](structmavsdk_1_1_camera_1_1_information.md)' (blocking). -[VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aebf91f740cc85682c6b7a0955635f848) | [subscribe_video_stream_info](#classmavsdk_1_1_camera_1a4dcf0ebeb1f9f5e5b2b71f59c9b7eeb9) (const [VideoStreamInfoCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1acd9baf073b816e46c22dbd6b599ece66) & callback) | Subscribe to video stream info updates. -void | [unsubscribe_video_stream_info](#classmavsdk_1_1_camera_1abc370783800fb90dda20d2843f990036) ([VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aebf91f740cc85682c6b7a0955635f848) handle) | Unsubscribe from subscribe_video_stream_info. -[VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) | [video_stream_info](#classmavsdk_1_1_camera_1ad466621feff2d4f0f11124a36dda656c) () const | Poll for '[VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md)' (blocking). +void | [take_photo_async](#classmavsdk_1_1_camera_1ae7a59d768c597fbee8eff47073dd8690) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Take one photo. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [take_photo](#classmavsdk_1_1_camera_1ae06036414213ef3af9dd1e63401b043e) (int32_t component_id)const | Take one photo. +void | [start_photo_interval_async](#classmavsdk_1_1_camera_1af57a8398e1f2d4ca79368d04bb7c211f) (int32_t component_id, float interval_s, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start photo timelapse with a given interval. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [start_photo_interval](#classmavsdk_1_1_camera_1afb346b7103eebf4b71846c17cda3b5d9) (int32_t component_id, float interval_s)const | Start photo timelapse with a given interval. +void | [stop_photo_interval_async](#classmavsdk_1_1_camera_1af63064187baaa598d1b38545ec28e173) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop a running photo timelapse. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [stop_photo_interval](#classmavsdk_1_1_camera_1a1284b8db67fd8444704680eeb5136915) (int32_t component_id)const | Stop a running photo timelapse. +void | [start_video_async](#classmavsdk_1_1_camera_1af88ebe8c37534ce6cdbc2956a5b7422f) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start a video recording. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [start_video](#classmavsdk_1_1_camera_1a962e0a2b69bedfffc34cdb87dca6ce15) (int32_t component_id)const | Start a video recording. +void | [stop_video_async](#classmavsdk_1_1_camera_1a35e4a079f3f82e936eb592ca926808b4) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop a running video recording. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [stop_video](#classmavsdk_1_1_camera_1a0f5c985d7c2b2d4e32af3ee2d16a2727) (int32_t component_id)const | Stop a running video recording. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [start_video_streaming](#classmavsdk_1_1_camera_1a91530da971787bc240f50171ebbf756d) (int32_t component_id, int32_t stream_id)const | Start video streaming. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [stop_video_streaming](#classmavsdk_1_1_camera_1a3992c4fc3f133904d039e3a9ab035818) (int32_t component_id, int32_t stream_id)const | Stop current video streaming. +void | [set_mode_async](#classmavsdk_1_1_camera_1a46e3a1929048d5ebc3bad7787e0ff72e) (int32_t component_id, [Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) mode, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Set camera mode. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [set_mode](#classmavsdk_1_1_camera_1a0f7421bda8f0a7c7e50865e315a35439) (int32_t component_id, [Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) mode)const | Set camera mode. +void | [list_photos_async](#classmavsdk_1_1_camera_1a8e9e1364079a503c705255b36cd41ff8) (int32_t component_id, [PhotosRange](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) photos_range, const [ListPhotosCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a23240233586f7673c3a1b48f07623fe4) callback) | List photos available on the camera. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) > > | [list_photos](#classmavsdk_1_1_camera_1a775bbe8873c57d789f42b5f59bf2bff0) (int32_t component_id, [PhotosRange](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) photos_range)const | List photos available on the camera. +[CameraListHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aeb7f6082a8f08509e8c45f23768a5a64) | [subscribe_camera_list](#classmavsdk_1_1_camera_1af7de7e428b7d1f95535d27e246be615a) (const [CameraListCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac853b9f8da070d22b1cfe2680f7785d3) & callback) | Subscribe to list of cameras. +void | [unsubscribe_camera_list](#classmavsdk_1_1_camera_1a686168126d1d9b7905f4b9c50504598d) ([CameraListHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aeb7f6082a8f08509e8c45f23768a5a64) handle) | Unsubscribe from subscribe_camera_list. +[CameraList](structmavsdk_1_1_camera_1_1_camera_list.md) | [camera_list](#classmavsdk_1_1_camera_1ac6514ecf820f819076663401e8527f2d) () const | Poll for '[CameraList](structmavsdk_1_1_camera_1_1_camera_list.md)' (blocking). +[ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a71c4937ed9dcc1766561370cfe0f523f) | [subscribe_mode](#classmavsdk_1_1_camera_1a1963bfcfcc8c9e96451648f96fd618cd) (const [ModeCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1af6649645c4056d797b42de9418dc4226) & callback) | Subscribe to camera mode updates. +void | [unsubscribe_mode](#classmavsdk_1_1_camera_1ab9437b41565d8957050e09cf4143f5d1) ([ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a71c4937ed9dcc1766561370cfe0f523f) handle) | Unsubscribe from subscribe_mode. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) > | [get_mode](#classmavsdk_1_1_camera_1a5f6377a669bfb8ad4c0efb310ef9bfd2) (int32_t component_id)const | Get camera mode. +[VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a093e5b2652791c703534f38ca329b198) | [subscribe_video_stream_info](#classmavsdk_1_1_camera_1a4dcf0ebeb1f9f5e5b2b71f59c9b7eeb9) (const [VideoStreamInfoCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a5c9669b2652e37e067c6c5c300c9409b) & callback) | Subscribe to video stream info updates. +void | [unsubscribe_video_stream_info](#classmavsdk_1_1_camera_1abc370783800fb90dda20d2843f990036) ([VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a093e5b2652791c703534f38ca329b198) handle) | Unsubscribe from subscribe_video_stream_info. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) > | [get_video_stream_info](#classmavsdk_1_1_camera_1a08b199c0a0cceb37f55a457d56a6797f) (int32_t component_id)const | Get video stream info. [CaptureInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a789f1fccde8eb44bc07694751b3a1b40) | [subscribe_capture_info](#classmavsdk_1_1_camera_1a8822ab1d802984a1acc9b53cd9810e8f) (const [CaptureInfoCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a9bf5c20ea0b03ab019057829d1a3441e) & callback) | Subscribe to capture info updates. void | [unsubscribe_capture_info](#classmavsdk_1_1_camera_1a9b7f729dfa30a6cb0d041533bd272793) ([CaptureInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a789f1fccde8eb44bc07694751b3a1b40) handle) | Unsubscribe from subscribe_capture_info. -[StatusHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a902bc3a824040a37714bb2c1c41a9601) | [subscribe_status](#classmavsdk_1_1_camera_1a1bf71cdb27a9b8d3fefe15463c9b9bf1) (const [StatusCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aea925914ce854b81b67e3213840c97ad) & callback) | Subscribe to camera status updates. -void | [unsubscribe_status](#classmavsdk_1_1_camera_1a402cf21219f9b303fca0a269dab15b63) ([StatusHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a902bc3a824040a37714bb2c1c41a9601) handle) | Unsubscribe from subscribe_status. -[Status](structmavsdk_1_1_camera_1_1_status.md) | [status](#classmavsdk_1_1_camera_1a0bb78c2b665c28b314f00f11a0f676b1) () const | Poll for '[Status](structmavsdk_1_1_camera_1_1_status.md)' (blocking). -[CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a19960e47f1c2b3fb5117ba2f7f3cfbe6) | [subscribe_current_settings](#classmavsdk_1_1_camera_1a906c431b63dde866b691ab4c839858ff) (const [CurrentSettingsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a77484487381b2579460c36d97d367fe6) & callback) | Get the list of current camera settings. -void | [unsubscribe_current_settings](#classmavsdk_1_1_camera_1a117e76672b39c9cd751fa64a42741c17) ([CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a19960e47f1c2b3fb5117ba2f7f3cfbe6) handle) | Unsubscribe from subscribe_current_settings. -[PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1144be14cd9f15724397ad6b5253b8a9) | [subscribe_possible_setting_options](#classmavsdk_1_1_camera_1aef7c545aaa05e36b212255120557967b) (const [PossibleSettingOptionsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a78e25614c29cd8bc1bbf26adcf417c2a) & callback) | Get the list of settings that can be changed. -void | [unsubscribe_possible_setting_options](#classmavsdk_1_1_camera_1a191cc00bb6b1c834fc93b19f4bff1c29) ([PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1144be14cd9f15724397ad6b5253b8a9) handle) | Unsubscribe from subscribe_possible_setting_options. -std::vector< [SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) > | [possible_setting_options](#classmavsdk_1_1_camera_1a5416dc30ec436707420db715ee56ce08) () const | Poll for 'std::vector< SettingOptions >' (blocking). -void | [set_setting_async](#classmavsdk_1_1_camera_1aace1d6ffd86a6fdf30b3466c8522feba) ([Setting](structmavsdk_1_1_camera_1_1_setting.md) setting, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Set a setting to some value. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [set_setting](#classmavsdk_1_1_camera_1aa4b1293d8c6332293cccde87ec79f64a) ([Setting](structmavsdk_1_1_camera_1_1_setting.md) setting)const | Set a setting to some value. -void | [get_setting_async](#classmavsdk_1_1_camera_1a6b2e4e9b5b304aff313e4f988aa6ba86) ([Setting](structmavsdk_1_1_camera_1_1_setting.md) setting, const [GetSettingCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac233f5688f0b7f1e712bb31dfaeadd85) callback) | Get a setting. -std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Setting](structmavsdk_1_1_camera_1_1_setting.md) > | [get_setting](#classmavsdk_1_1_camera_1ae88917857b666dc7cfd0d84b3ad29d9c) ([Setting](structmavsdk_1_1_camera_1_1_setting.md) setting)const | Get a setting. -void | [format_storage_async](#classmavsdk_1_1_camera_1afd1074b185776167e7355438ac69d955) (int32_t storage_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Format storage (e.g. SD card) in camera. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [format_storage](#classmavsdk_1_1_camera_1a942f9bad2e2bede982d404ce552090a5) (int32_t storage_id)const | Format storage (e.g. SD card) in camera. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [select_camera](#classmavsdk_1_1_camera_1ab3348f98003f71f2399dd15505effae3) (int32_t camera_id)const | Select current camera . -void | [reset_settings_async](#classmavsdk_1_1_camera_1ab2316e20104a5efa94bf2719dc3dd994) (const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Reset all settings in camera. -[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [reset_settings](#classmavsdk_1_1_camera_1a49c84f20f1100848e3951f5e14b569dc) () const | Reset all settings in camera. -const [Camera](classmavsdk_1_1_camera.md) & | [operator=](#classmavsdk_1_1_camera_1aeff295155b6a665f5c942e473f1fe894) (const [Camera](classmavsdk_1_1_camera.md) &)=delete | Equality operator (object is not copyable). +[StorageHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a4707b885d81143f3cb24ca956c1f91c9) | [subscribe_storage](#classmavsdk_1_1_camera_1a3b2c8f2f9512ceb6d456f35e1bf7777f) (const [StorageCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a7811502147e261b81f7f4ea2422fad03) & callback) | Subscribe to camera's storage status updates. +void | [unsubscribe_storage](#classmavsdk_1_1_camera_1a925cab3ea7e34ff2ed5a698598c5edd3) ([StorageHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a4707b885d81143f3cb24ca956c1f91c9) handle) | Unsubscribe from subscribe_storage. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Storage](structmavsdk_1_1_camera_1_1_storage.md) > | [get_storage](#classmavsdk_1_1_camera_1a2e35679fe372bb575a6b3b84dfc82c72) (int32_t component_id)const | Get camera's storage status. +[CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1afa537975f7985f7f7697dc7b4477ccd9) | [subscribe_current_settings](#classmavsdk_1_1_camera_1a906c431b63dde866b691ab4c839858ff) (const [CurrentSettingsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac12104378b90908410ffe100e9fd264e) & callback) | Get the list of current camera settings. +void | [unsubscribe_current_settings](#classmavsdk_1_1_camera_1a117e76672b39c9cd751fa64a42741c17) ([CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1afa537975f7985f7f7697dc7b4477ccd9) handle) | Unsubscribe from subscribe_current_settings. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::Setting](structmavsdk_1_1_camera_1_1_setting.md) > > | [get_current_settings](#classmavsdk_1_1_camera_1a980512b264c8aff8584a12a749d00382) (int32_t component_id)const | Get current settings. +[PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8ebb2da9f006cff11293e7e5a20d2f82) | [subscribe_possible_setting_options](#classmavsdk_1_1_camera_1aef7c545aaa05e36b212255120557967b) (const [PossibleSettingOptionsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a7eec62e8cdab1a2a7e787bbfeb5205e2) & callback) | Get the list of settings that can be changed. +void | [unsubscribe_possible_setting_options](#classmavsdk_1_1_camera_1a191cc00bb6b1c834fc93b19f4bff1c29) ([PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8ebb2da9f006cff11293e7e5a20d2f82) handle) | Unsubscribe from subscribe_possible_setting_options. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) > > | [get_possible_setting_options](#classmavsdk_1_1_camera_1a7c9aa933b7c93a5178cd9e478ee72170) (int32_t component_id)const | Get possible setting options. +void | [set_setting_async](#classmavsdk_1_1_camera_1a5861022cf053c2c347c994e0d0ae62a4) (int32_t component_id, [Setting](structmavsdk_1_1_camera_1_1_setting.md) setting, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Set a setting to some value. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [set_setting](#classmavsdk_1_1_camera_1ab34650789b55900716dd8ea3d81d5a05) (int32_t component_id, [Setting](structmavsdk_1_1_camera_1_1_setting.md) setting)const | Set a setting to some value. +void | [get_setting_async](#classmavsdk_1_1_camera_1a3364fd9b2f48388148620471bc598d85) (int32_t component_id, [Setting](structmavsdk_1_1_camera_1_1_setting.md) setting, const [GetSettingCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac233f5688f0b7f1e712bb31dfaeadd85) callback) | Get a setting. +std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Setting](structmavsdk_1_1_camera_1_1_setting.md) > | [get_setting](#classmavsdk_1_1_camera_1a0e8376bf9c3e4d9367b9e296e808529a) (int32_t component_id, [Setting](structmavsdk_1_1_camera_1_1_setting.md) setting)const | Get a setting. +void | [format_storage_async](#classmavsdk_1_1_camera_1a5ca1864fd62f357187290f753a3e7b89) (int32_t component_id, int32_t storage_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Format storage (e.g. SD card) in camera. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [format_storage](#classmavsdk_1_1_camera_1ad239fe6b8dad6783d1f53c3e8e8212ae) (int32_t component_id, int32_t storage_id)const | Format storage (e.g. SD card) in camera. +void | [reset_settings_async](#classmavsdk_1_1_camera_1a6b558f5e8e6298584883a5622dd0d5eb) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Reset all settings in camera. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [reset_settings](#classmavsdk_1_1_camera_1a6b5ba6cd713705848585d2808ceb53fc) (int32_t component_id)const | Reset all settings in camera. +void | [zoom_in_start_async](#classmavsdk_1_1_camera_1a6ff5149c53d8acc6c4a5f17081b88a15) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start zooming in. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [zoom_in_start](#classmavsdk_1_1_camera_1a71b6535b10a5cf00baf451e4b2e0b6c4) (int32_t component_id)const | Start zooming in. +void | [zoom_out_start_async](#classmavsdk_1_1_camera_1a088b21cec49f800ab666d7409a299937) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start zooming out. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [zoom_out_start](#classmavsdk_1_1_camera_1a72456e28c67ba451921cedf7f11f5954) (int32_t component_id)const | Start zooming out. +void | [zoom_stop_async](#classmavsdk_1_1_camera_1a2a30851420c2d2ceb102692cf917327b) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop zooming. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [zoom_stop](#classmavsdk_1_1_camera_1a30fee70ce5bb42071fcce27841a8a01a) (int32_t component_id)const | Stop zooming. +void | [zoom_range_async](#classmavsdk_1_1_camera_1acce728b12b8e767ee9cc55afb1d4d6ee) (int32_t component_id, float range, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [zoom_range](#classmavsdk_1_1_camera_1ac9a05ffb7a8520c9f9dcb29919878d11) (int32_t component_id, float range)const | Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). +void | [track_point_async](#classmavsdk_1_1_camera_1ac83433124165ec1b3fbe2629a9939617) (int32_t component_id, float point_x, float point_y, float radius, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Track point. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [track_point](#classmavsdk_1_1_camera_1aff70a9533d377b792ede73d1d3bec2fd) (int32_t component_id, float point_x, float point_y, float radius)const | Track point. +void | [track_rectangle_async](#classmavsdk_1_1_camera_1a4fcec80674d2de32934c67a3544130f6) (int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Track rectangle. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [track_rectangle](#classmavsdk_1_1_camera_1a32c338bc723337dcf4229bac94073d03) (int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y)const | Track rectangle. +void | [track_stop_async](#classmavsdk_1_1_camera_1a7b1c720a0a346516af8c1bc3e49210cc) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop tracking. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [track_stop](#classmavsdk_1_1_camera_1a1f4a0c1c2cfcef55cdab94f3d726766f) (int32_t component_id)const | Stop tracking. +void | [focus_in_start_async](#classmavsdk_1_1_camera_1ad40616613df551c00a78099e7790b880) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start focusing in. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [focus_in_start](#classmavsdk_1_1_camera_1a8be24bc7d5c21b94b388bc1eeed2e8fe) (int32_t component_id)const | Start focusing in. +void | [focus_out_start_async](#classmavsdk_1_1_camera_1ad7917d952b7d0e43dba631a152575765) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Start focusing out. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [focus_out_start](#classmavsdk_1_1_camera_1a25b5c34491cb17f40e7c9c4461c37723) (int32_t component_id)const | Start focusing out. +void | [focus_stop_async](#classmavsdk_1_1_camera_1a562ad9fa8f29b359785069a9dc5b8de2) (int32_t component_id, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Stop focus. +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [focus_stop](#classmavsdk_1_1_camera_1aed5b395a57b14da2d15395dfa2e56600) (int32_t component_id)const | Stop focus. +void | [focus_range_async](#classmavsdk_1_1_camera_1a44cebbb36a9bc9c203dc0233f8b52f7b) (int32_t component_id, float range, const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) callback) | Focus with range value of full range (value between 0.0 and 100.0). +[Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) | [focus_range](#classmavsdk_1_1_camera_1aec7d7a0ed5fa2ba84124f9f363e8d94a) (int32_t component_id, float range)const | Focus with range value of full range (value between 0.0 and 100.0). +const [Camera](classmavsdk_1_1_camera.md) & | [operator=](#classmavsdk_1_1_camera_1a358026db44ff9a10cf14a166d8f1da78) (const [Camera](classmavsdk_1_1_camera.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -203,60 +235,60 @@ using mavsdk::Camera::ListPhotosCallback = std::function +using mavsdk::Camera::CameraListCallback = std::function ``` -Callback type for subscribe_mode. +Callback type for subscribe_camera_list. -### typedef ModeHandle {#classmavsdk_1_1_camera_1ac6759725ac9696f9572b05524fde2354} +### typedef CameraListHandle {#classmavsdk_1_1_camera_1aeb7f6082a8f08509e8c45f23768a5a64} ```cpp -using mavsdk::Camera::ModeHandle = Handle +using mavsdk::Camera::CameraListHandle = Handle ``` -[Handle](classmavsdk_1_1_handle.md) type for subscribe_mode. +[Handle](classmavsdk_1_1_handle.md) type for subscribe_camera_list. -### typedef InformationCallback {#classmavsdk_1_1_camera_1af13455249eebaf152a71d59e32fcbf65} +### typedef ModeCallback {#classmavsdk_1_1_camera_1af6649645c4056d797b42de9418dc4226} ```cpp -using mavsdk::Camera::InformationCallback = std::function +using mavsdk::Camera::ModeCallback = std::function ``` -Callback type for subscribe_information. +Callback type for subscribe_mode. -### typedef InformationHandle {#classmavsdk_1_1_camera_1a0dcacb795da7de566fb6dce091ca4605} +### typedef ModeHandle {#classmavsdk_1_1_camera_1a71c4937ed9dcc1766561370cfe0f523f} ```cpp -using mavsdk::Camera::InformationHandle = Handle +using mavsdk::Camera::ModeHandle = Handle ``` -[Handle](classmavsdk_1_1_handle.md) type for subscribe_information. +[Handle](classmavsdk_1_1_handle.md) type for subscribe_mode. -### typedef VideoStreamInfoCallback {#classmavsdk_1_1_camera_1acd9baf073b816e46c22dbd6b599ece66} +### typedef VideoStreamInfoCallback {#classmavsdk_1_1_camera_1a5c9669b2652e37e067c6c5c300c9409b} ```cpp -using mavsdk::Camera::VideoStreamInfoCallback = std::function +using mavsdk::Camera::VideoStreamInfoCallback = std::function ``` Callback type for subscribe_video_stream_info. -### typedef VideoStreamInfoHandle {#classmavsdk_1_1_camera_1aebf91f740cc85682c6b7a0955635f848} +### typedef VideoStreamInfoHandle {#classmavsdk_1_1_camera_1a093e5b2652791c703534f38ca329b198} ```cpp -using mavsdk::Camera::VideoStreamInfoHandle = Handle +using mavsdk::Camera::VideoStreamInfoHandle = Handle ``` @@ -283,60 +315,60 @@ using mavsdk::Camera::CaptureInfoHandle = Handle [Handle](classmavsdk_1_1_handle.md) type for subscribe_capture_info. -### typedef StatusCallback {#classmavsdk_1_1_camera_1aea925914ce854b81b67e3213840c97ad} +### typedef StorageCallback {#classmavsdk_1_1_camera_1a7811502147e261b81f7f4ea2422fad03} ```cpp -using mavsdk::Camera::StatusCallback = std::function +using mavsdk::Camera::StorageCallback = std::function ``` -Callback type for subscribe_status. +Callback type for subscribe_storage. -### typedef StatusHandle {#classmavsdk_1_1_camera_1a902bc3a824040a37714bb2c1c41a9601} +### typedef StorageHandle {#classmavsdk_1_1_camera_1a4707b885d81143f3cb24ca956c1f91c9} ```cpp -using mavsdk::Camera::StatusHandle = Handle +using mavsdk::Camera::StorageHandle = Handle ``` -[Handle](classmavsdk_1_1_handle.md) type for subscribe_status. +[Handle](classmavsdk_1_1_handle.md) type for subscribe_storage. -### typedef CurrentSettingsCallback {#classmavsdk_1_1_camera_1a77484487381b2579460c36d97d367fe6} +### typedef CurrentSettingsCallback {#classmavsdk_1_1_camera_1ac12104378b90908410ffe100e9fd264e} ```cpp -using mavsdk::Camera::CurrentSettingsCallback = std::function)> +using mavsdk::Camera::CurrentSettingsCallback = std::function ``` Callback type for subscribe_current_settings. -### typedef CurrentSettingsHandle {#classmavsdk_1_1_camera_1a19960e47f1c2b3fb5117ba2f7f3cfbe6} +### typedef CurrentSettingsHandle {#classmavsdk_1_1_camera_1afa537975f7985f7f7697dc7b4477ccd9} ```cpp -using mavsdk::Camera::CurrentSettingsHandle = Handle > +using mavsdk::Camera::CurrentSettingsHandle = Handle ``` [Handle](classmavsdk_1_1_handle.md) type for subscribe_current_settings. -### typedef PossibleSettingOptionsCallback {#classmavsdk_1_1_camera_1a78e25614c29cd8bc1bbf26adcf417c2a} +### typedef PossibleSettingOptionsCallback {#classmavsdk_1_1_camera_1a7eec62e8cdab1a2a7e787bbfeb5205e2} ```cpp -using mavsdk::Camera::PossibleSettingOptionsCallback = std::function)> +using mavsdk::Camera::PossibleSettingOptionsCallback = std::function ``` Callback type for subscribe_possible_setting_options. -### typedef PossibleSettingOptionsHandle {#classmavsdk_1_1_camera_1a1144be14cd9f15724397ad6b5253b8a9} +### typedef PossibleSettingOptionsHandle {#classmavsdk_1_1_camera_1a8ebb2da9f006cff11293e7e5a20d2f82} ```cpp -using mavsdk::Camera::PossibleSettingOptionsHandle = Handle > +using mavsdk::Camera::PossibleSettingOptionsHandle = Handle ``` @@ -397,41 +429,16 @@ Value | Description `WrongArgument` | Command has wrong argument(s). `NoSystem` | No system connected. `ProtocolUnsupported` | Definition file protocol not supported. + `Unavailable` | Not available (yet). + `CameraIdInvalid` | [Camera](classmavsdk_1_1_camera.md) with camera ID not found. + `ActionUnsupported` | [Camera](classmavsdk_1_1_camera.md) action not supported. ## Member Function Documentation -### prepare_async() {#classmavsdk_1_1_camera_1aba33f1f8302259a7d51a09b60ea29cbf} -```cpp -void mavsdk::Camera::prepare_async(const ResultCallback callback) -``` - - -Prepare the camera plugin (e.g. download the camera definition, etc). - -This function is non-blocking. See 'prepare' for the blocking counterpart. - -**Parameters** - -* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - - -### prepare() {#classmavsdk_1_1_camera_1af263d3ea4e24da262f935c56fb578444} +### take_photo_async() {#classmavsdk_1_1_camera_1ae7a59d768c597fbee8eff47073dd8690} ```cpp -Result mavsdk::Camera::prepare() const -``` - - -Prepare the camera plugin (e.g. download the camera definition, etc). - -This function is blocking. See 'prepare_async' for the non-blocking counterpart. - -**Returns** - - [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. - -### take_photo_async() {#classmavsdk_1_1_camera_1a343217bf38cc71cd258c7e81626dccb5} -```cpp -void mavsdk::Camera::take_photo_async(const ResultCallback callback) +void mavsdk::Camera::take_photo_async(int32_t component_id, const ResultCallback callback) ``` @@ -441,11 +448,12 @@ This function is non-blocking. See 'take_photo' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### take_photo() {#classmavsdk_1_1_camera_1a44b86cfda6262652a1796661e595003c} +### take_photo() {#classmavsdk_1_1_camera_1ae06036414213ef3af9dd1e63401b043e} ```cpp -Result mavsdk::Camera::take_photo() const +Result mavsdk::Camera::take_photo(int32_t component_id) const ``` @@ -453,13 +461,17 @@ Take one photo. This function is blocking. See 'take_photo_async' for the non-blocking counterpart. +**Parameters** + +* int32_t **component_id** - + **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### start_photo_interval_async() {#classmavsdk_1_1_camera_1ae583f83e163e2b33a8dc4a6fcfebbac6} +### start_photo_interval_async() {#classmavsdk_1_1_camera_1af57a8398e1f2d4ca79368d04bb7c211f} ```cpp -void mavsdk::Camera::start_photo_interval_async(float interval_s, const ResultCallback callback) +void mavsdk::Camera::start_photo_interval_async(int32_t component_id, float interval_s, const ResultCallback callback) ``` @@ -469,12 +481,13 @@ This function is non-blocking. See 'start_photo_interval' for the blocking count **Parameters** +* int32_t **component_id** - * float **interval_s** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### start_photo_interval() {#classmavsdk_1_1_camera_1adfa32eb338aabf19675a1218fc28d8bc} +### start_photo_interval() {#classmavsdk_1_1_camera_1afb346b7103eebf4b71846c17cda3b5d9} ```cpp -Result mavsdk::Camera::start_photo_interval(float interval_s) const +Result mavsdk::Camera::start_photo_interval(int32_t component_id, float interval_s) const ``` @@ -484,15 +497,16 @@ This function is blocking. See 'start_photo_interval_async' for the non-blocking **Parameters** +* int32_t **component_id** - * float **interval_s** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### stop_photo_interval_async() {#classmavsdk_1_1_camera_1a540d94eb58efe02fdd3659994c778203} +### stop_photo_interval_async() {#classmavsdk_1_1_camera_1af63064187baaa598d1b38545ec28e173} ```cpp -void mavsdk::Camera::stop_photo_interval_async(const ResultCallback callback) +void mavsdk::Camera::stop_photo_interval_async(int32_t component_id, const ResultCallback callback) ``` @@ -502,11 +516,12 @@ This function is non-blocking. See 'stop_photo_interval' for the blocking counte **Parameters** +* int32_t **component_id** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### stop_photo_interval() {#classmavsdk_1_1_camera_1a287fa0fd3fcda1dee2cf40ad041d524a} +### stop_photo_interval() {#classmavsdk_1_1_camera_1a1284b8db67fd8444704680eeb5136915} ```cpp -Result mavsdk::Camera::stop_photo_interval() const +Result mavsdk::Camera::stop_photo_interval(int32_t component_id) const ``` @@ -514,13 +529,17 @@ Stop a running photo timelapse. This function is blocking. See 'stop_photo_interval_async' for the non-blocking counterpart. +**Parameters** + +* int32_t **component_id** - + **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### start_video_async() {#classmavsdk_1_1_camera_1a2d5dff782ea3f8346bc53560be368531} +### start_video_async() {#classmavsdk_1_1_camera_1af88ebe8c37534ce6cdbc2956a5b7422f} ```cpp -void mavsdk::Camera::start_video_async(const ResultCallback callback) +void mavsdk::Camera::start_video_async(int32_t component_id, const ResultCallback callback) ``` @@ -530,11 +549,12 @@ This function is non-blocking. See 'start_video' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### start_video() {#classmavsdk_1_1_camera_1ac64e77dee9f5ff9b5c84100d8f007670} +### start_video() {#classmavsdk_1_1_camera_1a962e0a2b69bedfffc34cdb87dca6ce15} ```cpp -Result mavsdk::Camera::start_video() const +Result mavsdk::Camera::start_video(int32_t component_id) const ``` @@ -542,13 +562,17 @@ Start a video recording. This function is blocking. See 'start_video_async' for the non-blocking counterpart. +**Parameters** + +* int32_t **component_id** - + **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### stop_video_async() {#classmavsdk_1_1_camera_1a77d1b1a201164023c5eef3c91cdd4e54} +### stop_video_async() {#classmavsdk_1_1_camera_1a35e4a079f3f82e936eb592ca926808b4} ```cpp -void mavsdk::Camera::stop_video_async(const ResultCallback callback) +void mavsdk::Camera::stop_video_async(int32_t component_id, const ResultCallback callback) ``` @@ -558,11 +582,12 @@ This function is non-blocking. See 'stop_video' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### stop_video() {#classmavsdk_1_1_camera_1a6062ac1907bd10944d2ddb9655943ddc} +### stop_video() {#classmavsdk_1_1_camera_1a0f5c985d7c2b2d4e32af3ee2d16a2727} ```cpp -Result mavsdk::Camera::stop_video() const +Result mavsdk::Camera::stop_video(int32_t component_id) const ``` @@ -570,13 +595,17 @@ Stop a running video recording. This function is blocking. See 'stop_video_async' for the non-blocking counterpart. +**Parameters** + +* int32_t **component_id** - + **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### start_video_streaming() {#classmavsdk_1_1_camera_1a6e062242a02389e2fc839f5e9ec03d7d} +### start_video_streaming() {#classmavsdk_1_1_camera_1a91530da971787bc240f50171ebbf756d} ```cpp -Result mavsdk::Camera::start_video_streaming(int32_t stream_id) const +Result mavsdk::Camera::start_video_streaming(int32_t component_id, int32_t stream_id) const ``` @@ -586,15 +615,16 @@ This function is blocking. **Parameters** +* int32_t **component_id** - * int32_t **stream_id** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### stop_video_streaming() {#classmavsdk_1_1_camera_1ae495e8c52984ad76b27b72fc58987d9d} +### stop_video_streaming() {#classmavsdk_1_1_camera_1a3992c4fc3f133904d039e3a9ab035818} ```cpp -Result mavsdk::Camera::stop_video_streaming(int32_t stream_id) const +Result mavsdk::Camera::stop_video_streaming(int32_t component_id, int32_t stream_id) const ``` @@ -604,15 +634,16 @@ This function is blocking. **Parameters** +* int32_t **component_id** - * int32_t **stream_id** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### set_mode_async() {#classmavsdk_1_1_camera_1a76d98d04885d38d0438da7c8696ef6ab} +### set_mode_async() {#classmavsdk_1_1_camera_1a46e3a1929048d5ebc3bad7787e0ff72e} ```cpp -void mavsdk::Camera::set_mode_async(Mode mode, const ResultCallback callback) +void mavsdk::Camera::set_mode_async(int32_t component_id, Mode mode, const ResultCallback callback) ``` @@ -622,12 +653,13 @@ This function is non-blocking. See 'set_mode' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * [Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) **mode** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### set_mode() {#classmavsdk_1_1_camera_1a249755db2eaa8fd3d202ac01ca52448d} +### set_mode() {#classmavsdk_1_1_camera_1a0f7421bda8f0a7c7e50865e315a35439} ```cpp -Result mavsdk::Camera::set_mode(Mode mode) const +Result mavsdk::Camera::set_mode(int32_t component_id, Mode mode) const ``` @@ -637,130 +669,145 @@ This function is blocking. See 'set_mode_async' for the non-blocking counterpart **Parameters** +* int32_t **component_id** - * [Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) **mode** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### list_photos_async() {#classmavsdk_1_1_camera_1aec1edfe505476d437d45ec2f0deec924} +### list_photos_async() {#classmavsdk_1_1_camera_1a8e9e1364079a503c705255b36cd41ff8} ```cpp -void mavsdk::Camera::list_photos_async(PhotosRange photos_range, const ListPhotosCallback callback) +void mavsdk::Camera::list_photos_async(int32_t component_id, PhotosRange photos_range, const ListPhotosCallback callback) ``` List photos available on the camera. +Note that this might need to be called initially to set the PhotosRange accordingly. Once set to 'all' rather than 'since connection', it will try to request the previous images over time. + + This function is non-blocking. See 'list_photos' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * [PhotosRange](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) **photos_range** - * const [ListPhotosCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a23240233586f7673c3a1b48f07623fe4) **callback** - -### list_photos() {#classmavsdk_1_1_camera_1a49dc17b74047049c386d88cd365de868} +### list_photos() {#classmavsdk_1_1_camera_1a775bbe8873c57d789f42b5f59bf2bff0} ```cpp -std::pair > mavsdk::Camera::list_photos(PhotosRange photos_range) const +std::pair< Result, std::vector< Camera::CaptureInfo > > mavsdk::Camera::list_photos(int32_t component_id, PhotosRange photos_range) const ``` List photos available on the camera. +Note that this might need to be called initially to set the PhotosRange accordingly. Once set to 'all' rather than 'since connection', it will try to request the previous images over time. + + This function is blocking. See 'list_photos_async' for the non-blocking counterpart. **Parameters** +* int32_t **component_id** - * [PhotosRange](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1211ea6664aa9c1d4ef4aede363c7c22) **photos_range** - **Returns**  std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) > > - Result of request. -### subscribe_mode() {#classmavsdk_1_1_camera_1a1963bfcfcc8c9e96451648f96fd618cd} +### subscribe_camera_list() {#classmavsdk_1_1_camera_1af7de7e428b7d1f95535d27e246be615a} ```cpp -ModeHandle mavsdk::Camera::subscribe_mode(const ModeCallback &callback) +CameraListHandle mavsdk::Camera::subscribe_camera_list(const CameraListCallback &callback) ``` -Subscribe to camera mode updates. +Subscribe to list of cameras. +This allows to find out what cameras are connected to the system. Based on the camera ID, we can then address a specific camera. **Parameters** -* const [ModeCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a33a7257ab95d9277b786e6de86604931)& **callback** - +* const [CameraListCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac853b9f8da070d22b1cfe2680f7785d3)& **callback** - **Returns** - [ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac6759725ac9696f9572b05524fde2354) - + [CameraListHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aeb7f6082a8f08509e8c45f23768a5a64) - -### unsubscribe_mode() {#classmavsdk_1_1_camera_1ab9437b41565d8957050e09cf4143f5d1} +### unsubscribe_camera_list() {#classmavsdk_1_1_camera_1a686168126d1d9b7905f4b9c50504598d} ```cpp -void mavsdk::Camera::unsubscribe_mode(ModeHandle handle) +void mavsdk::Camera::unsubscribe_camera_list(CameraListHandle handle) ``` -Unsubscribe from subscribe_mode. +Unsubscribe from subscribe_camera_list. **Parameters** -* [ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac6759725ac9696f9572b05524fde2354) **handle** - +* [CameraListHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aeb7f6082a8f08509e8c45f23768a5a64) **handle** - -### mode() {#classmavsdk_1_1_camera_1a222bce91e70d1ca53bcf5d885bacd418} +### camera_list() {#classmavsdk_1_1_camera_1ac6514ecf820f819076663401e8527f2d} ```cpp -Mode mavsdk::Camera::mode() const +CameraList mavsdk::Camera::camera_list() const ``` -Poll for 'Mode' (blocking). +Poll for '[CameraList](structmavsdk_1_1_camera_1_1_camera_list.md)' (blocking). **Returns** - [Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) - One Mode update. + [CameraList](structmavsdk_1_1_camera_1_1_camera_list.md) - One [CameraList](structmavsdk_1_1_camera_1_1_camera_list.md) update. -### subscribe_information() {#classmavsdk_1_1_camera_1af4b5c713813df8c407a09963295c33a2} +### subscribe_mode() {#classmavsdk_1_1_camera_1a1963bfcfcc8c9e96451648f96fd618cd} ```cpp -InformationHandle mavsdk::Camera::subscribe_information(const InformationCallback &callback) +ModeHandle mavsdk::Camera::subscribe_mode(const ModeCallback &callback) ``` -Subscribe to camera information updates. +Subscribe to camera mode updates. **Parameters** -* const [InformationCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1af13455249eebaf152a71d59e32fcbf65)& **callback** - +* const [ModeCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1af6649645c4056d797b42de9418dc4226)& **callback** - **Returns** - [InformationHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a0dcacb795da7de566fb6dce091ca4605) - + [ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a71c4937ed9dcc1766561370cfe0f523f) - -### unsubscribe_information() {#classmavsdk_1_1_camera_1a90b70deaf25dff027714afb856653ea5} +### unsubscribe_mode() {#classmavsdk_1_1_camera_1ab9437b41565d8957050e09cf4143f5d1} ```cpp -void mavsdk::Camera::unsubscribe_information(InformationHandle handle) +void mavsdk::Camera::unsubscribe_mode(ModeHandle handle) ``` -Unsubscribe from subscribe_information. +Unsubscribe from subscribe_mode. **Parameters** -* [InformationHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a0dcacb795da7de566fb6dce091ca4605) **handle** - +* [ModeHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a71c4937ed9dcc1766561370cfe0f523f) **handle** - -### information() {#classmavsdk_1_1_camera_1a7feb16f3d913b91d05efc803ce4e396b} +### get_mode() {#classmavsdk_1_1_camera_1a5f6377a669bfb8ad4c0efb310ef9bfd2} ```cpp -Information mavsdk::Camera::information() const +std::pair< Result, Camera::Mode > mavsdk::Camera::get_mode(int32_t component_id) const ``` -Poll for '[Information](structmavsdk_1_1_camera_1_1_information.md)' (blocking). +Get camera mode. +This function is blocking. + +**Parameters** + +* int32_t **component_id** - **Returns** - [Information](structmavsdk_1_1_camera_1_1_information.md) - One [Information](structmavsdk_1_1_camera_1_1_information.md) update. + std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) > - Result of request. ### subscribe_video_stream_info() {#classmavsdk_1_1_camera_1a4dcf0ebeb1f9f5e5b2b71f59c9b7eeb9} ```cpp @@ -773,11 +820,11 @@ Subscribe to video stream info updates. **Parameters** -* const [VideoStreamInfoCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1acd9baf073b816e46c22dbd6b599ece66)& **callback** - +* const [VideoStreamInfoCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a5c9669b2652e37e067c6c5c300c9409b)& **callback** - **Returns** - [VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aebf91f740cc85682c6b7a0955635f848) - + [VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a093e5b2652791c703534f38ca329b198) - ### unsubscribe_video_stream_info() {#classmavsdk_1_1_camera_1abc370783800fb90dda20d2843f990036} ```cpp @@ -790,20 +837,25 @@ Unsubscribe from subscribe_video_stream_info. **Parameters** -* [VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aebf91f740cc85682c6b7a0955635f848) **handle** - +* [VideoStreamInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a093e5b2652791c703534f38ca329b198) **handle** - -### video_stream_info() {#classmavsdk_1_1_camera_1ad466621feff2d4f0f11124a36dda656c} +### get_video_stream_info() {#classmavsdk_1_1_camera_1a08b199c0a0cceb37f55a457d56a6797f} ```cpp -VideoStreamInfo mavsdk::Camera::video_stream_info() const +std::pair< Result, Camera::VideoStreamInfo > mavsdk::Camera::get_video_stream_info(int32_t component_id) const ``` -Poll for '[VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md)' (blocking). +Get video stream info. +This function is blocking. + +**Parameters** + +* int32_t **component_id** - **Returns** - [VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) - One [VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) update. + std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) > - Result of request. ### subscribe_capture_info() {#classmavsdk_1_1_camera_1a8822ab1d802984a1acc9b53cd9810e8f} ```cpp @@ -835,48 +887,53 @@ Unsubscribe from subscribe_capture_info. * [CaptureInfoHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a789f1fccde8eb44bc07694751b3a1b40) **handle** - -### subscribe_status() {#classmavsdk_1_1_camera_1a1bf71cdb27a9b8d3fefe15463c9b9bf1} +### subscribe_storage() {#classmavsdk_1_1_camera_1a3b2c8f2f9512ceb6d456f35e1bf7777f} ```cpp -StatusHandle mavsdk::Camera::subscribe_status(const StatusCallback &callback) +StorageHandle mavsdk::Camera::subscribe_storage(const StorageCallback &callback) ``` -Subscribe to camera status updates. +Subscribe to camera's storage status updates. **Parameters** -* const [StatusCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1aea925914ce854b81b67e3213840c97ad)& **callback** - +* const [StorageCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a7811502147e261b81f7f4ea2422fad03)& **callback** - **Returns** - [StatusHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a902bc3a824040a37714bb2c1c41a9601) - + [StorageHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a4707b885d81143f3cb24ca956c1f91c9) - -### unsubscribe_status() {#classmavsdk_1_1_camera_1a402cf21219f9b303fca0a269dab15b63} +### unsubscribe_storage() {#classmavsdk_1_1_camera_1a925cab3ea7e34ff2ed5a698598c5edd3} ```cpp -void mavsdk::Camera::unsubscribe_status(StatusHandle handle) +void mavsdk::Camera::unsubscribe_storage(StorageHandle handle) ``` -Unsubscribe from subscribe_status. +Unsubscribe from subscribe_storage. **Parameters** -* [StatusHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a902bc3a824040a37714bb2c1c41a9601) **handle** - +* [StorageHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a4707b885d81143f3cb24ca956c1f91c9) **handle** - -### status() {#classmavsdk_1_1_camera_1a0bb78c2b665c28b314f00f11a0f676b1} +### get_storage() {#classmavsdk_1_1_camera_1a2e35679fe372bb575a6b3b84dfc82c72} ```cpp -Status mavsdk::Camera::status() const +std::pair< Result, Camera::Storage > mavsdk::Camera::get_storage(int32_t component_id) const ``` -Poll for '[Status](structmavsdk_1_1_camera_1_1_status.md)' (blocking). +Get camera's storage status. + +This function is blocking. + +**Parameters** +* int32_t **component_id** - **Returns** - [Status](structmavsdk_1_1_camera_1_1_status.md) - One [Status](structmavsdk_1_1_camera_1_1_status.md) update. + std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Storage](structmavsdk_1_1_camera_1_1_storage.md) > - Result of request. ### subscribe_current_settings() {#classmavsdk_1_1_camera_1a906c431b63dde866b691ab4c839858ff} ```cpp @@ -889,11 +946,11 @@ Get the list of current camera settings. **Parameters** -* const [CurrentSettingsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a77484487381b2579460c36d97d367fe6)& **callback** - +* const [CurrentSettingsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac12104378b90908410ffe100e9fd264e)& **callback** - **Returns** - [CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a19960e47f1c2b3fb5117ba2f7f3cfbe6) - + [CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1afa537975f7985f7f7697dc7b4477ccd9) - ### unsubscribe_current_settings() {#classmavsdk_1_1_camera_1a117e76672b39c9cd751fa64a42741c17} ```cpp @@ -906,7 +963,25 @@ Unsubscribe from subscribe_current_settings. **Parameters** -* [CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a19960e47f1c2b3fb5117ba2f7f3cfbe6) **handle** - +* [CurrentSettingsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1afa537975f7985f7f7697dc7b4477ccd9) **handle** - + +### get_current_settings() {#classmavsdk_1_1_camera_1a980512b264c8aff8584a12a749d00382} +```cpp +std::pair< Result, std::vector< Camera::Setting > > mavsdk::Camera::get_current_settings(int32_t component_id) const +``` + + +Get current settings. + +This function is blocking. + +**Parameters** + +* int32_t **component_id** - + +**Returns** + + std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::Setting](structmavsdk_1_1_camera_1_1_setting.md) > > - Result of request. ### subscribe_possible_setting_options() {#classmavsdk_1_1_camera_1aef7c545aaa05e36b212255120557967b} ```cpp @@ -919,11 +994,11 @@ Get the list of settings that can be changed. **Parameters** -* const [PossibleSettingOptionsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a78e25614c29cd8bc1bbf26adcf417c2a)& **callback** - +* const [PossibleSettingOptionsCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a7eec62e8cdab1a2a7e787bbfeb5205e2)& **callback** - **Returns** - [PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1144be14cd9f15724397ad6b5253b8a9) - + [PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8ebb2da9f006cff11293e7e5a20d2f82) - ### unsubscribe_possible_setting_options() {#classmavsdk_1_1_camera_1a191cc00bb6b1c834fc93b19f4bff1c29} ```cpp @@ -936,24 +1011,29 @@ Unsubscribe from subscribe_possible_setting_options. **Parameters** -* [PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a1144be14cd9f15724397ad6b5253b8a9) **handle** - +* [PossibleSettingOptionsHandle](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8ebb2da9f006cff11293e7e5a20d2f82) **handle** - -### possible_setting_options() {#classmavsdk_1_1_camera_1a5416dc30ec436707420db715ee56ce08} +### get_possible_setting_options() {#classmavsdk_1_1_camera_1a7c9aa933b7c93a5178cd9e478ee72170} ```cpp -std::vector mavsdk::Camera::possible_setting_options() const +std::pair< Result, std::vector< Camera::SettingOptions > > mavsdk::Camera::get_possible_setting_options(int32_t component_id) const ``` -Poll for 'std::vector< SettingOptions >' (blocking). +Get possible setting options. +This function is blocking. + +**Parameters** + +* int32_t **component_id** - **Returns** - std::vector< [SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) > - One std::vector< SettingOptions > update. + std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), std::vector< [Camera::SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) > > - Result of request. -### set_setting_async() {#classmavsdk_1_1_camera_1aace1d6ffd86a6fdf30b3466c8522feba} +### set_setting_async() {#classmavsdk_1_1_camera_1a5861022cf053c2c347c994e0d0ae62a4} ```cpp -void mavsdk::Camera::set_setting_async(Setting setting, const ResultCallback callback) +void mavsdk::Camera::set_setting_async(int32_t component_id, Setting setting, const ResultCallback callback) ``` @@ -966,12 +1046,13 @@ This function is non-blocking. See 'set_setting' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * [Setting](structmavsdk_1_1_camera_1_1_setting.md) **setting** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### set_setting() {#classmavsdk_1_1_camera_1aa4b1293d8c6332293cccde87ec79f64a} +### set_setting() {#classmavsdk_1_1_camera_1ab34650789b55900716dd8ea3d81d5a05} ```cpp -Result mavsdk::Camera::set_setting(Setting setting) const +Result mavsdk::Camera::set_setting(int32_t component_id, Setting setting) const ``` @@ -984,15 +1065,16 @@ This function is blocking. See 'set_setting_async' for the non-blocking counterp **Parameters** +* int32_t **component_id** - * [Setting](structmavsdk_1_1_camera_1_1_setting.md) **setting** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### get_setting_async() {#classmavsdk_1_1_camera_1a6b2e4e9b5b304aff313e4f988aa6ba86} +### get_setting_async() {#classmavsdk_1_1_camera_1a3364fd9b2f48388148620471bc598d85} ```cpp -void mavsdk::Camera::get_setting_async(Setting setting, const GetSettingCallback callback) +void mavsdk::Camera::get_setting_async(int32_t component_id, Setting setting, const GetSettingCallback callback) ``` @@ -1005,12 +1087,13 @@ This function is non-blocking. See 'get_setting' for the blocking counterpart. **Parameters** +* int32_t **component_id** - * [Setting](structmavsdk_1_1_camera_1_1_setting.md) **setting** - * const [GetSettingCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1ac233f5688f0b7f1e712bb31dfaeadd85) **callback** - -### get_setting() {#classmavsdk_1_1_camera_1ae88917857b666dc7cfd0d84b3ad29d9c} +### get_setting() {#classmavsdk_1_1_camera_1a0e8376bf9c3e4d9367b9e296e808529a} ```cpp -std::pair mavsdk::Camera::get_setting(Setting setting) const +std::pair< Result, Camera::Setting > mavsdk::Camera::get_setting(int32_t component_id, Setting setting) const ``` @@ -1023,15 +1106,16 @@ This function is blocking. See 'get_setting_async' for the non-blocking counterp **Parameters** +* int32_t **component_id** - * [Setting](structmavsdk_1_1_camera_1_1_setting.md) **setting** - **Returns**  std::pair< [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf), [Camera::Setting](structmavsdk_1_1_camera_1_1_setting.md) > - Result of request. -### format_storage_async() {#classmavsdk_1_1_camera_1afd1074b185776167e7355438ac69d955} +### format_storage_async() {#classmavsdk_1_1_camera_1a5ca1864fd62f357187290f753a3e7b89} ```cpp -void mavsdk::Camera::format_storage_async(int32_t storage_id, const ResultCallback callback) +void mavsdk::Camera::format_storage_async(int32_t component_id, int32_t storage_id, const ResultCallback callback) ``` @@ -1044,12 +1128,13 @@ This function is non-blocking. See 'format_storage' for the blocking counterpart **Parameters** +* int32_t **component_id** - * int32_t **storage_id** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### format_storage() {#classmavsdk_1_1_camera_1a942f9bad2e2bede982d404ce552090a5} +### format_storage() {#classmavsdk_1_1_camera_1ad239fe6b8dad6783d1f53c3e8e8212ae} ```cpp -Result mavsdk::Camera::format_storage(int32_t storage_id) const +Result mavsdk::Camera::format_storage(int32_t component_id, int32_t storage_id) const ``` @@ -1062,70 +1147,436 @@ This function is blocking. See 'format_storage_async' for the non-blocking count **Parameters** +* int32_t **component_id** - * int32_t **storage_id** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### select_camera() {#classmavsdk_1_1_camera_1ab3348f98003f71f2399dd15505effae3} +### reset_settings_async() {#classmavsdk_1_1_camera_1a6b558f5e8e6298584883a5622dd0d5eb} ```cpp -Result mavsdk::Camera::select_camera(int32_t camera_id) const +void mavsdk::Camera::reset_settings_async(int32_t component_id, const ResultCallback callback) ``` -Select current camera . +Reset all settings in camera. + +This will reset all camera settings to default value -Bind the plugin instance to a specific camera_id +This function is non-blocking. See 'reset_settings' for the blocking counterpart. -This function is blocking. +**Parameters** + +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### reset_settings() {#classmavsdk_1_1_camera_1a6b5ba6cd713705848585d2808ceb53fc} +```cpp +Result mavsdk::Camera::reset_settings(int32_t component_id) const +``` + + +Reset all settings in camera. + +This will reset all camera settings to default value + + +This function is blocking. See 'reset_settings_async' for the non-blocking counterpart. **Parameters** -* int32_t **camera_id** - +* int32_t **component_id** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### reset_settings_async() {#classmavsdk_1_1_camera_1ab2316e20104a5efa94bf2719dc3dd994} +### zoom_in_start_async() {#classmavsdk_1_1_camera_1a6ff5149c53d8acc6c4a5f17081b88a15} ```cpp -void mavsdk::Camera::reset_settings_async(const ResultCallback callback) +void mavsdk::Camera::zoom_in_start_async(int32_t component_id, const ResultCallback callback) ``` -Reset all settings in camera. +Start zooming in. -This will reset all camera settings to default value +This function is non-blocking. See 'zoom_in_start' for the blocking counterpart. +**Parameters** -This function is non-blocking. See 'reset_settings' for the blocking counterpart. +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### zoom_in_start() {#classmavsdk_1_1_camera_1a71b6535b10a5cf00baf451e4b2e0b6c4} +```cpp +Result mavsdk::Camera::zoom_in_start(int32_t component_id) const +``` + + +Start zooming in. + +This function is blocking. See 'zoom_in_start_async' for the non-blocking counterpart. **Parameters** +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### zoom_out_start_async() {#classmavsdk_1_1_camera_1a088b21cec49f800ab666d7409a299937} +```cpp +void mavsdk::Camera::zoom_out_start_async(int32_t component_id, const ResultCallback callback) +``` + + +Start zooming out. + +This function is non-blocking. See 'zoom_out_start' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - * const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - -### reset_settings() {#classmavsdk_1_1_camera_1a49c84f20f1100848e3951f5e14b569dc} +### zoom_out_start() {#classmavsdk_1_1_camera_1a72456e28c67ba451921cedf7f11f5954} ```cpp -Result mavsdk::Camera::reset_settings() const +Result mavsdk::Camera::zoom_out_start(int32_t component_id) const ``` -Reset all settings in camera. +Start zooming out. -This will reset all camera settings to default value +This function is blocking. See 'zoom_out_start_async' for the non-blocking counterpart. +**Parameters** -This function is blocking. See 'reset_settings_async' for the non-blocking counterpart. +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### zoom_stop_async() {#classmavsdk_1_1_camera_1a2a30851420c2d2ceb102692cf917327b} +```cpp +void mavsdk::Camera::zoom_stop_async(int32_t component_id, const ResultCallback callback) +``` + + +Stop zooming. + +This function is non-blocking. See 'zoom_stop' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### zoom_stop() {#classmavsdk_1_1_camera_1a30fee70ce5bb42071fcce27841a8a01a} +```cpp +Result mavsdk::Camera::zoom_stop(int32_t component_id) const +``` + + +Stop zooming. + +This function is blocking. See 'zoom_stop_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### zoom_range_async() {#classmavsdk_1_1_camera_1acce728b12b8e767ee9cc55afb1d4d6ee} +```cpp +void mavsdk::Camera::zoom_range_async(int32_t component_id, float range, const ResultCallback callback) +``` + + +Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + +This function is non-blocking. See 'zoom_range' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **range** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### zoom_range() {#classmavsdk_1_1_camera_1ac9a05ffb7a8520c9f9dcb29919878d11} +```cpp +Result mavsdk::Camera::zoom_range(int32_t component_id, float range) const +``` + + +Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + +This function is blocking. See 'zoom_range_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **range** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### track_point_async() {#classmavsdk_1_1_camera_1ac83433124165ec1b3fbe2629a9939617} +```cpp +void mavsdk::Camera::track_point_async(int32_t component_id, float point_x, float point_y, float radius, const ResultCallback callback) +``` + + +Track point. + +This function is non-blocking. See 'track_point' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **point_x** - +* float **point_y** - +* float **radius** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### track_point() {#classmavsdk_1_1_camera_1aff70a9533d377b792ede73d1d3bec2fd} +```cpp +Result mavsdk::Camera::track_point(int32_t component_id, float point_x, float point_y, float radius) const +``` + + +Track point. + +This function is blocking. See 'track_point_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **point_x** - +* float **point_y** - +* float **radius** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### track_rectangle_async() {#classmavsdk_1_1_camera_1a4fcec80674d2de32934c67a3544130f6} +```cpp +void mavsdk::Camera::track_rectangle_async(int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y, const ResultCallback callback) +``` + + +Track rectangle. + +This function is non-blocking. See 'track_rectangle' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **top_left_x** - +* float **top_left_y** - +* float **bottom_right_x** - +* float **bottom_right_y** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### track_rectangle() {#classmavsdk_1_1_camera_1a32c338bc723337dcf4229bac94073d03} +```cpp +Result mavsdk::Camera::track_rectangle(int32_t component_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) const +``` + + +Track rectangle. + +This function is blocking. See 'track_rectangle_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **top_left_x** - +* float **top_left_y** - +* float **bottom_right_x** - +* float **bottom_right_y** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### track_stop_async() {#classmavsdk_1_1_camera_1a7b1c720a0a346516af8c1bc3e49210cc} +```cpp +void mavsdk::Camera::track_stop_async(int32_t component_id, const ResultCallback callback) +``` + + +Stop tracking. + +This function is non-blocking. See 'track_stop' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### track_stop() {#classmavsdk_1_1_camera_1a1f4a0c1c2cfcef55cdab94f3d726766f} +```cpp +Result mavsdk::Camera::track_stop(int32_t component_id) const +``` + + +Stop tracking. + +This function is blocking. See 'track_stop_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### focus_in_start_async() {#classmavsdk_1_1_camera_1ad40616613df551c00a78099e7790b880} +```cpp +void mavsdk::Camera::focus_in_start_async(int32_t component_id, const ResultCallback callback) +``` + + +Start focusing in. + +This function is non-blocking. See 'focus_in_start' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### focus_in_start() {#classmavsdk_1_1_camera_1a8be24bc7d5c21b94b388bc1eeed2e8fe} +```cpp +Result mavsdk::Camera::focus_in_start(int32_t component_id) const +``` + + +Start focusing in. + +This function is blocking. See 'focus_in_start_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### focus_out_start_async() {#classmavsdk_1_1_camera_1ad7917d952b7d0e43dba631a152575765} +```cpp +void mavsdk::Camera::focus_out_start_async(int32_t component_id, const ResultCallback callback) +``` + + +Start focusing out. + +This function is non-blocking. See 'focus_out_start' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### focus_out_start() {#classmavsdk_1_1_camera_1a25b5c34491cb17f40e7c9c4461c37723} +```cpp +Result mavsdk::Camera::focus_out_start(int32_t component_id) const +``` + + +Start focusing out. + +This function is blocking. See 'focus_out_start_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### focus_stop_async() {#classmavsdk_1_1_camera_1a562ad9fa8f29b359785069a9dc5b8de2} +```cpp +void mavsdk::Camera::focus_stop_async(int32_t component_id, const ResultCallback callback) +``` + + +Stop focus. + +This function is non-blocking. See 'focus_stop' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### focus_stop() {#classmavsdk_1_1_camera_1aed5b395a57b14da2d15395dfa2e56600} +```cpp +Result mavsdk::Camera::focus_stop(int32_t component_id) const +``` + + +Stop focus. + +This function is blocking. See 'focus_stop_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - + +**Returns** + + [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. + +### focus_range_async() {#classmavsdk_1_1_camera_1a44cebbb36a9bc9c203dc0233f8b52f7b} +```cpp +void mavsdk::Camera::focus_range_async(int32_t component_id, float range, const ResultCallback callback) +``` + + +Focus with range value of full range (value between 0.0 and 100.0). + +This function is non-blocking. See 'focus_range' for the blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **range** - +* const [ResultCallback](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a8d6d59cd8d0a3584ef60b16255b6301f) **callback** - + +### focus_range() {#classmavsdk_1_1_camera_1aec7d7a0ed5fa2ba84124f9f363e8d94a} +```cpp +Result mavsdk::Camera::focus_range(int32_t component_id, float range) const +``` + + +Focus with range value of full range (value between 0.0 and 100.0). + +This function is blocking. See 'focus_range_async' for the non-blocking counterpart. + +**Parameters** + +* int32_t **component_id** - +* float **range** - **Returns**  [Result](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a2a84df3938372f4f302576227b308bcf) - Result of request. -### operator=() {#classmavsdk_1_1_camera_1aeff295155b6a665f5c942e473f1fe894} +### operator=() {#classmavsdk_1_1_camera_1a358026db44ff9a10cf14a166d8f1da78} ```cpp -const Camera& mavsdk::Camera::operator=(const Camera &)=delete +const Camera & mavsdk::Camera::operator=(const Camera &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_camera_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_camera_server.md index f6c943481e..b3c21d9521 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_camera_server.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_camera_server.md @@ -4,7 +4,7 @@ ---- -Provides handling of camera trigger commands. +Provides handling of camera interface. ## Data Structures @@ -22,6 +22,10 @@ struct [Quaternion](structmavsdk_1_1_camera_server_1_1_quaternion.md) struct [StorageInformation](structmavsdk_1_1_camera_server_1_1_storage_information.md) +struct [TrackPoint](structmavsdk_1_1_camera_server_1_1_track_point.md) + +struct [TrackRectangle](structmavsdk_1_1_camera_server_1_1_track_rectangle.md) + struct [VideoStreaming](structmavsdk_1_1_camera_server_1_1_video_streaming.md) ## Public Types @@ -53,6 +57,20 @@ std::function< void(int32_t)> [FormatStorageCallback](#classmavsdk_1_1_camera_se [Handle](classmavsdk_1_1_handle.md)< int32_t > [FormatStorageHandle](#classmavsdk_1_1_camera_server_1a71b5531c91f7fba1c74296e55ecd3f45) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_format_storage. std::function< void(int32_t)> [ResetSettingsCallback](#classmavsdk_1_1_camera_server_1ac88b7c640c76e5ff2bdc9afb243ceac2) | Callback type for subscribe_reset_settings. [Handle](classmavsdk_1_1_handle.md)< int32_t > [ResetSettingsHandle](#classmavsdk_1_1_camera_server_1aec973cf0e67863272e63e12902094f25) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_reset_settings. +std::function< void(int32_t)> [ZoomInStartCallback](#classmavsdk_1_1_camera_server_1a7b6c98f6051a80539ef891f65311aa71) | Callback type for subscribe_zoom_in_start. +[Handle](classmavsdk_1_1_handle.md)< int32_t > [ZoomInStartHandle](#classmavsdk_1_1_camera_server_1a3e67fff49fcc4557662826305531e879) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_in_start. +std::function< void(int32_t)> [ZoomOutStartCallback](#classmavsdk_1_1_camera_server_1aa07c374347ed42ec8d2b6727c0d60f5b) | Callback type for subscribe_zoom_out_start. +[Handle](classmavsdk_1_1_handle.md)< int32_t > [ZoomOutStartHandle](#classmavsdk_1_1_camera_server_1afdfa5f070466f4bcd52af5af989d5226) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_out_start. +std::function< void(int32_t)> [ZoomStopCallback](#classmavsdk_1_1_camera_server_1a6fc78f44226f6a326afb935a1dca5c86) | Callback type for subscribe_zoom_stop. +[Handle](classmavsdk_1_1_handle.md)< int32_t > [ZoomStopHandle](#classmavsdk_1_1_camera_server_1a8bb9a99dfb5089332be6241230d54d34) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_stop. +std::function< void(float)> [ZoomRangeCallback](#classmavsdk_1_1_camera_server_1aa23f7ca9c7bf5eee8a12846743bed3a2) | Callback type for subscribe_zoom_range. +[Handle](classmavsdk_1_1_handle.md)< float > [ZoomRangeHandle](#classmavsdk_1_1_camera_server_1a37067e1804927f01921079dfa1e133c2) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_range. +std::function< void([TrackPoint](structmavsdk_1_1_camera_server_1_1_track_point.md))> [TrackingPointCommandCallback](#classmavsdk_1_1_camera_server_1afcb7cf46d38b362562653e9648191ef4) | Callback type for subscribe_tracking_point_command. +[Handle](classmavsdk_1_1_handle.md)< [TrackPoint](structmavsdk_1_1_camera_server_1_1_track_point.md) > [TrackingPointCommandHandle](#classmavsdk_1_1_camera_server_1a38c4148c1c717351865787b1529e9617) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_point_command. +std::function< void([TrackRectangle](structmavsdk_1_1_camera_server_1_1_track_rectangle.md))> [TrackingRectangleCommandCallback](#classmavsdk_1_1_camera_server_1aa7541523c37bb4b24246e40deb0e35a6) | Callback type for subscribe_tracking_rectangle_command. +[Handle](classmavsdk_1_1_handle.md)< [TrackRectangle](structmavsdk_1_1_camera_server_1_1_track_rectangle.md) > [TrackingRectangleCommandHandle](#classmavsdk_1_1_camera_server_1a2e6b6f5ec287bec05357cc9dc9259566) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_rectangle_command. +std::function< void(int32_t)> [TrackingOffCommandCallback](#classmavsdk_1_1_camera_server_1ae46621448c7e035ec4da57338d898109) | Callback type for subscribe_tracking_off_command. +[Handle](classmavsdk_1_1_handle.md)< int32_t > [TrackingOffCommandHandle](#classmavsdk_1_1_camera_server_1a5948e4523cdeff02791277df0d059557) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_off_command. ## Public Member Functions @@ -95,7 +113,30 @@ void | [unsubscribe_format_storage](#classmavsdk_1_1_camera_server_1a9b51f14ffa8 [ResetSettingsHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aec973cf0e67863272e63e12902094f25) | [subscribe_reset_settings](#classmavsdk_1_1_camera_server_1ab1022684bc503e1d6294495de8c68165) (const [ResetSettingsCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1ac88b7c640c76e5ff2bdc9afb243ceac2) & callback) | Subscribe to reset settings requests. Each request received should response to using RespondResetSettings. void | [unsubscribe_reset_settings](#classmavsdk_1_1_camera_server_1a09c70966fa6f98215c11d8257d1b9608) ([ResetSettingsHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aec973cf0e67863272e63e12902094f25) handle) | Unsubscribe from subscribe_reset_settings. [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_reset_settings](#classmavsdk_1_1_camera_server_1a1d7b2793d899c9052038f4e9569eb32b) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) reset_settings_feedback)const | Respond to reset settings from SubscribeResetSettings. -const [CameraServer](classmavsdk_1_1_camera_server.md) & | [operator=](#classmavsdk_1_1_camera_server_1a08a928060071a9a9e4d321403f7d446a) (const [CameraServer](classmavsdk_1_1_camera_server.md) &)=delete | Equality operator (object is not copyable). +[ZoomInStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a3e67fff49fcc4557662826305531e879) | [subscribe_zoom_in_start](#classmavsdk_1_1_camera_server_1a4d5f9d60ad7e19cea32b4af040727d46) (const [ZoomInStartCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a7b6c98f6051a80539ef891f65311aa71) & callback) | Subscribe to zoom in start command. +void | [unsubscribe_zoom_in_start](#classmavsdk_1_1_camera_server_1a5ab3f69f82b3b848decf5067c26a66fa) ([ZoomInStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a3e67fff49fcc4557662826305531e879) handle) | Unsubscribe from subscribe_zoom_in_start. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_zoom_in_start](#classmavsdk_1_1_camera_server_1a059b221e9dc918ea4a3c17371ae8833f) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) zoom_in_start_feedback)const | Respond to zoom in start. +[ZoomOutStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1afdfa5f070466f4bcd52af5af989d5226) | [subscribe_zoom_out_start](#classmavsdk_1_1_camera_server_1a46244b254bce6fd53ca1c0db3c0966a1) (const [ZoomOutStartCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa07c374347ed42ec8d2b6727c0d60f5b) & callback) | Subscribe to zoom out start command. +void | [unsubscribe_zoom_out_start](#classmavsdk_1_1_camera_server_1a1aa244c9eeaef416cd67ef2896264959) ([ZoomOutStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1afdfa5f070466f4bcd52af5af989d5226) handle) | Unsubscribe from subscribe_zoom_out_start. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_zoom_out_start](#classmavsdk_1_1_camera_server_1aaf52d7ad70cb10219db015e17a657632) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) zoom_out_start_feedback)const | Respond to zoom out start. +[ZoomStopHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a8bb9a99dfb5089332be6241230d54d34) | [subscribe_zoom_stop](#classmavsdk_1_1_camera_server_1a2be8527911fe1f4dafc7cd87f9be60cd) (const [ZoomStopCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a6fc78f44226f6a326afb935a1dca5c86) & callback) | Subscribe to zoom stop command. +void | [unsubscribe_zoom_stop](#classmavsdk_1_1_camera_server_1aab7d43df6c39266ccdcb80ee6f5621fb) ([ZoomStopHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a8bb9a99dfb5089332be6241230d54d34) handle) | Unsubscribe from subscribe_zoom_stop. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_zoom_stop](#classmavsdk_1_1_camera_server_1a968890afb4b3b33a7a6965dd4b32aa1f) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) zoom_stop_feedback)const | Respond to zoom stop. +[ZoomRangeHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a37067e1804927f01921079dfa1e133c2) | [subscribe_zoom_range](#classmavsdk_1_1_camera_server_1a6dc95f635c88749b4e2bbfa07bd5b0fd) (const [ZoomRangeCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa23f7ca9c7bf5eee8a12846743bed3a2) & callback) | Subscribe to zoom range command. +void | [unsubscribe_zoom_range](#classmavsdk_1_1_camera_server_1a9fc5f5daed094bea620011bce222bb88) ([ZoomRangeHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a37067e1804927f01921079dfa1e133c2) handle) | Unsubscribe from subscribe_zoom_range. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_zoom_range](#classmavsdk_1_1_camera_server_1a5ea9dd6521f43d91671b0fa1eef6d0f6) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) zoom_range_feedback)const | Respond to zoom range. +void | [set_tracking_rectangle_status](#classmavsdk_1_1_camera_server_1a262b7ec85fee9aa1b83eebd3ffb9abaa) ([TrackRectangle](structmavsdk_1_1_camera_server_1_1_track_rectangle.md) tracked_rectangle)const | Set/update the current rectangle tracking status. +void | [set_tracking_off_status](#classmavsdk_1_1_camera_server_1a22ba37443a3bc69c826261964949a8d4) () const | Set the current tracking status to off. +[TrackingPointCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a38c4148c1c717351865787b1529e9617) | [subscribe_tracking_point_command](#classmavsdk_1_1_camera_server_1a474c49eff4fe7a1b707df2c610197b3d) (const [TrackingPointCommandCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1afcb7cf46d38b362562653e9648191ef4) & callback) | Subscribe to incoming tracking point command. +void | [unsubscribe_tracking_point_command](#classmavsdk_1_1_camera_server_1a8cd6c774f5cebb423cb32782d213f4de) ([TrackingPointCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a38c4148c1c717351865787b1529e9617) handle) | Unsubscribe from subscribe_tracking_point_command. +[TrackingRectangleCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a2e6b6f5ec287bec05357cc9dc9259566) | [subscribe_tracking_rectangle_command](#classmavsdk_1_1_camera_server_1a752751ac6064456d0139592697bfd3a8) (const [TrackingRectangleCommandCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa7541523c37bb4b24246e40deb0e35a6) & callback) | Subscribe to incoming tracking rectangle command. +void | [unsubscribe_tracking_rectangle_command](#classmavsdk_1_1_camera_server_1a6abfa99ac94653930aa1e558d7c7beaa) ([TrackingRectangleCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a2e6b6f5ec287bec05357cc9dc9259566) handle) | Unsubscribe from subscribe_tracking_rectangle_command. +[TrackingOffCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a5948e4523cdeff02791277df0d059557) | [subscribe_tracking_off_command](#classmavsdk_1_1_camera_server_1ac976e22ee5831c8144a4b917ab615946) (const [TrackingOffCommandCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1ae46621448c7e035ec4da57338d898109) & callback) | Subscribe to incoming tracking off command. +void | [unsubscribe_tracking_off_command](#classmavsdk_1_1_camera_server_1a13d8edd63c57c53c3d17893dc31e3bc3) ([TrackingOffCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a5948e4523cdeff02791277df0d059557) handle) | Unsubscribe from subscribe_tracking_off_command. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_tracking_point_command](#classmavsdk_1_1_camera_server_1a8749824a1326cc0a7c441fb7c59b9507) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) stop_video_feedback)const | Respond to an incoming tracking point command. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_tracking_rectangle_command](#classmavsdk_1_1_camera_server_1a2de79ab19b5d51e6760eb3173e9c6f77) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) stop_video_feedback)const | Respond to an incoming tracking rectangle command. +[Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) | [respond_tracking_off_command](#classmavsdk_1_1_camera_server_1a31e8a3a8996ae48afbacbef38d31e209) ([CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) stop_video_feedback)const | Respond to an incoming tracking off command. +const [CameraServer](classmavsdk_1_1_camera_server.md) & | [operator=](#classmavsdk_1_1_camera_server_1a6b516bbddcbaa2867d1a11be8eda14bd) (const [CameraServer](classmavsdk_1_1_camera_server.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -354,6 +395,146 @@ using mavsdk::CameraServer::ResetSettingsHandle = Handle [Handle](classmavsdk_1_1_handle.md) type for subscribe_reset_settings. +### typedef ZoomInStartCallback {#classmavsdk_1_1_camera_server_1a7b6c98f6051a80539ef891f65311aa71} + +```cpp +using mavsdk::CameraServer::ZoomInStartCallback = std::function +``` + + +Callback type for subscribe_zoom_in_start. + + +### typedef ZoomInStartHandle {#classmavsdk_1_1_camera_server_1a3e67fff49fcc4557662826305531e879} + +```cpp +using mavsdk::CameraServer::ZoomInStartHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_in_start. + + +### typedef ZoomOutStartCallback {#classmavsdk_1_1_camera_server_1aa07c374347ed42ec8d2b6727c0d60f5b} + +```cpp +using mavsdk::CameraServer::ZoomOutStartCallback = std::function +``` + + +Callback type for subscribe_zoom_out_start. + + +### typedef ZoomOutStartHandle {#classmavsdk_1_1_camera_server_1afdfa5f070466f4bcd52af5af989d5226} + +```cpp +using mavsdk::CameraServer::ZoomOutStartHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_out_start. + + +### typedef ZoomStopCallback {#classmavsdk_1_1_camera_server_1a6fc78f44226f6a326afb935a1dca5c86} + +```cpp +using mavsdk::CameraServer::ZoomStopCallback = std::function +``` + + +Callback type for subscribe_zoom_stop. + + +### typedef ZoomStopHandle {#classmavsdk_1_1_camera_server_1a8bb9a99dfb5089332be6241230d54d34} + +```cpp +using mavsdk::CameraServer::ZoomStopHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_stop. + + +### typedef ZoomRangeCallback {#classmavsdk_1_1_camera_server_1aa23f7ca9c7bf5eee8a12846743bed3a2} + +```cpp +using mavsdk::CameraServer::ZoomRangeCallback = std::function +``` + + +Callback type for subscribe_zoom_range. + + +### typedef ZoomRangeHandle {#classmavsdk_1_1_camera_server_1a37067e1804927f01921079dfa1e133c2} + +```cpp +using mavsdk::CameraServer::ZoomRangeHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_zoom_range. + + +### typedef TrackingPointCommandCallback {#classmavsdk_1_1_camera_server_1afcb7cf46d38b362562653e9648191ef4} + +```cpp +using mavsdk::CameraServer::TrackingPointCommandCallback = std::function +``` + + +Callback type for subscribe_tracking_point_command. + + +### typedef TrackingPointCommandHandle {#classmavsdk_1_1_camera_server_1a38c4148c1c717351865787b1529e9617} + +```cpp +using mavsdk::CameraServer::TrackingPointCommandHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_point_command. + + +### typedef TrackingRectangleCommandCallback {#classmavsdk_1_1_camera_server_1aa7541523c37bb4b24246e40deb0e35a6} + +```cpp +using mavsdk::CameraServer::TrackingRectangleCommandCallback = std::function +``` + + +Callback type for subscribe_tracking_rectangle_command. + + +### typedef TrackingRectangleCommandHandle {#classmavsdk_1_1_camera_server_1a2e6b6f5ec287bec05357cc9dc9259566} + +```cpp +using mavsdk::CameraServer::TrackingRectangleCommandHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_rectangle_command. + + +### typedef TrackingOffCommandCallback {#classmavsdk_1_1_camera_server_1ae46621448c7e035ec4da57338d898109} + +```cpp +using mavsdk::CameraServer::TrackingOffCommandCallback = std::function +``` + + +Callback type for subscribe_tracking_off_command. + + +### typedef TrackingOffCommandHandle {#classmavsdk_1_1_camera_server_1a5948e4523cdeff02791277df0d059557} + +```cpp +using mavsdk::CameraServer::TrackingOffCommandHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_off_command. + + ## Member Enumeration Documentation @@ -940,9 +1121,369 @@ This function is blocking.  [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. -### operator=() {#classmavsdk_1_1_camera_server_1a08a928060071a9a9e4d321403f7d446a} +### subscribe_zoom_in_start() {#classmavsdk_1_1_camera_server_1a4d5f9d60ad7e19cea32b4af040727d46} +```cpp +ZoomInStartHandle mavsdk::CameraServer::subscribe_zoom_in_start(const ZoomInStartCallback &callback) +``` + + +Subscribe to zoom in start command. + + +**Parameters** + +* const [ZoomInStartCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a7b6c98f6051a80539ef891f65311aa71)& **callback** - + +**Returns** + + [ZoomInStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a3e67fff49fcc4557662826305531e879) - + +### unsubscribe_zoom_in_start() {#classmavsdk_1_1_camera_server_1a5ab3f69f82b3b848decf5067c26a66fa} +```cpp +void mavsdk::CameraServer::unsubscribe_zoom_in_start(ZoomInStartHandle handle) +``` + + +Unsubscribe from subscribe_zoom_in_start. + + +**Parameters** + +* [ZoomInStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a3e67fff49fcc4557662826305531e879) **handle** - + +### respond_zoom_in_start() {#classmavsdk_1_1_camera_server_1a059b221e9dc918ea4a3c17371ae8833f} +```cpp +Result mavsdk::CameraServer::respond_zoom_in_start(CameraFeedback zoom_in_start_feedback) const +``` + + +Respond to zoom in start. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **zoom_in_start_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### subscribe_zoom_out_start() {#classmavsdk_1_1_camera_server_1a46244b254bce6fd53ca1c0db3c0966a1} +```cpp +ZoomOutStartHandle mavsdk::CameraServer::subscribe_zoom_out_start(const ZoomOutStartCallback &callback) +``` + + +Subscribe to zoom out start command. + + +**Parameters** + +* const [ZoomOutStartCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa07c374347ed42ec8d2b6727c0d60f5b)& **callback** - + +**Returns** + + [ZoomOutStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1afdfa5f070466f4bcd52af5af989d5226) - + +### unsubscribe_zoom_out_start() {#classmavsdk_1_1_camera_server_1a1aa244c9eeaef416cd67ef2896264959} +```cpp +void mavsdk::CameraServer::unsubscribe_zoom_out_start(ZoomOutStartHandle handle) +``` + + +Unsubscribe from subscribe_zoom_out_start. + + +**Parameters** + +* [ZoomOutStartHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1afdfa5f070466f4bcd52af5af989d5226) **handle** - + +### respond_zoom_out_start() {#classmavsdk_1_1_camera_server_1aaf52d7ad70cb10219db015e17a657632} +```cpp +Result mavsdk::CameraServer::respond_zoom_out_start(CameraFeedback zoom_out_start_feedback) const +``` + + +Respond to zoom out start. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **zoom_out_start_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### subscribe_zoom_stop() {#classmavsdk_1_1_camera_server_1a2be8527911fe1f4dafc7cd87f9be60cd} +```cpp +ZoomStopHandle mavsdk::CameraServer::subscribe_zoom_stop(const ZoomStopCallback &callback) +``` + + +Subscribe to zoom stop command. + + +**Parameters** + +* const [ZoomStopCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a6fc78f44226f6a326afb935a1dca5c86)& **callback** - + +**Returns** + + [ZoomStopHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a8bb9a99dfb5089332be6241230d54d34) - + +### unsubscribe_zoom_stop() {#classmavsdk_1_1_camera_server_1aab7d43df6c39266ccdcb80ee6f5621fb} +```cpp +void mavsdk::CameraServer::unsubscribe_zoom_stop(ZoomStopHandle handle) +``` + + +Unsubscribe from subscribe_zoom_stop. + + +**Parameters** + +* [ZoomStopHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a8bb9a99dfb5089332be6241230d54d34) **handle** - + +### respond_zoom_stop() {#classmavsdk_1_1_camera_server_1a968890afb4b3b33a7a6965dd4b32aa1f} +```cpp +Result mavsdk::CameraServer::respond_zoom_stop(CameraFeedback zoom_stop_feedback) const +``` + + +Respond to zoom stop. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **zoom_stop_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### subscribe_zoom_range() {#classmavsdk_1_1_camera_server_1a6dc95f635c88749b4e2bbfa07bd5b0fd} +```cpp +ZoomRangeHandle mavsdk::CameraServer::subscribe_zoom_range(const ZoomRangeCallback &callback) +``` + + +Subscribe to zoom range command. + + +**Parameters** + +* const [ZoomRangeCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa23f7ca9c7bf5eee8a12846743bed3a2)& **callback** - + +**Returns** + + [ZoomRangeHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a37067e1804927f01921079dfa1e133c2) - + +### unsubscribe_zoom_range() {#classmavsdk_1_1_camera_server_1a9fc5f5daed094bea620011bce222bb88} +```cpp +void mavsdk::CameraServer::unsubscribe_zoom_range(ZoomRangeHandle handle) +``` + + +Unsubscribe from subscribe_zoom_range. + + +**Parameters** + +* [ZoomRangeHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a37067e1804927f01921079dfa1e133c2) **handle** - + +### respond_zoom_range() {#classmavsdk_1_1_camera_server_1a5ea9dd6521f43d91671b0fa1eef6d0f6} +```cpp +Result mavsdk::CameraServer::respond_zoom_range(CameraFeedback zoom_range_feedback) const +``` + + +Respond to zoom range. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **zoom_range_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### set_tracking_rectangle_status() {#classmavsdk_1_1_camera_server_1a262b7ec85fee9aa1b83eebd3ffb9abaa} +```cpp +void mavsdk::CameraServer::set_tracking_rectangle_status(TrackRectangle tracked_rectangle) const +``` + + +Set/update the current rectangle tracking status. + +This function is blocking. + +**Parameters** + +* [TrackRectangle](structmavsdk_1_1_camera_server_1_1_track_rectangle.md) **tracked_rectangle** - + +### set_tracking_off_status() {#classmavsdk_1_1_camera_server_1a22ba37443a3bc69c826261964949a8d4} +```cpp +void mavsdk::CameraServer::set_tracking_off_status() const +``` + + +Set the current tracking status to off. + +This function is blocking. + +### subscribe_tracking_point_command() {#classmavsdk_1_1_camera_server_1a474c49eff4fe7a1b707df2c610197b3d} +```cpp +TrackingPointCommandHandle mavsdk::CameraServer::subscribe_tracking_point_command(const TrackingPointCommandCallback &callback) +``` + + +Subscribe to incoming tracking point command. + + +**Parameters** + +* const [TrackingPointCommandCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1afcb7cf46d38b362562653e9648191ef4)& **callback** - + +**Returns** + + [TrackingPointCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a38c4148c1c717351865787b1529e9617) - + +### unsubscribe_tracking_point_command() {#classmavsdk_1_1_camera_server_1a8cd6c774f5cebb423cb32782d213f4de} +```cpp +void mavsdk::CameraServer::unsubscribe_tracking_point_command(TrackingPointCommandHandle handle) +``` + + +Unsubscribe from subscribe_tracking_point_command. + + +**Parameters** + +* [TrackingPointCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a38c4148c1c717351865787b1529e9617) **handle** - + +### subscribe_tracking_rectangle_command() {#classmavsdk_1_1_camera_server_1a752751ac6064456d0139592697bfd3a8} +```cpp +TrackingRectangleCommandHandle mavsdk::CameraServer::subscribe_tracking_rectangle_command(const TrackingRectangleCommandCallback &callback) +``` + + +Subscribe to incoming tracking rectangle command. + + +**Parameters** + +* const [TrackingRectangleCommandCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa7541523c37bb4b24246e40deb0e35a6)& **callback** - + +**Returns** + + [TrackingRectangleCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a2e6b6f5ec287bec05357cc9dc9259566) - + +### unsubscribe_tracking_rectangle_command() {#classmavsdk_1_1_camera_server_1a6abfa99ac94653930aa1e558d7c7beaa} +```cpp +void mavsdk::CameraServer::unsubscribe_tracking_rectangle_command(TrackingRectangleCommandHandle handle) +``` + + +Unsubscribe from subscribe_tracking_rectangle_command. + + +**Parameters** + +* [TrackingRectangleCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a2e6b6f5ec287bec05357cc9dc9259566) **handle** - + +### subscribe_tracking_off_command() {#classmavsdk_1_1_camera_server_1ac976e22ee5831c8144a4b917ab615946} +```cpp +TrackingOffCommandHandle mavsdk::CameraServer::subscribe_tracking_off_command(const TrackingOffCommandCallback &callback) +``` + + +Subscribe to incoming tracking off command. + + +**Parameters** + +* const [TrackingOffCommandCallback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1ae46621448c7e035ec4da57338d898109)& **callback** - + +**Returns** + + [TrackingOffCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a5948e4523cdeff02791277df0d059557) - + +### unsubscribe_tracking_off_command() {#classmavsdk_1_1_camera_server_1a13d8edd63c57c53c3d17893dc31e3bc3} +```cpp +void mavsdk::CameraServer::unsubscribe_tracking_off_command(TrackingOffCommandHandle handle) +``` + + +Unsubscribe from subscribe_tracking_off_command. + + +**Parameters** + +* [TrackingOffCommandHandle](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a5948e4523cdeff02791277df0d059557) **handle** - + +### respond_tracking_point_command() {#classmavsdk_1_1_camera_server_1a8749824a1326cc0a7c441fb7c59b9507} +```cpp +Result mavsdk::CameraServer::respond_tracking_point_command(CameraFeedback stop_video_feedback) const +``` + + +Respond to an incoming tracking point command. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **stop_video_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### respond_tracking_rectangle_command() {#classmavsdk_1_1_camera_server_1a2de79ab19b5d51e6760eb3173e9c6f77} +```cpp +Result mavsdk::CameraServer::respond_tracking_rectangle_command(CameraFeedback stop_video_feedback) const +``` + + +Respond to an incoming tracking rectangle command. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **stop_video_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### respond_tracking_off_command() {#classmavsdk_1_1_camera_server_1a31e8a3a8996ae48afbacbef38d31e209} +```cpp +Result mavsdk::CameraServer::respond_tracking_off_command(CameraFeedback stop_video_feedback) const +``` + + +Respond to an incoming tracking off command. + +This function is blocking. + +**Parameters** + +* [CameraFeedback](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1a088cdcd9da37b84f075d20d5b7458a72) **stop_video_feedback** - + +**Returns** + + [Result](classmavsdk_1_1_camera_server.md#classmavsdk_1_1_camera_server_1aa625af622ca91165c737cffebfe57f8d) - Result of request. + +### operator=() {#classmavsdk_1_1_camera_server_1a6b516bbddcbaa2867d1a11be8eda14bd} ```cpp -const CameraServer& mavsdk::CameraServer::operator=(const CameraServer &)=delete +const CameraServer & mavsdk::CameraServer::operator=(const CameraServer &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_component_information.md b/docs/en/cpp/api_reference/classmavsdk_1_1_component_information.md deleted file mode 100644 index f83858eef8..0000000000 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_component_information.md +++ /dev/null @@ -1,213 +0,0 @@ -# mavsdk::ComponentInformation Class Reference -`#include: component_information.h` - ----- - - -Access component information such as parameters. - - -## Data Structures - - -struct [FloatParam](structmavsdk_1_1_component_information_1_1_float_param.md) - -struct [FloatParamUpdate](structmavsdk_1_1_component_information_1_1_float_param_update.md) - -## Public Types - - -Type | Description ---- | --- -enum [Result](#classmavsdk_1_1_component_information_1aa91c6fe2a0335b2b86a140e37359341f) | Possible results returned for param requests. -std::function< void([Result](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1aa91c6fe2a0335b2b86a140e37359341f))> [ResultCallback](#classmavsdk_1_1_component_information_1a37506981d2b48162f3304947e5520ea8) | Callback type for asynchronous [ComponentInformation](classmavsdk_1_1_component_information.md) calls. -std::function< void([FloatParamUpdate](structmavsdk_1_1_component_information_1_1_float_param_update.md))> [FloatParamCallback](#classmavsdk_1_1_component_information_1a346dfd9dc8de60f6cdeca0a4ddb20f78) | Callback type for subscribe_float_param. -[Handle](classmavsdk_1_1_handle.md)< [FloatParamUpdate](structmavsdk_1_1_component_information_1_1_float_param_update.md) > [FloatParamHandle](#classmavsdk_1_1_component_information_1ab22a0bb9704930d17c2e2c82ffa9a977) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_float_param. - -## Public Member Functions - - -Type | Name | Description ----: | --- | --- -  | [ComponentInformation](#classmavsdk_1_1_component_information_1afd3a1f8282548a895ff3bf3f08da20ac) ([System](classmavsdk_1_1_system.md) & system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). -  | [ComponentInformation](#classmavsdk_1_1_component_information_1a3c6bc3ad6d571a944407e148e2496f13) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). -  | [~ComponentInformation](#classmavsdk_1_1_component_information_1adc9f86087470dcf0b1eb888c236918ec) () override | Destructor (internal use only). -  | [ComponentInformation](#classmavsdk_1_1_component_information_1a146e2a8d181c75ae1c7c98501c4b205a) (const [ComponentInformation](classmavsdk_1_1_component_information.md) & other) | Copy constructor. -std::pair< [Result](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1aa91c6fe2a0335b2b86a140e37359341f), std::vector< [ComponentInformation::FloatParam](structmavsdk_1_1_component_information_1_1_float_param.md) > > | [access_float_params](#classmavsdk_1_1_component_information_1ababf4e7ff24e6fabfd3ee52b58e66002) () const | List available float params. -[FloatParamHandle](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1ab22a0bb9704930d17c2e2c82ffa9a977) | [subscribe_float_param](#classmavsdk_1_1_component_information_1a41df5c7f9340d3e01b24a96d3215754d) (const [FloatParamCallback](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1a346dfd9dc8de60f6cdeca0a4ddb20f78) & callback) | Subscribe to float param changes/updates. -void | [unsubscribe_float_param](#classmavsdk_1_1_component_information_1a877d2a620d6646bf4063863297c0b666) ([FloatParamHandle](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1ab22a0bb9704930d17c2e2c82ffa9a977) handle) | Unsubscribe from subscribe_float_param. -const [ComponentInformation](classmavsdk_1_1_component_information.md) & | [operator=](#classmavsdk_1_1_component_information_1ada12fb6199ef988219281900ad2d9b79) (const [ComponentInformation](classmavsdk_1_1_component_information.md) &)=delete | Equality operator (object is not copyable). - - -## Constructor & Destructor Documentation - - -### ComponentInformation() {#classmavsdk_1_1_component_information_1afd3a1f8282548a895ff3bf3f08da20ac} -```cpp -mavsdk::ComponentInformation::ComponentInformation(System &system) -``` - - -Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). - -The plugin is typically created as shown below: - -```cpp -auto component_information = ComponentInformation(system); -``` - -**Parameters** - -* [System](classmavsdk_1_1_system.md)& **system** - The specific system associated with this plugin. - -### ComponentInformation() {#classmavsdk_1_1_component_information_1a3c6bc3ad6d571a944407e148e2496f13} -```cpp -mavsdk::ComponentInformation::ComponentInformation(std::shared_ptr< System > system) -``` - - -Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). - -The plugin is typically created as shown below: - -```cpp -auto component_information = ComponentInformation(system); -``` - -**Parameters** - -* std::shared_ptr< [System](classmavsdk_1_1_system.md) > **system** - The specific system associated with this plugin. - -### ~ComponentInformation() {#classmavsdk_1_1_component_information_1adc9f86087470dcf0b1eb888c236918ec} -```cpp -mavsdk::ComponentInformation::~ComponentInformation() override -``` - - -Destructor (internal use only). - - -### ComponentInformation() {#classmavsdk_1_1_component_information_1a146e2a8d181c75ae1c7c98501c4b205a} -```cpp -mavsdk::ComponentInformation::ComponentInformation(const ComponentInformation &other) -``` - - -Copy constructor. - - -**Parameters** - -* const [ComponentInformation](classmavsdk_1_1_component_information.md)& **other** - - -## Member Typdef Documentation - - -### typedef ResultCallback {#classmavsdk_1_1_component_information_1a37506981d2b48162f3304947e5520ea8} - -```cpp -using mavsdk::ComponentInformation::ResultCallback = std::function -``` - - -Callback type for asynchronous [ComponentInformation](classmavsdk_1_1_component_information.md) calls. - - -### typedef FloatParamCallback {#classmavsdk_1_1_component_information_1a346dfd9dc8de60f6cdeca0a4ddb20f78} - -```cpp -using mavsdk::ComponentInformation::FloatParamCallback = std::function -``` - - -Callback type for subscribe_float_param. - - -### typedef FloatParamHandle {#classmavsdk_1_1_component_information_1ab22a0bb9704930d17c2e2c82ffa9a977} - -```cpp -using mavsdk::ComponentInformation::FloatParamHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_float_param. - - -## Member Enumeration Documentation - - -### enum Result {#classmavsdk_1_1_component_information_1aa91c6fe2a0335b2b86a140e37359341f} - - -Possible results returned for param requests. - - -Value | Description ---- | --- - `Unknown` | Unknown result. - `Success` | Request succeeded. - `NoSystem` | No system is connected. - -## Member Function Documentation - - -### access_float_params() {#classmavsdk_1_1_component_information_1ababf4e7ff24e6fabfd3ee52b58e66002} -```cpp -std::pair > mavsdk::ComponentInformation::access_float_params() const -``` - - -List available float params. - -This function is blocking. - -**Returns** - - std::pair< [Result](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1aa91c6fe2a0335b2b86a140e37359341f), std::vector< [ComponentInformation::FloatParam](structmavsdk_1_1_component_information_1_1_float_param.md) > > - Result of request. - -### subscribe_float_param() {#classmavsdk_1_1_component_information_1a41df5c7f9340d3e01b24a96d3215754d} -```cpp -FloatParamHandle mavsdk::ComponentInformation::subscribe_float_param(const FloatParamCallback &callback) -``` - - -Subscribe to float param changes/updates. - - -**Parameters** - -* const [FloatParamCallback](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1a346dfd9dc8de60f6cdeca0a4ddb20f78)& **callback** - - -**Returns** - - [FloatParamHandle](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1ab22a0bb9704930d17c2e2c82ffa9a977) - - -### unsubscribe_float_param() {#classmavsdk_1_1_component_information_1a877d2a620d6646bf4063863297c0b666} -```cpp -void mavsdk::ComponentInformation::unsubscribe_float_param(FloatParamHandle handle) -``` - - -Unsubscribe from subscribe_float_param. - - -**Parameters** - -* [FloatParamHandle](classmavsdk_1_1_component_information.md#classmavsdk_1_1_component_information_1ab22a0bb9704930d17c2e2c82ffa9a977) **handle** - - -### operator=() {#classmavsdk_1_1_component_information_1ada12fb6199ef988219281900ad2d9b79} -```cpp -const ComponentInformation& mavsdk::ComponentInformation::operator=(const ComponentInformation &)=delete -``` - - -Equality operator (object is not copyable). - - -**Parameters** - -* const [ComponentInformation](classmavsdk_1_1_component_information.md)& - - -**Returns** - - const [ComponentInformation](classmavsdk_1_1_component_information.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_component_information_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_component_information_server.md deleted file mode 100644 index fd534493fe..0000000000 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_component_information_server.md +++ /dev/null @@ -1,202 +0,0 @@ -# mavsdk::ComponentInformationServer Class Reference -`#include: component_information_server.h` - ----- - - -Provide component information such as parameters. - - -## Data Structures - - -struct [FloatParam](structmavsdk_1_1_component_information_server_1_1_float_param.md) - -struct [FloatParamUpdate](structmavsdk_1_1_component_information_server_1_1_float_param_update.md) - -## Public Types - - -Type | Description ---- | --- -enum [Result](#classmavsdk_1_1_component_information_server_1aca86e47230e256d3f812269dcbaa5cad) | Possible results returned for param requests. -std::function< void([Result](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1aca86e47230e256d3f812269dcbaa5cad))> [ResultCallback](#classmavsdk_1_1_component_information_server_1a5f65b34949a1954c85f3f02e64dec35f) | Callback type for asynchronous [ComponentInformationServer](classmavsdk_1_1_component_information_server.md) calls. -std::function< void([FloatParamUpdate](structmavsdk_1_1_component_information_server_1_1_float_param_update.md))> [FloatParamCallback](#classmavsdk_1_1_component_information_server_1a6174e3eebb5a10c619c57723623696cf) | Callback type for subscribe_float_param. -[Handle](classmavsdk_1_1_handle.md)< [FloatParamUpdate](structmavsdk_1_1_component_information_server_1_1_float_param_update.md) > [FloatParamHandle](#classmavsdk_1_1_component_information_server_1a0843521587e27f0d630280309712bddb) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_float_param. - -## Public Member Functions - - -Type | Name | Description ----: | --- | --- -  | [ComponentInformationServer](#classmavsdk_1_1_component_information_server_1a89266c1e143f0cffb6596897b92f7b62) (std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > server_component) | Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. -  | [~ComponentInformationServer](#classmavsdk_1_1_component_information_server_1a64a224210755136e130b349db3a8fd10) () override | Destructor (internal use only). -  | [ComponentInformationServer](#classmavsdk_1_1_component_information_server_1a7f8fc33e21e00a390da14596465c800d) (const [ComponentInformationServer](classmavsdk_1_1_component_information_server.md) & other) | Copy constructor. -[Result](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1aca86e47230e256d3f812269dcbaa5cad) | [provide_float_param](#classmavsdk_1_1_component_information_server_1ac4f9a480ef052b792e65b82c3c08b225) ([FloatParam](structmavsdk_1_1_component_information_server_1_1_float_param.md) param)const | Provide a param of type float. -[FloatParamHandle](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1a0843521587e27f0d630280309712bddb) | [subscribe_float_param](#classmavsdk_1_1_component_information_server_1afb87c280501c677a8f4eaa33394d24e7) (const [FloatParamCallback](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1a6174e3eebb5a10c619c57723623696cf) & callback) | Subscribe to float param updates. -void | [unsubscribe_float_param](#classmavsdk_1_1_component_information_server_1a56650131d743e441232c5edf844acaeb) ([FloatParamHandle](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1a0843521587e27f0d630280309712bddb) handle) | Unsubscribe from subscribe_float_param. -const [ComponentInformationServer](classmavsdk_1_1_component_information_server.md) & | [operator=](#classmavsdk_1_1_component_information_server_1a850a10c9d195da5f52807984e72d21fa) (const [ComponentInformationServer](classmavsdk_1_1_component_information_server.md) &)=delete | Equality operator (object is not copyable). - - -## Constructor & Destructor Documentation - - -### ComponentInformationServer() {#classmavsdk_1_1_component_information_server_1a89266c1e143f0cffb6596897b92f7b62} -```cpp -mavsdk::ComponentInformationServer::ComponentInformationServer(std::shared_ptr< ServerComponent > server_component) -``` - - -Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. - -The plugin is typically created as shown below: - -```cpp -auto component_information_server = ComponentInformationServer(server_component); -``` - -**Parameters** - -* std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > **server_component** - The [ServerComponent](classmavsdk_1_1_server_component.md) instance associated with this server plugin. - -### ~ComponentInformationServer() {#classmavsdk_1_1_component_information_server_1a64a224210755136e130b349db3a8fd10} -```cpp -mavsdk::ComponentInformationServer::~ComponentInformationServer() override -``` - - -Destructor (internal use only). - - -### ComponentInformationServer() {#classmavsdk_1_1_component_information_server_1a7f8fc33e21e00a390da14596465c800d} -```cpp -mavsdk::ComponentInformationServer::ComponentInformationServer(const ComponentInformationServer &other) -``` - - -Copy constructor. - - -**Parameters** - -* const [ComponentInformationServer](classmavsdk_1_1_component_information_server.md)& **other** - - -## Member Typdef Documentation - - -### typedef ResultCallback {#classmavsdk_1_1_component_information_server_1a5f65b34949a1954c85f3f02e64dec35f} - -```cpp -using mavsdk::ComponentInformationServer::ResultCallback = std::function -``` - - -Callback type for asynchronous [ComponentInformationServer](classmavsdk_1_1_component_information_server.md) calls. - - -### typedef FloatParamCallback {#classmavsdk_1_1_component_information_server_1a6174e3eebb5a10c619c57723623696cf} - -```cpp -using mavsdk::ComponentInformationServer::FloatParamCallback = std::function -``` - - -Callback type for subscribe_float_param. - - -### typedef FloatParamHandle {#classmavsdk_1_1_component_information_server_1a0843521587e27f0d630280309712bddb} - -```cpp -using mavsdk::ComponentInformationServer::FloatParamHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_float_param. - - -## Member Enumeration Documentation - - -### enum Result {#classmavsdk_1_1_component_information_server_1aca86e47230e256d3f812269dcbaa5cad} - - -Possible results returned for param requests. - - -Value | Description ---- | --- - `Unknown` | Unknown result. - `Success` | Request succeeded. - `DuplicateParam` | Duplicate param. - `InvalidParamStartValue` | Invalid start param value. - `InvalidParamDefaultValue` | Invalid default param value. - `InvalidParamName` | Invalid param name. - `NoSystem` | No system is connected. - -## Member Function Documentation - - -### provide_float_param() {#classmavsdk_1_1_component_information_server_1ac4f9a480ef052b792e65b82c3c08b225} -```cpp -Result mavsdk::ComponentInformationServer::provide_float_param(FloatParam param) const -``` - - -Provide a param of type float. - -This function is blocking. - -**Parameters** - -* [FloatParam](structmavsdk_1_1_component_information_server_1_1_float_param.md) **param** - - -**Returns** - - [Result](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1aca86e47230e256d3f812269dcbaa5cad) - Result of request. - -### subscribe_float_param() {#classmavsdk_1_1_component_information_server_1afb87c280501c677a8f4eaa33394d24e7} -```cpp -FloatParamHandle mavsdk::ComponentInformationServer::subscribe_float_param(const FloatParamCallback &callback) -``` - - -Subscribe to float param updates. - - -**Parameters** - -* const [FloatParamCallback](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1a6174e3eebb5a10c619c57723623696cf)& **callback** - - -**Returns** - - [FloatParamHandle](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1a0843521587e27f0d630280309712bddb) - - -### unsubscribe_float_param() {#classmavsdk_1_1_component_information_server_1a56650131d743e441232c5edf844acaeb} -```cpp -void mavsdk::ComponentInformationServer::unsubscribe_float_param(FloatParamHandle handle) -``` - - -Unsubscribe from subscribe_float_param. - - -**Parameters** - -* [FloatParamHandle](classmavsdk_1_1_component_information_server.md#classmavsdk_1_1_component_information_server_1a0843521587e27f0d630280309712bddb) **handle** - - -### operator=() {#classmavsdk_1_1_component_information_server_1a850a10c9d195da5f52807984e72d21fa} -```cpp -const ComponentInformationServer& mavsdk::ComponentInformationServer::operator=(const ComponentInformationServer &)=delete -``` - - -Equality operator (object is not copyable). - - -**Parameters** - -* const [ComponentInformationServer](classmavsdk_1_1_component_information_server.md)& - - -**Returns** - - const [ComponentInformationServer](classmavsdk_1_1_component_information_server.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_component_metadata.md b/docs/en/cpp/api_reference/classmavsdk_1_1_component_metadata.md new file mode 100644 index 0000000000..9b25beeffd --- /dev/null +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_component_metadata.md @@ -0,0 +1,264 @@ +# mavsdk::ComponentMetadata Class Reference +`#include: component_metadata.h` + +---- + + +Access component metadata json definitions, such as parameters. + + +## Data Structures + + +struct [MetadataData](structmavsdk_1_1_component_metadata_1_1_metadata_data.md) + +struct [MetadataUpdate](structmavsdk_1_1_component_metadata_1_1_metadata_update.md) + +## Public Types + + +Type | Description +--- | --- +enum [MetadataType](#classmavsdk_1_1_component_metadata_1a0d85236afbbb3dc6b2dd46351a6b38bc) | The metadata type. +enum [Result](#classmavsdk_1_1_component_metadata_1af7b6ff8c58634fac8d2670f2b882ef44) | Possible results returned. +std::function< void([Result](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1af7b6ff8c58634fac8d2670f2b882ef44))> [ResultCallback](#classmavsdk_1_1_component_metadata_1aca3d0432b9711666398eb1e3acdab327) | Callback type for asynchronous [ComponentMetadata](classmavsdk_1_1_component_metadata.md) calls. +std::function< void([MetadataUpdate](structmavsdk_1_1_component_metadata_1_1_metadata_update.md))> [MetadataAvailableCallback](#classmavsdk_1_1_component_metadata_1aba4946a5e2219b6b24a9dd3ce4f9ace1) | Callback type for subscribe_metadata_available. +[Handle](classmavsdk_1_1_handle.md)< [MetadataUpdate](structmavsdk_1_1_component_metadata_1_1_metadata_update.md) > [MetadataAvailableHandle](#classmavsdk_1_1_component_metadata_1a374204a0542af5f4a73bf36e25513910) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_metadata_available. + +## Public Member Functions + + +Type | Name | Description +---: | --- | --- +  | [ComponentMetadata](#classmavsdk_1_1_component_metadata_1a1d5efd4730ac6cc96131195675e76dd9) ([System](classmavsdk_1_1_system.md) & system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). +  | [ComponentMetadata](#classmavsdk_1_1_component_metadata_1aa6ecff15e5832fbcd023d140a5583341) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). +  | [~ComponentMetadata](#classmavsdk_1_1_component_metadata_1aac93ac109e9327015fd199646df75a73) () override | Destructor (internal use only). +  | [ComponentMetadata](#classmavsdk_1_1_component_metadata_1a3b145559b5d92068e1bc9f7689223a48) (const [ComponentMetadata](classmavsdk_1_1_component_metadata.md) & other) | Copy constructor. +void | [request_component](#classmavsdk_1_1_component_metadata_1a1237d1aad4d8ab70470cf3390370625a) (uint32_t compid)const | Request metadata from a specific component. This is used to start requesting metadata from a component. The metadata can later be accessed via subscription (see below) or GetMetadata. +void | [request_autopilot_component](#classmavsdk_1_1_component_metadata_1a7620b5ef1adb417b6fea0222c44d2c33) () const | Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. The metadata can later be accessed via subscription (see below) or GetMetadata. +[MetadataAvailableHandle](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a374204a0542af5f4a73bf36e25513910) | [subscribe_metadata_available](#classmavsdk_1_1_component_metadata_1a622e41c77a19b137ae8dfd40bdb44ee5) (const [MetadataAvailableCallback](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1aba4946a5e2219b6b24a9dd3ce4f9ace1) & callback) | Register a callback that gets called when metadata is available. +void | [unsubscribe_metadata_available](#classmavsdk_1_1_component_metadata_1a1245bcbb6d6edc650fe7e0b7035d90f4) ([MetadataAvailableHandle](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a374204a0542af5f4a73bf36e25513910) handle) | Unsubscribe from subscribe_metadata_available. +std::pair< [Result](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1af7b6ff8c58634fac8d2670f2b882ef44), [ComponentMetadata::MetadataData](structmavsdk_1_1_component_metadata_1_1_metadata_data.md) > | [get_metadata](#classmavsdk_1_1_component_metadata_1a2a268428596fe70a97b6be3ec0d4046d) (uint32_t compid, [MetadataType](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a0d85236afbbb3dc6b2dd46351a6b38bc) metadata_type)const | Access metadata. This can be used if you know the metadata is available already, otherwise use the subscription to get notified when it becomes available. +const [ComponentMetadata](classmavsdk_1_1_component_metadata.md) & | [operator=](#classmavsdk_1_1_component_metadata_1a2be7fadaa2dad61f558430278ecf51bb) (const [ComponentMetadata](classmavsdk_1_1_component_metadata.md) &)=delete | Equality operator (object is not copyable). + + +## Constructor & Destructor Documentation + + +### ComponentMetadata() {#classmavsdk_1_1_component_metadata_1a1d5efd4730ac6cc96131195675e76dd9} +```cpp +mavsdk::ComponentMetadata::ComponentMetadata(System &system) +``` + + +Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). + +The plugin is typically created as shown below: + +```cpp +auto component_metadata = ComponentMetadata(system); +``` + +**Parameters** + +* [System](classmavsdk_1_1_system.md)& **system** - The specific system associated with this plugin. + +### ComponentMetadata() {#classmavsdk_1_1_component_metadata_1aa6ecff15e5832fbcd023d140a5583341} +```cpp +mavsdk::ComponentMetadata::ComponentMetadata(std::shared_ptr< System > system) +``` + + +Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). + +The plugin is typically created as shown below: + +```cpp +auto component_metadata = ComponentMetadata(system); +``` + +**Parameters** + +* std::shared_ptr< [System](classmavsdk_1_1_system.md) > **system** - The specific system associated with this plugin. + +### ~ComponentMetadata() {#classmavsdk_1_1_component_metadata_1aac93ac109e9327015fd199646df75a73} +```cpp +mavsdk::ComponentMetadata::~ComponentMetadata() override +``` + + +Destructor (internal use only). + + +### ComponentMetadata() {#classmavsdk_1_1_component_metadata_1a3b145559b5d92068e1bc9f7689223a48} +```cpp +mavsdk::ComponentMetadata::ComponentMetadata(const ComponentMetadata &other) +``` + + +Copy constructor. + + +**Parameters** + +* const [ComponentMetadata](classmavsdk_1_1_component_metadata.md)& **other** - + +## Member Typdef Documentation + + +### typedef ResultCallback {#classmavsdk_1_1_component_metadata_1aca3d0432b9711666398eb1e3acdab327} + +```cpp +using mavsdk::ComponentMetadata::ResultCallback = std::function +``` + + +Callback type for asynchronous [ComponentMetadata](classmavsdk_1_1_component_metadata.md) calls. + + +### typedef MetadataAvailableCallback {#classmavsdk_1_1_component_metadata_1aba4946a5e2219b6b24a9dd3ce4f9ace1} + +```cpp +using mavsdk::ComponentMetadata::MetadataAvailableCallback = std::function +``` + + +Callback type for subscribe_metadata_available. + + +### typedef MetadataAvailableHandle {#classmavsdk_1_1_component_metadata_1a374204a0542af5f4a73bf36e25513910} + +```cpp +using mavsdk::ComponentMetadata::MetadataAvailableHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_metadata_available. + + +## Member Enumeration Documentation + + +### enum MetadataType {#classmavsdk_1_1_component_metadata_1a0d85236afbbb3dc6b2dd46351a6b38bc} + + +The metadata type. + + +Value | Description +--- | --- + `AllCompleted` | This is set in the subscription callback when all metadata types completed for a given component ID. + `Parameter` | Parameter metadata. + `Events` | Event definitions. + `Actuators` | Actuator definitions. + +### enum Result {#classmavsdk_1_1_component_metadata_1af7b6ff8c58634fac8d2670f2b882ef44} + + +Possible results returned. + + +Value | Description +--- | --- + `Success` | Success. + `NotAvailable` | Not available. + `ConnectionError` | Connection error. + `Unsupported` | Unsupported. + `Denied` | Denied. + `Failed` | Failed. + `Timeout` | Timeout. + `NoSystem` | No system. + `NotRequested` | Not requested. + +## Member Function Documentation + + +### request_component() {#classmavsdk_1_1_component_metadata_1a1237d1aad4d8ab70470cf3390370625a} +```cpp +void mavsdk::ComponentMetadata::request_component(uint32_t compid) const +``` + + +Request metadata from a specific component. This is used to start requesting metadata from a component. The metadata can later be accessed via subscription (see below) or GetMetadata. + +This function is blocking. + +**Parameters** + +* uint32_t **compid** - + +### request_autopilot_component() {#classmavsdk_1_1_component_metadata_1a7620b5ef1adb417b6fea0222c44d2c33} +```cpp +void mavsdk::ComponentMetadata::request_autopilot_component() const +``` + + +Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. The metadata can later be accessed via subscription (see below) or GetMetadata. + +This function is blocking. + +### subscribe_metadata_available() {#classmavsdk_1_1_component_metadata_1a622e41c77a19b137ae8dfd40bdb44ee5} +```cpp +MetadataAvailableHandle mavsdk::ComponentMetadata::subscribe_metadata_available(const MetadataAvailableCallback &callback) +``` + + +Register a callback that gets called when metadata is available. + + +**Parameters** + +* const [MetadataAvailableCallback](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1aba4946a5e2219b6b24a9dd3ce4f9ace1)& **callback** - + +**Returns** + + [MetadataAvailableHandle](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a374204a0542af5f4a73bf36e25513910) - + +### unsubscribe_metadata_available() {#classmavsdk_1_1_component_metadata_1a1245bcbb6d6edc650fe7e0b7035d90f4} +```cpp +void mavsdk::ComponentMetadata::unsubscribe_metadata_available(MetadataAvailableHandle handle) +``` + + +Unsubscribe from subscribe_metadata_available. + + +**Parameters** + +* [MetadataAvailableHandle](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a374204a0542af5f4a73bf36e25513910) **handle** - + +### get_metadata() {#classmavsdk_1_1_component_metadata_1a2a268428596fe70a97b6be3ec0d4046d} +```cpp +std::pair< Result, ComponentMetadata::MetadataData > mavsdk::ComponentMetadata::get_metadata(uint32_t compid, MetadataType metadata_type) const +``` + + +Access metadata. This can be used if you know the metadata is available already, otherwise use the subscription to get notified when it becomes available. + +This function is blocking. + +**Parameters** + +* uint32_t **compid** - +* [MetadataType](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a0d85236afbbb3dc6b2dd46351a6b38bc) **metadata_type** - + +**Returns** + + std::pair< [Result](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1af7b6ff8c58634fac8d2670f2b882ef44), [ComponentMetadata::MetadataData](structmavsdk_1_1_component_metadata_1_1_metadata_data.md) > - Result of request. + +### operator=() {#classmavsdk_1_1_component_metadata_1a2be7fadaa2dad61f558430278ecf51bb} +```cpp +const ComponentMetadata & mavsdk::ComponentMetadata::operator=(const ComponentMetadata &)=delete +``` + + +Equality operator (object is not copyable). + + +**Parameters** + +* const [ComponentMetadata](classmavsdk_1_1_component_metadata.md)& - + +**Returns** + + const [ComponentMetadata](classmavsdk_1_1_component_metadata.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_component_metadata_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_component_metadata_server.md new file mode 100644 index 0000000000..766e2a1860 --- /dev/null +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_component_metadata_server.md @@ -0,0 +1,124 @@ +# mavsdk::ComponentMetadataServer Class Reference +`#include: component_metadata_server.h` + +---- + + +Provide component metadata json definitions, such as parameters. + + +## Data Structures + + +struct [Metadata](structmavsdk_1_1_component_metadata_server_1_1_metadata.md) + +## Public Types + + +Type | Description +--- | --- +enum [MetadataType](#classmavsdk_1_1_component_metadata_server_1abaa555f8d1e2ae73f2275b18271537d6) | The metadata type. + +## Public Member Functions + + +Type | Name | Description +---: | --- | --- +  | [ComponentMetadataServer](#classmavsdk_1_1_component_metadata_server_1a83ef20f6459a983e6c499ec4a40232f0) (std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > server_component) | Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. +  | [~ComponentMetadataServer](#classmavsdk_1_1_component_metadata_server_1a7597c973992ce3cab32c8270996f9900) () override | Destructor (internal use only). +  | [ComponentMetadataServer](#classmavsdk_1_1_component_metadata_server_1a9f56317067d68551868680af34ac1124) (const [ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md) & other) | Copy constructor. +void | [set_metadata](#classmavsdk_1_1_component_metadata_server_1a441be303b7421b527d3ff3bc1dc8ac9d) (std::vector< [Metadata](structmavsdk_1_1_component_metadata_server_1_1_metadata.md) > metadata)const | Provide metadata (can only be called once) +const [ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md) & | [operator=](#classmavsdk_1_1_component_metadata_server_1ae873337d2e144e0cc1fbdcfd2881dfee) (const [ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md) &)=delete | Equality operator (object is not copyable). + + +## Constructor & Destructor Documentation + + +### ComponentMetadataServer() {#classmavsdk_1_1_component_metadata_server_1a83ef20f6459a983e6c499ec4a40232f0} +```cpp +mavsdk::ComponentMetadataServer::ComponentMetadataServer(std::shared_ptr< ServerComponent > server_component) +``` + + +Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. + +The plugin is typically created as shown below: + +```cpp +auto component_metadata_server = ComponentMetadataServer(server_component); +``` + +**Parameters** + +* std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > **server_component** - The [ServerComponent](classmavsdk_1_1_server_component.md) instance associated with this server plugin. + +### ~ComponentMetadataServer() {#classmavsdk_1_1_component_metadata_server_1a7597c973992ce3cab32c8270996f9900} +```cpp +mavsdk::ComponentMetadataServer::~ComponentMetadataServer() override +``` + + +Destructor (internal use only). + + +### ComponentMetadataServer() {#classmavsdk_1_1_component_metadata_server_1a9f56317067d68551868680af34ac1124} +```cpp +mavsdk::ComponentMetadataServer::ComponentMetadataServer(const ComponentMetadataServer &other) +``` + + +Copy constructor. + + +**Parameters** + +* const [ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md)& **other** - + +## Member Enumeration Documentation + + +### enum MetadataType {#classmavsdk_1_1_component_metadata_server_1abaa555f8d1e2ae73f2275b18271537d6} + + +The metadata type. + + +Value | Description +--- | --- + `Parameter` | Parameter metadata. + `Events` | Event definitions. + `Actuators` | Actuator definitions. + +## Member Function Documentation + + +### set_metadata() {#classmavsdk_1_1_component_metadata_server_1a441be303b7421b527d3ff3bc1dc8ac9d} +```cpp +void mavsdk::ComponentMetadataServer::set_metadata(std::vector< Metadata > metadata) const +``` + + +Provide metadata (can only be called once) + +This function is blocking. + +**Parameters** + +* std::vector< [Metadata](structmavsdk_1_1_component_metadata_server_1_1_metadata.md) > **metadata** - + +### operator=() {#classmavsdk_1_1_component_metadata_server_1ae873337d2e144e0cc1fbdcfd2881dfee} +```cpp +const ComponentMetadataServer & mavsdk::ComponentMetadataServer::operator=(const ComponentMetadataServer &)=delete +``` + + +Equality operator (object is not copyable). + + +**Parameters** + +* const [ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md)& - + +**Returns** + + const [ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_events.md b/docs/en/cpp/api_reference/classmavsdk_1_1_events.md new file mode 100644 index 0000000000..63011da41f --- /dev/null +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_events.md @@ -0,0 +1,297 @@ +# mavsdk::Events Class Reference +`#include: events.h` + +---- + + +Get event notifications, such as takeoff, or arming checks. + + +## Data Structures + + +struct [Event](structmavsdk_1_1_events_1_1_event.md) + +struct [HealthAndArmingCheckMode](structmavsdk_1_1_events_1_1_health_and_arming_check_mode.md) + +struct [HealthAndArmingCheckProblem](structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md) + +struct [HealthAndArmingCheckReport](structmavsdk_1_1_events_1_1_health_and_arming_check_report.md) + +struct [HealthComponentReport](structmavsdk_1_1_events_1_1_health_component_report.md) + +## Public Types + + +Type | Description +--- | --- +enum [LogLevel](#classmavsdk_1_1_events_1a237c8de77f3995138125db44d148cecc) | Log level type. +enum [Result](#classmavsdk_1_1_events_1abf1e4db55bd810ee6f5fce5d5c9439b1) | Possible results returned. +std::function< void([Result](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1abf1e4db55bd810ee6f5fce5d5c9439b1))> [ResultCallback](#classmavsdk_1_1_events_1a36c781e03d503c528d7da31506cb0af3) | Callback type for asynchronous [Events](classmavsdk_1_1_events.md) calls. +std::function< void([Event](structmavsdk_1_1_events_1_1_event.md))> [EventsCallback](#classmavsdk_1_1_events_1aaa9c2f1d7915aedfdb0da5de7e31bbfb) | Callback type for subscribe_events. +[Handle](classmavsdk_1_1_handle.md)< [Event](structmavsdk_1_1_events_1_1_event.md) > [EventsHandle](#classmavsdk_1_1_events_1a64c99a834c6babf6cdb3b466a923e3ee) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_events. +std::function< void([HealthAndArmingCheckReport](structmavsdk_1_1_events_1_1_health_and_arming_check_report.md))> [HealthAndArmingChecksCallback](#classmavsdk_1_1_events_1ada96803a50810356893417591d91b1a3) | Callback type for subscribe_health_and_arming_checks. +[Handle](classmavsdk_1_1_handle.md)< [HealthAndArmingCheckReport](structmavsdk_1_1_events_1_1_health_and_arming_check_report.md) > [HealthAndArmingChecksHandle](#classmavsdk_1_1_events_1a09ac962d8d560de37c93b16484474fa4) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_health_and_arming_checks. + +## Public Member Functions + + +Type | Name | Description +---: | --- | --- +  | [Events](#classmavsdk_1_1_events_1a2f3778cf7118bd5a11b68e28655ef485) ([System](classmavsdk_1_1_system.md) & system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). +  | [Events](#classmavsdk_1_1_events_1ae8e05a45bfac1043356936f1a15f8f2f) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). +  | [~Events](#classmavsdk_1_1_events_1ac04cade0cb57f7858655c75a321c9370) () override | Destructor (internal use only). +  | [Events](#classmavsdk_1_1_events_1a888740505c24a9bdad1f6e9ccd60a130) (const [Events](classmavsdk_1_1_events.md) & other) | Copy constructor. +[EventsHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a64c99a834c6babf6cdb3b466a923e3ee) | [subscribe_events](#classmavsdk_1_1_events_1a4f167095c9a2c6362a9e5c336a7646a3) (const [EventsCallback](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1aaa9c2f1d7915aedfdb0da5de7e31bbfb) & callback) | Subscribe to event updates. +void | [unsubscribe_events](#classmavsdk_1_1_events_1a4e7146bf1708b3d8a00bc29dd1205c97) ([EventsHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a64c99a834c6babf6cdb3b466a923e3ee) handle) | Unsubscribe from subscribe_events. +[HealthAndArmingChecksHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a09ac962d8d560de37c93b16484474fa4) | [subscribe_health_and_arming_checks](#classmavsdk_1_1_events_1a1d95f16aec0b9d9af3fc379029883b3e) (const [HealthAndArmingChecksCallback](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1ada96803a50810356893417591d91b1a3) & callback) | Subscribe to arming check updates. +void | [unsubscribe_health_and_arming_checks](#classmavsdk_1_1_events_1a6e37b2dc8ae70404e459bf8f6d37bcb7) ([HealthAndArmingChecksHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a09ac962d8d560de37c93b16484474fa4) handle) | Unsubscribe from subscribe_health_and_arming_checks. +std::pair< [Result](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1abf1e4db55bd810ee6f5fce5d5c9439b1), [Events::HealthAndArmingCheckReport](structmavsdk_1_1_events_1_1_health_and_arming_check_report.md) > | [get_health_and_arming_checks_report](#classmavsdk_1_1_events_1ae8af916ca33c66d0d6ffb6fe8e8ae60d) () const | Get the latest report. +const [Events](classmavsdk_1_1_events.md) & | [operator=](#classmavsdk_1_1_events_1a7fa7923b2757e03a566ec46646440f75) (const [Events](classmavsdk_1_1_events.md) &)=delete | Equality operator (object is not copyable). + + +## Constructor & Destructor Documentation + + +### Events() {#classmavsdk_1_1_events_1a2f3778cf7118bd5a11b68e28655ef485} +```cpp +mavsdk::Events::Events(System &system) +``` + + +Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). + +The plugin is typically created as shown below: + +```cpp +auto events = Events(system); +``` + +**Parameters** + +* [System](classmavsdk_1_1_system.md)& **system** - The specific system associated with this plugin. + +### Events() {#classmavsdk_1_1_events_1ae8e05a45bfac1043356936f1a15f8f2f} +```cpp +mavsdk::Events::Events(std::shared_ptr< System > system) +``` + + +Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). + +The plugin is typically created as shown below: + +```cpp +auto events = Events(system); +``` + +**Parameters** + +* std::shared_ptr< [System](classmavsdk_1_1_system.md) > **system** - The specific system associated with this plugin. + +### ~Events() {#classmavsdk_1_1_events_1ac04cade0cb57f7858655c75a321c9370} +```cpp +mavsdk::Events::~Events() override +``` + + +Destructor (internal use only). + + +### Events() {#classmavsdk_1_1_events_1a888740505c24a9bdad1f6e9ccd60a130} +```cpp +mavsdk::Events::Events(const Events &other) +``` + + +Copy constructor. + + +**Parameters** + +* const [Events](classmavsdk_1_1_events.md)& **other** - + +## Member Typdef Documentation + + +### typedef ResultCallback {#classmavsdk_1_1_events_1a36c781e03d503c528d7da31506cb0af3} + +```cpp +using mavsdk::Events::ResultCallback = std::function +``` + + +Callback type for asynchronous [Events](classmavsdk_1_1_events.md) calls. + + +### typedef EventsCallback {#classmavsdk_1_1_events_1aaa9c2f1d7915aedfdb0da5de7e31bbfb} + +```cpp +using mavsdk::Events::EventsCallback = std::function +``` + + +Callback type for subscribe_events. + + +### typedef EventsHandle {#classmavsdk_1_1_events_1a64c99a834c6babf6cdb3b466a923e3ee} + +```cpp +using mavsdk::Events::EventsHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_events. + + +### typedef HealthAndArmingChecksCallback {#classmavsdk_1_1_events_1ada96803a50810356893417591d91b1a3} + +```cpp +using mavsdk::Events::HealthAndArmingChecksCallback = std::function +``` + + +Callback type for subscribe_health_and_arming_checks. + + +### typedef HealthAndArmingChecksHandle {#classmavsdk_1_1_events_1a09ac962d8d560de37c93b16484474fa4} + +```cpp +using mavsdk::Events::HealthAndArmingChecksHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_health_and_arming_checks. + + +## Member Enumeration Documentation + + +### enum LogLevel {#classmavsdk_1_1_events_1a237c8de77f3995138125db44d148cecc} + + +Log level type. + + +Value | Description +--- | --- + `Emergency` | Emergency. + `Alert` | Alert. + `Critical` | Critical. + `Error` | Error. + `Warning` | Warning. + `Notice` | Notice. + `Info` | [Info](classmavsdk_1_1_info.md). + `Debug` | Debug. + +### enum Result {#classmavsdk_1_1_events_1abf1e4db55bd810ee6f5fce5d5c9439b1} + + +Possible results returned. + + +Value | Description +--- | --- + `Success` | Successful result. + `NotAvailable` | Not available. + `ConnectionError` | Connection error. + `Unsupported` | Unsupported. + `Denied` | Denied. + `Failed` | Failed. + `Timeout` | Timeout. + `NoSystem` | No system available. + `Unknown` | Unknown result. + +## Member Function Documentation + + +### subscribe_events() {#classmavsdk_1_1_events_1a4f167095c9a2c6362a9e5c336a7646a3} +```cpp +EventsHandle mavsdk::Events::subscribe_events(const EventsCallback &callback) +``` + + +Subscribe to event updates. + + +**Parameters** + +* const [EventsCallback](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1aaa9c2f1d7915aedfdb0da5de7e31bbfb)& **callback** - + +**Returns** + + [EventsHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a64c99a834c6babf6cdb3b466a923e3ee) - + +### unsubscribe_events() {#classmavsdk_1_1_events_1a4e7146bf1708b3d8a00bc29dd1205c97} +```cpp +void mavsdk::Events::unsubscribe_events(EventsHandle handle) +``` + + +Unsubscribe from subscribe_events. + + +**Parameters** + +* [EventsHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a64c99a834c6babf6cdb3b466a923e3ee) **handle** - + +### subscribe_health_and_arming_checks() {#classmavsdk_1_1_events_1a1d95f16aec0b9d9af3fc379029883b3e} +```cpp +HealthAndArmingChecksHandle mavsdk::Events::subscribe_health_and_arming_checks(const HealthAndArmingChecksCallback &callback) +``` + + +Subscribe to arming check updates. + + +**Parameters** + +* const [HealthAndArmingChecksCallback](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1ada96803a50810356893417591d91b1a3)& **callback** - + +**Returns** + + [HealthAndArmingChecksHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a09ac962d8d560de37c93b16484474fa4) - + +### unsubscribe_health_and_arming_checks() {#classmavsdk_1_1_events_1a6e37b2dc8ae70404e459bf8f6d37bcb7} +```cpp +void mavsdk::Events::unsubscribe_health_and_arming_checks(HealthAndArmingChecksHandle handle) +``` + + +Unsubscribe from subscribe_health_and_arming_checks. + + +**Parameters** + +* [HealthAndArmingChecksHandle](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a09ac962d8d560de37c93b16484474fa4) **handle** - + +### get_health_and_arming_checks_report() {#classmavsdk_1_1_events_1ae8af916ca33c66d0d6ffb6fe8e8ae60d} +```cpp +std::pair< Result, Events::HealthAndArmingCheckReport > mavsdk::Events::get_health_and_arming_checks_report() const +``` + + +Get the latest report. + +This function is blocking. + +**Returns** + + std::pair< [Result](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1abf1e4db55bd810ee6f5fce5d5c9439b1), [Events::HealthAndArmingCheckReport](structmavsdk_1_1_events_1_1_health_and_arming_check_report.md) > - Result of request. + +### operator=() {#classmavsdk_1_1_events_1a7fa7923b2757e03a566ec46646440f75} +```cpp +const Events & mavsdk::Events::operator=(const Events &)=delete +``` + + +Equality operator (object is not copyable). + + +**Parameters** + +* const [Events](classmavsdk_1_1_events.md)& - + +**Returns** + + const [Events](classmavsdk_1_1_events.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_failure.md b/docs/en/cpp/api_reference/classmavsdk_1_1_failure.md index f5020ce478..e68d924341 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_failure.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_failure.md @@ -27,7 +27,7 @@ Type | Name | Description   | [~Failure](#classmavsdk_1_1_failure_1a1358a71e00d96af5415236183c6508cd) () override | Destructor (internal use only).   | [Failure](#classmavsdk_1_1_failure_1ae12162366b96624fa85d345a7166749c) (const [Failure](classmavsdk_1_1_failure.md) & other) | Copy constructor. [Result](classmavsdk_1_1_failure.md#classmavsdk_1_1_failure_1a6dcdd665b49a7ddf48c76b41475022f1) | [inject](#classmavsdk_1_1_failure_1ae937d22216ecae38f4c763f503cbbd88) ([FailureUnit](classmavsdk_1_1_failure.md#classmavsdk_1_1_failure_1a471f93c1fbff2124ebdea7fb681e23f1) failure_unit, [FailureType](classmavsdk_1_1_failure.md#classmavsdk_1_1_failure_1ade0813be29826ae35e6692f506e8ab72) failure_type, int32_t instance)const | Injects a failure. -const [Failure](classmavsdk_1_1_failure.md) & | [operator=](#classmavsdk_1_1_failure_1a255209f9df74ffde1f63b707f17bdb72) (const [Failure](classmavsdk_1_1_failure.md) &)=delete | Equality operator (object is not copyable). +const [Failure](classmavsdk_1_1_failure.md) & | [operator=](#classmavsdk_1_1_failure_1a9995bc44876b37dc942862090bb57fb2) (const [Failure](classmavsdk_1_1_failure.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -188,9 +188,9 @@ This function is blocking.  [Result](classmavsdk_1_1_failure.md#classmavsdk_1_1_failure_1a6dcdd665b49a7ddf48c76b41475022f1) - Result of request. -### operator=() {#classmavsdk_1_1_failure_1a255209f9df74ffde1f63b707f17bdb72} +### operator=() {#classmavsdk_1_1_failure_1a9995bc44876b37dc942862090bb57fb2} ```cpp -const Failure& mavsdk::Failure::operator=(const Failure &)=delete +const Failure & mavsdk::Failure::operator=(const Failure &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_follow_me.md b/docs/en/cpp/api_reference/classmavsdk_1_1_follow_me.md index cbd397efec..cee4d136c5 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_follow_me.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_follow_me.md @@ -38,7 +38,7 @@ bool | [is_active](#classmavsdk_1_1_follow_me_1a48ab77939257e52159bd9ed19335a7de [FollowMe::TargetLocation](structmavsdk_1_1_follow_me_1_1_target_location.md) | [get_last_location](#classmavsdk_1_1_follow_me_1af2a1af346ee2fa7761b58b406e9e6e0c) () const | Get the last location of the target. [Result](classmavsdk_1_1_follow_me.md#classmavsdk_1_1_follow_me_1a2b3f334ea72fd84d9e925fb3756451d8) | [start](#classmavsdk_1_1_follow_me_1a4b6ae3ec1ff07d8b3a79038e04992003) () const | Start [FollowMe](classmavsdk_1_1_follow_me.md) mode. [Result](classmavsdk_1_1_follow_me.md#classmavsdk_1_1_follow_me_1a2b3f334ea72fd84d9e925fb3756451d8) | [stop](#classmavsdk_1_1_follow_me_1a202a7b9edf56d9b883c974a09c14ba7d) () const | Stop [FollowMe](classmavsdk_1_1_follow_me.md) mode. -const [FollowMe](classmavsdk_1_1_follow_me.md) & | [operator=](#classmavsdk_1_1_follow_me_1a6292f6dd2c91cedde0e3b82952d83510) (const [FollowMe](classmavsdk_1_1_follow_me.md) &)=delete | Equality operator (object is not copyable). +const [FollowMe](classmavsdk_1_1_follow_me.md) & | [operator=](#classmavsdk_1_1_follow_me_1ab9787b3a8301c734aa22745ac753bbb9) (const [FollowMe](classmavsdk_1_1_follow_me.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -245,9 +245,9 @@ This function is blocking.  [Result](classmavsdk_1_1_follow_me.md#classmavsdk_1_1_follow_me_1a2b3f334ea72fd84d9e925fb3756451d8) - Result of request. -### operator=() {#classmavsdk_1_1_follow_me_1a6292f6dd2c91cedde0e3b82952d83510} +### operator=() {#classmavsdk_1_1_follow_me_1ab9787b3a8301c734aa22745ac753bbb9} ```cpp -const FollowMe& mavsdk::FollowMe::operator=(const FollowMe &)=delete +const FollowMe & mavsdk::FollowMe::operator=(const FollowMe &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_ftp.md b/docs/en/cpp/api_reference/classmavsdk_1_1_ftp.md index 827da40119..5826a04264 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_ftp.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_ftp.md @@ -10,6 +10,8 @@ Implements file transfer functionality using MAVLink FTP. ## Data Structures +struct [ListDirectoryData](structmavsdk_1_1_ftp_1_1_list_directory_data.md) + struct [ProgressData](structmavsdk_1_1_ftp_1_1_progress_data.md) ## Public Types @@ -21,7 +23,7 @@ enum [Result](#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4) | Possibl std::function< void([Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4))> [ResultCallback](#classmavsdk_1_1_ftp_1a04a12a1ab954b24a54570300f89486b0) | Callback type for asynchronous [Ftp](classmavsdk_1_1_ftp.md) calls. std::function< void([Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), [ProgressData](structmavsdk_1_1_ftp_1_1_progress_data.md))> [DownloadCallback](#classmavsdk_1_1_ftp_1a7c8e0377726e349a8a4e12495db42c75) | Callback type for download_async. std::function< void([Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), [ProgressData](structmavsdk_1_1_ftp_1_1_progress_data.md))> [UploadCallback](#classmavsdk_1_1_ftp_1a50ffb77f0730267f499656d40291f5a3) | Callback type for upload_async. -std::function< void([Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), std::vector< std::string >)> [ListDirectoryCallback](#classmavsdk_1_1_ftp_1a87a77c4e013a8665017504a550d876b7) | Callback type for list_directory_async. +std::function< void([Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), [ListDirectoryData](structmavsdk_1_1_ftp_1_1_list_directory_data.md))> [ListDirectoryCallback](#classmavsdk_1_1_ftp_1a88f904585306ce744d4f723a840c976c) | Callback type for list_directory_async. std::function< void([Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), bool)> [AreFilesIdenticalCallback](#classmavsdk_1_1_ftp_1abe24e99f7141a234206f8952d2f61318) | Callback type for are_files_identical_async. ## Public Member Functions @@ -35,8 +37,8 @@ Type | Name | Description   | [Ftp](#classmavsdk_1_1_ftp_1a7b7486356a7b04fb231c430e090c673e) (const [Ftp](classmavsdk_1_1_ftp.md) & other) | Copy constructor. void | [download_async](#classmavsdk_1_1_ftp_1a0845245b8e1d0e74ed8961c90c96d1d3) (std::string remote_file_path, std::string local_dir, bool use_burst, const [DownloadCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a7c8e0377726e349a8a4e12495db42c75) & callback) | Downloads a file to local directory. void | [upload_async](#classmavsdk_1_1_ftp_1affe86a8b0a035109e7df9bd85c99f442) (std::string local_file_path, std::string remote_dir, const [UploadCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a50ffb77f0730267f499656d40291f5a3) & callback) | Uploads local file to remote directory. -void | [list_directory_async](#classmavsdk_1_1_ftp_1abf5d83104a7293413b62e7a8ba1a0f2c) (std::string remote_dir, const [ListDirectoryCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a87a77c4e013a8665017504a550d876b7) callback) | Lists items from a remote directory. -std::pair< [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), std::vector< std::string > > | [list_directory](#classmavsdk_1_1_ftp_1a2301aba586be9dd4569d984a58967ccc) (std::string remote_dir)const | Lists items from a remote directory. +void | [list_directory_async](#classmavsdk_1_1_ftp_1abf5d83104a7293413b62e7a8ba1a0f2c) (std::string remote_dir, const [ListDirectoryCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a88f904585306ce744d4f723a840c976c) callback) | Lists items from a remote directory. +std::pair< [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), [Ftp::ListDirectoryData](structmavsdk_1_1_ftp_1_1_list_directory_data.md) > | [list_directory](#classmavsdk_1_1_ftp_1a7a6160b63fa193f84c9059b8a7c09fc4) (std::string remote_dir)const | Lists items from a remote directory. void | [create_directory_async](#classmavsdk_1_1_ftp_1aa53fdd5c005bd4da3e0cb29d448689d3) (std::string remote_dir, const [ResultCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a04a12a1ab954b24a54570300f89486b0) callback) | Creates a remote directory. [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4) | [create_directory](#classmavsdk_1_1_ftp_1ac6edf64fe63d5934b892c95778e1c548) (std::string remote_dir)const | Creates a remote directory. void | [remove_directory_async](#classmavsdk_1_1_ftp_1a25823c7298dc2d081532dd094d013b8a) (std::string remote_dir, const [ResultCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a04a12a1ab954b24a54570300f89486b0) callback) | Removes a remote directory. @@ -46,9 +48,9 @@ void | [remove_file_async](#classmavsdk_1_1_ftp_1a3ecda69288fb860a8da1f8fad25af3 void | [rename_async](#classmavsdk_1_1_ftp_1afea8b15ad7b5748b0b5f68fd7103514a) (std::string remote_from_path, std::string remote_to_path, const [ResultCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a04a12a1ab954b24a54570300f89486b0) callback) | Renames a remote file or remote directory. [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4) | [rename](#classmavsdk_1_1_ftp_1ac7411b38ea31f84f4f679b6b85313032) (std::string remote_from_path, std::string remote_to_path)const | Renames a remote file or remote directory. void | [are_files_identical_async](#classmavsdk_1_1_ftp_1abddebf1a103b2853116e68f5f870e4a7) (std::string local_file_path, std::string remote_file_path, const [AreFilesIdenticalCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1abe24e99f7141a234206f8952d2f61318) callback) | Compares a local file to a remote file using a CRC32 checksum. -std::pair< [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), bool > | [are_files_identical](#classmavsdk_1_1_ftp_1a1ace427243aedef4b0988a055fc414bf) (std::string local_file_path, std::string remote_file_path)const | Compares a local file to a remote file using a CRC32 checksum. +std::pair< [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), bool > | [are_files_identical](#classmavsdk_1_1_ftp_1af4c63e732c056f906a10b9fdb915c4bc) (std::string local_file_path, std::string remote_file_path)const | Compares a local file to a remote file using a CRC32 checksum. [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4) | [set_target_compid](#classmavsdk_1_1_ftp_1ad93744cd25a89beffe0d72a090748229) (uint32_t compid)const | Set target component ID. By default it is the autopilot. -const [Ftp](classmavsdk_1_1_ftp.md) & | [operator=](#classmavsdk_1_1_ftp_1a01dc5f41d1e684a667d31c213728b376) (const [Ftp](classmavsdk_1_1_ftp.md) &)=delete | Equality operator (object is not copyable). +const [Ftp](classmavsdk_1_1_ftp.md) & | [operator=](#classmavsdk_1_1_ftp_1a43e32f49ce47a9424ac2ded204413225) (const [Ftp](classmavsdk_1_1_ftp.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -145,10 +147,10 @@ using mavsdk::Ftp::UploadCallback = std::function Callback type for upload_async. -### typedef ListDirectoryCallback {#classmavsdk_1_1_ftp_1a87a77c4e013a8665017504a550d876b7} +### typedef ListDirectoryCallback {#classmavsdk_1_1_ftp_1a88f904585306ce744d4f723a840c976c} ```cpp -using mavsdk::Ftp::ListDirectoryCallback = std::function)> +using mavsdk::Ftp::ListDirectoryCallback = std::function ``` @@ -237,11 +239,11 @@ This function is non-blocking. See 'list_directory' for the blocking counterpart **Parameters** * std::string **remote_dir** - -* const [ListDirectoryCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a87a77c4e013a8665017504a550d876b7) **callback** - +* const [ListDirectoryCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a88f904585306ce744d4f723a840c976c) **callback** - -### list_directory() {#classmavsdk_1_1_ftp_1a2301aba586be9dd4569d984a58967ccc} +### list_directory() {#classmavsdk_1_1_ftp_1a7a6160b63fa193f84c9059b8a7c09fc4} ```cpp -std::pair > mavsdk::Ftp::list_directory(std::string remote_dir) const +std::pair< Result, Ftp::ListDirectoryData > mavsdk::Ftp::list_directory(std::string remote_dir) const ``` @@ -255,7 +257,7 @@ This function is blocking. See 'list_directory_async' for the non-blocking count **Returns** - std::pair< [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), std::vector< std::string > > - Result of request. + std::pair< [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4), [Ftp::ListDirectoryData](structmavsdk_1_1_ftp_1_1_list_directory_data.md) > - Result of request. ### create_directory_async() {#classmavsdk_1_1_ftp_1aa53fdd5c005bd4da3e0cb29d448689d3} ```cpp @@ -407,9 +409,9 @@ This function is non-blocking. See 'are_files_identical' for the blocking counte * std::string **remote_file_path** - * const [AreFilesIdenticalCallback](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1abe24e99f7141a234206f8952d2f61318) **callback** - -### are_files_identical() {#classmavsdk_1_1_ftp_1a1ace427243aedef4b0988a055fc414bf} +### are_files_identical() {#classmavsdk_1_1_ftp_1af4c63e732c056f906a10b9fdb915c4bc} ```cpp -std::pair mavsdk::Ftp::are_files_identical(std::string local_file_path, std::string remote_file_path) const +std::pair< Result, bool > mavsdk::Ftp::are_files_identical(std::string local_file_path, std::string remote_file_path) const ``` @@ -444,9 +446,9 @@ This function is blocking.  [Result](classmavsdk_1_1_ftp.md#classmavsdk_1_1_ftp_1a4cc4f42a3ef6d63403d811e594b946e4) - Result of request. -### operator=() {#classmavsdk_1_1_ftp_1a01dc5f41d1e684a667d31c213728b376} +### operator=() {#classmavsdk_1_1_ftp_1a43e32f49ce47a9424ac2ded204413225} ```cpp -const Ftp& mavsdk::Ftp::operator=(const Ftp &)=delete +const Ftp & mavsdk::Ftp::operator=(const Ftp &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_ftp_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_ftp_server.md index f8fb61961f..0c469927e1 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_ftp_server.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_ftp_server.md @@ -24,7 +24,7 @@ Type | Name | Description   | [~FtpServer](#classmavsdk_1_1_ftp_server_1a685d6499b3fbc7d8b4fac6f8031e7e99) () override | Destructor (internal use only).   | [FtpServer](#classmavsdk_1_1_ftp_server_1afed6d9c192b299e27d5e0014e63c275f) (const [FtpServer](classmavsdk_1_1_ftp_server.md) & other) | Copy constructor. [Result](classmavsdk_1_1_ftp_server.md#classmavsdk_1_1_ftp_server_1a24027b6ade1f681dd191a81c25653763) | [set_root_dir](#classmavsdk_1_1_ftp_server_1aa79196f0d3cd0bc178a57711252ed8f3) (std::string path)const | Set root directory. -const [FtpServer](classmavsdk_1_1_ftp_server.md) & | [operator=](#classmavsdk_1_1_ftp_server_1aa3822f6508adad0b930cbca3be4fd5c5) (const [FtpServer](classmavsdk_1_1_ftp_server.md) &)=delete | Equality operator (object is not copyable). +const [FtpServer](classmavsdk_1_1_ftp_server.md) & | [operator=](#classmavsdk_1_1_ftp_server_1ae2226ea7897a33dfa5225cdc023f23ed) (const [FtpServer](classmavsdk_1_1_ftp_server.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -123,9 +123,9 @@ This function is blocking.  [Result](classmavsdk_1_1_ftp_server.md#classmavsdk_1_1_ftp_server_1a24027b6ade1f681dd191a81c25653763) - Result of request. -### operator=() {#classmavsdk_1_1_ftp_server_1aa3822f6508adad0b930cbca3be4fd5c5} +### operator=() {#classmavsdk_1_1_ftp_server_1ae2226ea7897a33dfa5225cdc023f23ed} ```cpp -const FtpServer& mavsdk::FtpServer::operator=(const FtpServer &)=delete +const FtpServer & mavsdk::FtpServer::operator=(const FtpServer &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_geofence.md b/docs/en/cpp/api_reference/classmavsdk_1_1_geofence.md index 175259a495..0cea6b6014 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_geofence.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_geofence.md @@ -40,7 +40,7 @@ void | [upload_geofence_async](#classmavsdk_1_1_geofence_1a1f0c6431b86b77c29f19e [Result](classmavsdk_1_1_geofence.md#classmavsdk_1_1_geofence_1ab64d6e3b9aeb9b6d5e45ae8a843a2642) | [upload_geofence](#classmavsdk_1_1_geofence_1ab2e825f0955e7a320117a21d649bab09) ([GeofenceData](structmavsdk_1_1_geofence_1_1_geofence_data.md) geofence_data)const | Upload geofences. void | [clear_geofence_async](#classmavsdk_1_1_geofence_1a6947151765b621a93d35885599812752) (const [ResultCallback](classmavsdk_1_1_geofence.md#classmavsdk_1_1_geofence_1af9662e645781e4e64ed8b7c65d3d9309) callback) | Clear all geofences saved on the vehicle. [Result](classmavsdk_1_1_geofence.md#classmavsdk_1_1_geofence_1ab64d6e3b9aeb9b6d5e45ae8a843a2642) | [clear_geofence](#classmavsdk_1_1_geofence_1a54b2a696e8aebae6916116adb92c03c3) () const | Clear all geofences saved on the vehicle. -const [Geofence](classmavsdk_1_1_geofence.md) & | [operator=](#classmavsdk_1_1_geofence_1a2e8a69dddfa9b4937df117060fa2e0d7) (const [Geofence](classmavsdk_1_1_geofence.md) &)=delete | Equality operator (object is not copyable). +const [Geofence](classmavsdk_1_1_geofence.md) & | [operator=](#classmavsdk_1_1_geofence_1a174d03979e425bf8440dfe9bbabaf7d2) (const [Geofence](classmavsdk_1_1_geofence.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -218,9 +218,9 @@ This function is blocking. See 'clear_geofence_async' for the non-blocking count  [Result](classmavsdk_1_1_geofence.md#classmavsdk_1_1_geofence_1ab64d6e3b9aeb9b6d5e45ae8a843a2642) - Result of request. -### operator=() {#classmavsdk_1_1_geofence_1a2e8a69dddfa9b4937df117060fa2e0d7} +### operator=() {#classmavsdk_1_1_geofence_1a174d03979e425bf8440dfe9bbabaf7d2} ```cpp -const Geofence& mavsdk::Geofence::operator=(const Geofence &)=delete +const Geofence & mavsdk::Geofence::operator=(const Geofence &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_gimbal.md b/docs/en/cpp/api_reference/classmavsdk_1_1_gimbal.md index ec98cdb59a..999e5980d2 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_gimbal.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_gimbal.md @@ -10,8 +10,20 @@ Provide control over a gimbal. ## Data Structures +struct [AngularVelocityBody](structmavsdk_1_1_gimbal_1_1_angular_velocity_body.md) + +struct [Attitude](structmavsdk_1_1_gimbal_1_1_attitude.md) + struct [ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) +struct [EulerAngle](structmavsdk_1_1_gimbal_1_1_euler_angle.md) + +struct [GimbalItem](structmavsdk_1_1_gimbal_1_1_gimbal_item.md) + +struct [GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md) + +struct [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) + ## Public Types @@ -19,10 +31,15 @@ Type | Description --- | --- enum [GimbalMode](#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) | [Gimbal](classmavsdk_1_1_gimbal.md) mode type. enum [ControlMode](#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) | Control mode. +enum [SendMode](#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) | The send mode type. enum [Result](#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | Possible results returned for gimbal commands. std::function< void([Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac))> [ResultCallback](#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) | Callback type for asynchronous [Gimbal](classmavsdk_1_1_gimbal.md) calls. -std::function< void([ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md))> [ControlCallback](#classmavsdk_1_1_gimbal_1a1645ab20c41161e6c47620b7352eef62) | Callback type for subscribe_control. -[Handle](classmavsdk_1_1_handle.md)< [ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) > [ControlHandle](#classmavsdk_1_1_gimbal_1accab76c321008685a455ccff45811397) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_control. +std::function< void([GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md))> [GimbalListCallback](#classmavsdk_1_1_gimbal_1a1656fb54230e1adc61b3a050a423a6c9) | Callback type for subscribe_gimbal_list. +[Handle](classmavsdk_1_1_handle.md)< [GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md) > [GimbalListHandle](#classmavsdk_1_1_gimbal_1a51e98cc1239dd440d37d4dbed78f4ae7) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_gimbal_list. +std::function< void([ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md))> [ControlStatusCallback](#classmavsdk_1_1_gimbal_1a2ab2120cb3ff6c6a1f726542bd0d8dea) | Callback type for subscribe_control_status. +[Handle](classmavsdk_1_1_handle.md)< [ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) > [ControlStatusHandle](#classmavsdk_1_1_gimbal_1aade6db709ce87cb0ec5536ae243cb50d) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_control_status. +std::function< void([Attitude](structmavsdk_1_1_gimbal_1_1_attitude.md))> [AttitudeCallback](#classmavsdk_1_1_gimbal_1a07eafc661a23ee1d55ab0dd86e3c71ed) | Callback type for subscribe_attitude. +[Handle](classmavsdk_1_1_handle.md)< [Attitude](structmavsdk_1_1_gimbal_1_1_attitude.md) > [AttitudeHandle](#classmavsdk_1_1_gimbal_1af7c71cdd8516aec8c9d160977f7c5396) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_attitude. ## Public Member Functions @@ -33,22 +50,26 @@ Type | Name | Description   | [Gimbal](#classmavsdk_1_1_gimbal_1aa3cb6e1e37a2f275ab5cc8ed4dd71d93) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md).   | [~Gimbal](#classmavsdk_1_1_gimbal_1a3b86d8209172a578f238928b9f5bfdd6) () override | Destructor (internal use only).   | [Gimbal](#classmavsdk_1_1_gimbal_1ae69df278ca37deaee22fb13053fd4f2d) (const [Gimbal](classmavsdk_1_1_gimbal.md) & other) | Copy constructor. -void | [set_pitch_and_yaw_async](#classmavsdk_1_1_gimbal_1a325a49cc256359013cbc917b3576f292) (float pitch_deg, float yaw_deg, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal pitch and yaw angles. -[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_pitch_and_yaw](#classmavsdk_1_1_gimbal_1ad65ba3258833fe78f2939b9b72dc3b88) (float pitch_deg, float yaw_deg)const | Set gimbal pitch and yaw angles. -void | [set_pitch_rate_and_yaw_rate_async](#classmavsdk_1_1_gimbal_1a161b3f85cd9fa30439774ef47a10c51d) (float pitch_rate_deg_s, float yaw_rate_deg_s, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal angular rates around pitch and yaw axes. -[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_pitch_rate_and_yaw_rate](#classmavsdk_1_1_gimbal_1a2ad12582d192d8594d7da315e2729129) (float pitch_rate_deg_s, float yaw_rate_deg_s)const | Set gimbal angular rates around pitch and yaw axes. -void | [set_mode_async](#classmavsdk_1_1_gimbal_1ad69853994c134b0e88d0f94744254066) ([GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) gimbal_mode, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal mode. -[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_mode](#classmavsdk_1_1_gimbal_1a037285883ceba14e0df9c7f8c19f4423) ([GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) gimbal_mode)const | Set gimbal mode. -void | [set_roi_location_async](#classmavsdk_1_1_gimbal_1ab3c42a7042231e48dfab881030fe30c0) (double latitude_deg, double longitude_deg, float altitude_m, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal region of interest (ROI). -[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_roi_location](#classmavsdk_1_1_gimbal_1a035ddc270efce19a9be54b98add57919) (double latitude_deg, double longitude_deg, float altitude_m)const | Set gimbal region of interest (ROI). -void | [take_control_async](#classmavsdk_1_1_gimbal_1a331139df593e8ccef0f8ca7652f2d2bc) ([ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) control_mode, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Take control. -[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [take_control](#classmavsdk_1_1_gimbal_1a7dabe20d1bceb7031440fefba59cd707) ([ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) control_mode)const | Take control. -void | [release_control_async](#classmavsdk_1_1_gimbal_1aa58402c4e2d9506dbe9839ef8cbfb920) (const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Release control. -[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [release_control](#classmavsdk_1_1_gimbal_1ab994d4130b2956e2d33613ffb2127335) () const | Release control. -[ControlHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1accab76c321008685a455ccff45811397) | [subscribe_control](#classmavsdk_1_1_gimbal_1aafd016582be5b63d9b378d414f2faf30) (const [ControlCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a1645ab20c41161e6c47620b7352eef62) & callback) | Subscribe to control status updates. -void | [unsubscribe_control](#classmavsdk_1_1_gimbal_1a899b442fafac1d83b9450bd219f6975e) ([ControlHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1accab76c321008685a455ccff45811397) handle) | Unsubscribe from subscribe_control. -[ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) | [control](#classmavsdk_1_1_gimbal_1aae172788140e37d6125b224f5e79829e) () const | Poll for '[ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md)' (blocking). -const [Gimbal](classmavsdk_1_1_gimbal.md) & | [operator=](#classmavsdk_1_1_gimbal_1ac9a6e1936f58ce8f957be7c6bcc0d134) (const [Gimbal](classmavsdk_1_1_gimbal.md) &)=delete | Equality operator (object is not copyable). +void | [set_angles_async](#classmavsdk_1_1_gimbal_1a2da4d10fa81ec525dfda9c0036f94302) (int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, [GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) gimbal_mode, [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) send_mode, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal roll, pitch and yaw angles. +[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_angles](#classmavsdk_1_1_gimbal_1a481cc6658ef52d40469d71d4b3a1ebda) (int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, [GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) gimbal_mode, [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) send_mode)const | Set gimbal roll, pitch and yaw angles. +void | [set_angular_rates_async](#classmavsdk_1_1_gimbal_1a0f0751ee5268f95d1833651dff78b956) (int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, [GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) gimbal_mode, [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) send_mode, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal angular rates. +[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_angular_rates](#classmavsdk_1_1_gimbal_1ac69110603cc67a3988791f371706b698) (int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, [GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) gimbal_mode, [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) send_mode)const | Set gimbal angular rates. +void | [set_roi_location_async](#classmavsdk_1_1_gimbal_1a762050f84df6be7adc1eecae4f1b2e48) (int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Set gimbal region of interest (ROI). +[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [set_roi_location](#classmavsdk_1_1_gimbal_1a5010c2665f20524d3b86ccfe6b33cdfa) (int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m)const | Set gimbal region of interest (ROI). +void | [take_control_async](#classmavsdk_1_1_gimbal_1a814363300828b02981bf2e818267c9be) (int32_t gimbal_id, [ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) control_mode, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Take control. +[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [take_control](#classmavsdk_1_1_gimbal_1afe512b2ce37eda69a28d285716076db7) (int32_t gimbal_id, [ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) control_mode)const | Take control. +void | [release_control_async](#classmavsdk_1_1_gimbal_1a68305d969bc88353513890aa2a7a627f) (int32_t gimbal_id, const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) callback) | Release control. +[Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) | [release_control](#classmavsdk_1_1_gimbal_1ad0b0665a3502fac6199ac903b24bbd6f) (int32_t gimbal_id)const | Release control. +[GimbalListHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a51e98cc1239dd440d37d4dbed78f4ae7) | [subscribe_gimbal_list](#classmavsdk_1_1_gimbal_1a4ca185553a4a327f46c317942d2731d0) (const [GimbalListCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a1656fb54230e1adc61b3a050a423a6c9) & callback) | Subscribe to list of gimbals. +void | [unsubscribe_gimbal_list](#classmavsdk_1_1_gimbal_1a82e516c2080c56d056cbf7a22ff4e716) ([GimbalListHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a51e98cc1239dd440d37d4dbed78f4ae7) handle) | Unsubscribe from subscribe_gimbal_list. +[GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md) | [gimbal_list](#classmavsdk_1_1_gimbal_1ad67df5fc01473dd94797d42c6be368fd) () const | Poll for '[GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md)' (blocking). +[ControlStatusHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aade6db709ce87cb0ec5536ae243cb50d) | [subscribe_control_status](#classmavsdk_1_1_gimbal_1ab34d06ee1ea0af89e334c3010aeacfd9) (const [ControlStatusCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a2ab2120cb3ff6c6a1f726542bd0d8dea) & callback) | Subscribe to control status updates. +void | [unsubscribe_control_status](#classmavsdk_1_1_gimbal_1a7314f438bd2b91ba98374cd2a1a2b285) ([ControlStatusHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aade6db709ce87cb0ec5536ae243cb50d) handle) | Unsubscribe from subscribe_control_status. +std::pair< [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac), [Gimbal::ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) > | [get_control_status](#classmavsdk_1_1_gimbal_1a6c4a10de4ecb79c7116654c1d99236f3) (int32_t gimbal_id)const | Get control status for specific gimbal. +[AttitudeHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1af7c71cdd8516aec8c9d160977f7c5396) | [subscribe_attitude](#classmavsdk_1_1_gimbal_1aa3500df0c7adff3819493dd7d38976a3) (const [AttitudeCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a07eafc661a23ee1d55ab0dd86e3c71ed) & callback) | Subscribe to attitude updates. +void | [unsubscribe_attitude](#classmavsdk_1_1_gimbal_1a11b1e0d91ca5c8ec50afd802d9d2532e) ([AttitudeHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1af7c71cdd8516aec8c9d160977f7c5396) handle) | Unsubscribe from subscribe_attitude. +std::pair< [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac), [Gimbal::Attitude](structmavsdk_1_1_gimbal_1_1_attitude.md) > | [get_attitude](#classmavsdk_1_1_gimbal_1a57c6e6c7297e55f5cc660e40e91b898b) (int32_t gimbal_id)const | Get attitude for specific gimbal. +const [Gimbal](classmavsdk_1_1_gimbal.md) & | [operator=](#classmavsdk_1_1_gimbal_1a2d16cfd6fbe82b0e34d35133ab5c9617) (const [Gimbal](classmavsdk_1_1_gimbal.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -125,24 +146,64 @@ using mavsdk::Gimbal::ResultCallback = std::function Callback type for asynchronous [Gimbal](classmavsdk_1_1_gimbal.md) calls. -### typedef ControlCallback {#classmavsdk_1_1_gimbal_1a1645ab20c41161e6c47620b7352eef62} +### typedef GimbalListCallback {#classmavsdk_1_1_gimbal_1a1656fb54230e1adc61b3a050a423a6c9} ```cpp -using mavsdk::Gimbal::ControlCallback = std::function +using mavsdk::Gimbal::GimbalListCallback = std::function ``` -Callback type for subscribe_control. +Callback type for subscribe_gimbal_list. -### typedef ControlHandle {#classmavsdk_1_1_gimbal_1accab76c321008685a455ccff45811397} +### typedef GimbalListHandle {#classmavsdk_1_1_gimbal_1a51e98cc1239dd440d37d4dbed78f4ae7} ```cpp -using mavsdk::Gimbal::ControlHandle = Handle +using mavsdk::Gimbal::GimbalListHandle = Handle ``` -[Handle](classmavsdk_1_1_handle.md) type for subscribe_control. +[Handle](classmavsdk_1_1_handle.md) type for subscribe_gimbal_list. + + +### typedef ControlStatusCallback {#classmavsdk_1_1_gimbal_1a2ab2120cb3ff6c6a1f726542bd0d8dea} + +```cpp +using mavsdk::Gimbal::ControlStatusCallback = std::function +``` + + +Callback type for subscribe_control_status. + + +### typedef ControlStatusHandle {#classmavsdk_1_1_gimbal_1aade6db709ce87cb0ec5536ae243cb50d} + +```cpp +using mavsdk::Gimbal::ControlStatusHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_control_status. + + +### typedef AttitudeCallback {#classmavsdk_1_1_gimbal_1a07eafc661a23ee1d55ab0dd86e3c71ed} + +```cpp +using mavsdk::Gimbal::AttitudeCallback = std::function +``` + + +Callback type for subscribe_attitude. + + +### typedef AttitudeHandle {#classmavsdk_1_1_gimbal_1af7c71cdd8516aec8c9d160977f7c5396} + +```cpp +using mavsdk::Gimbal::AttitudeHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_attitude. ## Member Enumeration Documentation @@ -171,6 +232,17 @@ Value | Description `Primary` | To take primary control over the gimbal. `Secondary` | To take secondary control over the gimbal. +### enum SendMode {#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2} + + +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 {#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac} @@ -185,134 +257,124 @@ Value | Description `Timeout` | Command timed out. `Unsupported` | Functionality not supported. `NoSystem` | No system connected. + `InvalidArgument` | Invalid argument. ## Member Function Documentation -### set_pitch_and_yaw_async() {#classmavsdk_1_1_gimbal_1a325a49cc256359013cbc917b3576f292} +### set_angles_async() {#classmavsdk_1_1_gimbal_1a2da4d10fa81ec525dfda9c0036f94302} ```cpp -void mavsdk::Gimbal::set_pitch_and_yaw_async(float pitch_deg, float yaw_deg, const ResultCallback callback) +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 pitch and yaw angles. +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. -This sets the desired 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_pitch_and_yaw' for the blocking counterpart. + +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](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) **gimbal_mode** - +* [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) **send_mode** - * const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) **callback** - -### set_pitch_and_yaw() {#classmavsdk_1_1_gimbal_1ad65ba3258833fe78f2939b9b72dc3b88} +### set_angles() {#classmavsdk_1_1_gimbal_1a481cc6658ef52d40469d71d4b3a1ebda} ```cpp -Result mavsdk::Gimbal::set_pitch_and_yaw(float pitch_deg, float yaw_deg) const +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 pitch and yaw angles. +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. -This sets the desired 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_pitch_and_yaw_async' for the non-blocking counterpart. + +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](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) **gimbal_mode** - +* [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) **send_mode** - **Returns**  [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) - Result of request. -### set_pitch_rate_and_yaw_rate_async() {#classmavsdk_1_1_gimbal_1a161b3f85cd9fa30439774ef47a10c51d} +### set_angular_rates_async() {#classmavsdk_1_1_gimbal_1a0f0751ee5268f95d1833651dff78b956} ```cpp -void mavsdk::Gimbal::set_pitch_rate_and_yaw_rate_async(float pitch_rate_deg_s, float yaw_rate_deg_s, const ResultCallback callback) +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 around pitch and yaw axes. +Set gimbal angular rates. -This sets the desired angular rates around 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. +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. -This function is non-blocking. See 'set_pitch_rate_and_yaw_rate' for the blocking counterpart. - -**Parameters** - -* float **pitch_rate_deg_s** - -* float **yaw_rate_deg_s** - -* const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) **callback** - - -### set_pitch_rate_and_yaw_rate() {#classmavsdk_1_1_gimbal_1a2ad12582d192d8594d7da315e2729129} -```cpp -Result mavsdk::Gimbal::set_pitch_rate_and_yaw_rate(float pitch_rate_deg_s, float yaw_rate_deg_s) const -``` +Note that the roll angle needs to be set to 0 when send_mode is Once. -Set gimbal angular rates around pitch and yaw axes. - -This sets the desired angular rates around 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. - - -This function is blocking. See 'set_pitch_rate_and_yaw_rate_async' for the non-blocking counterpart. +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** - - -**Returns** - - [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) - Result of request. - -### set_mode_async() {#classmavsdk_1_1_gimbal_1ad69853994c134b0e88d0f94744254066} -```cpp -void mavsdk::Gimbal::set_mode_async(GimbalMode gimbal_mode, const ResultCallback callback) -``` - - -Set gimbal mode. - -This sets the desired yaw mode 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. - - -This function is non-blocking. See 'set_mode' for the blocking counterpart. - -**Parameters** - * [GimbalMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) **gimbal_mode** - +* [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) **send_mode** - * const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) **callback** - -### set_mode() {#classmavsdk_1_1_gimbal_1a037285883ceba14e0df9c7f8c19f4423} +### set_angular_rates() {#classmavsdk_1_1_gimbal_1ac69110603cc67a3988791f371706b698} ```cpp -Result mavsdk::Gimbal::set_mode(GimbalMode gimbal_mode) const +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 mode. +Set gimbal angular rates. -This sets the desired yaw mode 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. +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. -This function is blocking. See 'set_mode_async' for the non-blocking counterpart. +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](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1afb92614c5d5915d3960bcea51bec2dca) **gimbal_mode** - +* [SendMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a625fee23155be376ebd67853bf9383a2) **send_mode** - **Returns**  [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) - Result of request. -### set_roi_location_async() {#classmavsdk_1_1_gimbal_1ab3c42a7042231e48dfab881030fe30c0} +### set_roi_location_async() {#classmavsdk_1_1_gimbal_1a762050f84df6be7adc1eecae4f1b2e48} ```cpp -void mavsdk::Gimbal::set_roi_location_async(double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback) +void mavsdk::Gimbal::set_roi_location_async(int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback) ``` @@ -325,14 +387,15 @@ This function is non-blocking. See 'set_roi_location' for the blocking counterpa **Parameters** +* int32_t **gimbal_id** - * double **latitude_deg** - * double **longitude_deg** - * float **altitude_m** - * const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) **callback** - -### set_roi_location() {#classmavsdk_1_1_gimbal_1a035ddc270efce19a9be54b98add57919} +### set_roi_location() {#classmavsdk_1_1_gimbal_1a5010c2665f20524d3b86ccfe6b33cdfa} ```cpp -Result mavsdk::Gimbal::set_roi_location(double latitude_deg, double longitude_deg, float altitude_m) const +Result mavsdk::Gimbal::set_roi_location(int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m) const ``` @@ -345,6 +408,7 @@ This function is blocking. See 'set_roi_location_async' for the non-blocking cou **Parameters** +* int32_t **gimbal_id** - * double **latitude_deg** - * double **longitude_deg** - * float **altitude_m** - @@ -353,9 +417,9 @@ This function is blocking. See 'set_roi_location_async' for the non-blocking cou  [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) - Result of request. -### take_control_async() {#classmavsdk_1_1_gimbal_1a331139df593e8ccef0f8ca7652f2d2bc} +### take_control_async() {#classmavsdk_1_1_gimbal_1a814363300828b02981bf2e818267c9be} ```cpp -void mavsdk::Gimbal::take_control_async(ControlMode control_mode, const ResultCallback callback) +void mavsdk::Gimbal::take_control_async(int32_t gimbal_id, ControlMode control_mode, const ResultCallback callback) ``` @@ -371,12 +435,13 @@ This function is non-blocking. See 'take_control' for the blocking counterpart. **Parameters** +* int32_t **gimbal_id** - * [ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) **control_mode** - * const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) **callback** - -### take_control() {#classmavsdk_1_1_gimbal_1a7dabe20d1bceb7031440fefba59cd707} +### take_control() {#classmavsdk_1_1_gimbal_1afe512b2ce37eda69a28d285716076db7} ```cpp -Result mavsdk::Gimbal::take_control(ControlMode control_mode) const +Result mavsdk::Gimbal::take_control(int32_t gimbal_id, ControlMode control_mode) const ``` @@ -392,15 +457,16 @@ This function is blocking. See 'take_control_async' for the non-blocking counter **Parameters** +* int32_t **gimbal_id** - * [ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) **control_mode** - **Returns**  [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) - Result of request. -### release_control_async() {#classmavsdk_1_1_gimbal_1aa58402c4e2d9506dbe9839ef8cbfb920} +### release_control_async() {#classmavsdk_1_1_gimbal_1a68305d969bc88353513890aa2a7a627f} ```cpp -void mavsdk::Gimbal::release_control_async(const ResultCallback callback) +void mavsdk::Gimbal::release_control_async(int32_t gimbal_id, const ResultCallback callback) ``` @@ -413,11 +479,12 @@ This function is non-blocking. See 'release_control' for the blocking counterpar **Parameters** +* int32_t **gimbal_id** - * const [ResultCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a88ee7dd17821fb9b12c44b2a3630c197) **callback** - -### release_control() {#classmavsdk_1_1_gimbal_1ab994d4130b2956e2d33613ffb2127335} +### release_control() {#classmavsdk_1_1_gimbal_1ad0b0665a3502fac6199ac903b24bbd6f} ```cpp -Result mavsdk::Gimbal::release_control() const +Result mavsdk::Gimbal::release_control(int32_t gimbal_id) const ``` @@ -428,13 +495,61 @@ 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](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac) - Result of request. -### subscribe_control() {#classmavsdk_1_1_gimbal_1aafd016582be5b63d9b378d414f2faf30} +### subscribe_gimbal_list() {#classmavsdk_1_1_gimbal_1a4ca185553a4a327f46c317942d2731d0} +```cpp +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](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a1656fb54230e1adc61b3a050a423a6c9)& **callback** - + +**Returns** + + [GimbalListHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a51e98cc1239dd440d37d4dbed78f4ae7) - + +### unsubscribe_gimbal_list() {#classmavsdk_1_1_gimbal_1a82e516c2080c56d056cbf7a22ff4e716} +```cpp +void mavsdk::Gimbal::unsubscribe_gimbal_list(GimbalListHandle handle) +``` + + +Unsubscribe from subscribe_gimbal_list. + + +**Parameters** + +* [GimbalListHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a51e98cc1239dd440d37d4dbed78f4ae7) **handle** - + +### gimbal_list() {#classmavsdk_1_1_gimbal_1ad67df5fc01473dd94797d42c6be368fd} +```cpp +GimbalList mavsdk::Gimbal::gimbal_list() const +``` + + +Poll for '[GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md)' (blocking). + + +**Returns** + + [GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md) - One [GimbalList](structmavsdk_1_1_gimbal_1_1_gimbal_list.md) update. + +### subscribe_control_status() {#classmavsdk_1_1_gimbal_1ab34d06ee1ea0af89e334c3010aeacfd9} ```cpp -ControlHandle mavsdk::Gimbal::subscribe_control(const ControlCallback &callback) +ControlStatusHandle mavsdk::Gimbal::subscribe_control_status(const ControlStatusCallback &callback) ``` @@ -444,41 +559,95 @@ This allows a component to know if it has primary, secondary or no control over **Parameters** -* const [ControlCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a1645ab20c41161e6c47620b7352eef62)& **callback** - +* const [ControlStatusCallback](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a2ab2120cb3ff6c6a1f726542bd0d8dea)& **callback** - **Returns** - [ControlHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1accab76c321008685a455ccff45811397) - + [ControlStatusHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aade6db709ce87cb0ec5536ae243cb50d) - -### unsubscribe_control() {#classmavsdk_1_1_gimbal_1a899b442fafac1d83b9450bd219f6975e} +### unsubscribe_control_status() {#classmavsdk_1_1_gimbal_1a7314f438bd2b91ba98374cd2a1a2b285} ```cpp -void mavsdk::Gimbal::unsubscribe_control(ControlHandle handle) +void mavsdk::Gimbal::unsubscribe_control_status(ControlStatusHandle handle) ``` -Unsubscribe from subscribe_control. +Unsubscribe from subscribe_control_status. **Parameters** -* [ControlHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1accab76c321008685a455ccff45811397) **handle** - +* [ControlStatusHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aade6db709ce87cb0ec5536ae243cb50d) **handle** - -### control() {#classmavsdk_1_1_gimbal_1aae172788140e37d6125b224f5e79829e} +### get_control_status() {#classmavsdk_1_1_gimbal_1a6c4a10de4ecb79c7116654c1d99236f3} ```cpp -ControlStatus mavsdk::Gimbal::control() const +std::pair< Result, Gimbal::ControlStatus > mavsdk::Gimbal::get_control_status(int32_t gimbal_id) const ``` -Poll for '[ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md)' (blocking). +Get control status for specific gimbal. + +This function is blocking. + +**Parameters** + +* int32_t **gimbal_id** - + +**Returns** + + std::pair< [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac), [Gimbal::ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) > - Result of request. + +### subscribe_attitude() {#classmavsdk_1_1_gimbal_1aa3500df0c7adff3819493dd7d38976a3} +```cpp +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](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a07eafc661a23ee1d55ab0dd86e3c71ed)& **callback** - + +**Returns** + + [AttitudeHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1af7c71cdd8516aec8c9d160977f7c5396) - + +### unsubscribe_attitude() {#classmavsdk_1_1_gimbal_1a11b1e0d91ca5c8ec50afd802d9d2532e} +```cpp +void mavsdk::Gimbal::unsubscribe_attitude(AttitudeHandle handle) +``` + + +Unsubscribe from subscribe_attitude. + + +**Parameters** + +* [AttitudeHandle](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1af7c71cdd8516aec8c9d160977f7c5396) **handle** - + +### get_attitude() {#classmavsdk_1_1_gimbal_1a57c6e6c7297e55f5cc660e40e91b898b} +```cpp +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** - [ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) - One [ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) update. + std::pair< [Result](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1aa732ec0bd49ac03b7910199d635f76ac), [Gimbal::Attitude](structmavsdk_1_1_gimbal_1_1_attitude.md) > - Result of request. -### operator=() {#classmavsdk_1_1_gimbal_1ac9a6e1936f58ce8f957be7c6bcc0d134} +### operator=() {#classmavsdk_1_1_gimbal_1a2d16cfd6fbe82b0e34d35133ab5c9617} ```cpp -const Gimbal& mavsdk::Gimbal::operator=(const Gimbal &)=delete +const Gimbal & mavsdk::Gimbal::operator=(const Gimbal &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_gripper.md b/docs/en/cpp/api_reference/classmavsdk_1_1_gripper.md index 3ab13634e5..ca4aefc36e 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_gripper.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_gripper.md @@ -29,7 +29,7 @@ void | [grab_async](#classmavsdk_1_1_gripper_1a90c5ebf377fa1691a045a3ae70d885fa) [Result](classmavsdk_1_1_gripper.md#classmavsdk_1_1_gripper_1a82c5d2dec9badc2fad436ae56962b534) | [grab](#classmavsdk_1_1_gripper_1abba980736acaf541721c7e23a9f2f8b1) (uint32_t instance)const | [Gripper](classmavsdk_1_1_gripper.md) grab cargo. void | [release_async](#classmavsdk_1_1_gripper_1acb9a3f03a7c67f1a5c066aa2380a5e34) (uint32_t instance, const [ResultCallback](classmavsdk_1_1_gripper.md#classmavsdk_1_1_gripper_1ac8cce161ab7fe573125f4915de0a993f) callback) | [Gripper](classmavsdk_1_1_gripper.md) release cargo. [Result](classmavsdk_1_1_gripper.md#classmavsdk_1_1_gripper_1a82c5d2dec9badc2fad436ae56962b534) | [release](#classmavsdk_1_1_gripper_1a7b0d151d7a596d3977f2da9861204d8c) (uint32_t instance)const | [Gripper](classmavsdk_1_1_gripper.md) release cargo. -const [Gripper](classmavsdk_1_1_gripper.md) & | [operator=](#classmavsdk_1_1_gripper_1a6b26bd1ca3f795dce56b5a14717b9c40) (const [Gripper](classmavsdk_1_1_gripper.md) &)=delete | Equality operator (object is not copyable). +const [Gripper](classmavsdk_1_1_gripper.md) & | [operator=](#classmavsdk_1_1_gripper_1a2823e5efade717a7c7c9f5b330b26c72) (const [Gripper](classmavsdk_1_1_gripper.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -206,9 +206,9 @@ This function is blocking. See 'release_async' for the non-blocking counterpart.  [Result](classmavsdk_1_1_gripper.md#classmavsdk_1_1_gripper_1a82c5d2dec9badc2fad436ae56962b534) - Result of request. -### operator=() {#classmavsdk_1_1_gripper_1a6b26bd1ca3f795dce56b5a14717b9c40} +### operator=() {#classmavsdk_1_1_gripper_1a2823e5efade717a7c7c9f5b330b26c72} ```cpp -const Gripper& mavsdk::Gripper::operator=(const Gripper &)=delete +const Gripper & mavsdk::Gripper::operator=(const Gripper &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_handle.md b/docs/en/cpp/api_reference/classmavsdk_1_1_handle.md index 2bbeef54d6..b24c67f644 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_handle.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_handle.md @@ -14,6 +14,9 @@ Type | Name | Description ---: | --- | ---   | [Handle](#classmavsdk_1_1_handle_1a4dde9be588a605aa7a7fa77cc4ed98f2) ()=default |   | [~Handle](#classmavsdk_1_1_handle_1a986e2ba72802e6cc5bdc5f06f27f6acb) ()=default | +bool | [valid](#classmavsdk_1_1_handle_1a424583fcc5165eb16b167829557c782b) () const | Wheter handle is valid. +bool | [operator<](#classmavsdk_1_1_handle_1ad0a7552f878d8bf20e998821ae2ed82f) (const [Handle](classmavsdk_1_1_handle.md) & other)const | +bool | [operator==](#classmavsdk_1_1_handle_1ad7b7891c68f244a615219fea16808998) (const [Handle](classmavsdk_1_1_handle.md) & other)const | ## Constructor & Destructor Documentation @@ -30,3 +33,47 @@ mavsdk::Handle< Args >::Handle()=default mavsdk::Handle< Args >::~Handle()=default ``` + +## Member Function Documentation + + +### valid() {#classmavsdk_1_1_handle_1a424583fcc5165eb16b167829557c782b} +```cpp +bool mavsdk::Handle< Args >::valid() const +``` + + +Wheter handle is valid. + + +**Returns** + + bool - true if handle is valid + +### operator<() {#classmavsdk_1_1_handle_1ad0a7552f878d8bf20e998821ae2ed82f} +```cpp +bool mavsdk::Handle< Args >::operator<(const Handle &other) const +``` + + +**Parameters** + +* const [Handle](classmavsdk_1_1_handle.md)& **other** - + +**Returns** + + bool - + +### operator==() {#classmavsdk_1_1_handle_1ad7b7891c68f244a615219fea16808998} +```cpp +bool mavsdk::Handle< Args >::operator==(const Handle &other) const +``` + + +**Parameters** + +* const [Handle](classmavsdk_1_1_handle.md)& **other** - + +**Returns** + + bool - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_handle_factory.md b/docs/en/cpp/api_reference/classmavsdk_1_1_handle_factory.md new file mode 100644 index 0000000000..8321bde3ae --- /dev/null +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_handle_factory.md @@ -0,0 +1,5 @@ +# mavsdk::HandleFactory Class Reference +`#include: UNKNOWN` + +---- + diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_info.md b/docs/en/cpp/api_reference/classmavsdk_1_1_info.md index 379a143137..ce32ae1024 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_info.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_info.md @@ -25,6 +25,8 @@ Type | Description --- | --- enum [Result](#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a) | Possible results returned for info requests. std::function< void([Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a))> [ResultCallback](#classmavsdk_1_1_info_1a649bf4a0936dea3168d40eb9b9dcdd57) | Callback type for asynchronous [Info](classmavsdk_1_1_info.md) calls. +std::function< void([FlightInfo](structmavsdk_1_1_info_1_1_flight_info.md))> [FlightInformationCallback](#classmavsdk_1_1_info_1a73d05cffe26df98cdf8ba1eaa032476f) | Callback type for subscribe_flight_information. +[Handle](classmavsdk_1_1_handle.md)< [FlightInfo](structmavsdk_1_1_info_1_1_flight_info.md) > [FlightInformationHandle](#classmavsdk_1_1_info_1aa3be384db51ec318510ae19650762efe) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_flight_information. ## Public Member Functions @@ -35,12 +37,14 @@ Type | Name | Description   | [Info](#classmavsdk_1_1_info_1ae67e006f16f1e1aa12efe94120ef83ec) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md).   | [~Info](#classmavsdk_1_1_info_1abbf48bc4b9aa5b9fdbdb54ec3e398f65) () override | Destructor (internal use only).   | [Info](#classmavsdk_1_1_info_1a0f6e0851757046c540fe7ce920eb3fa2) (const [Info](classmavsdk_1_1_info.md) & other) | Copy constructor. -std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::FlightInfo](structmavsdk_1_1_info_1_1_flight_info.md) > | [get_flight_information](#classmavsdk_1_1_info_1a915e0833d8c3c61fed9b9ad687caef77) () const | Get flight information of the system. -std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Identification](structmavsdk_1_1_info_1_1_identification.md) > | [get_identification](#classmavsdk_1_1_info_1a812ed66265b7427bc781faec3f0fa89e) () const | Get the identification of the system. -std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Product](structmavsdk_1_1_info_1_1_product.md) > | [get_product](#classmavsdk_1_1_info_1ae60d71a6dcd7546d1bdc06a9c26e629f) () const | Get product information of the system. -std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Version](structmavsdk_1_1_info_1_1_version.md) > | [get_version](#classmavsdk_1_1_info_1a2403b975a73b2b52a455b96cdc899af3) () const | Get the version information of the system. -std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), double > | [get_speed_factor](#classmavsdk_1_1_info_1a3b372b3f6e4b167cb272ae68d3d172c6) () const | Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). -const [Info](classmavsdk_1_1_info.md) & | [operator=](#classmavsdk_1_1_info_1a586eb91fd65d602bad1d016dca42b435) (const [Info](classmavsdk_1_1_info.md) &)=delete | Equality operator (object is not copyable). +std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::FlightInfo](structmavsdk_1_1_info_1_1_flight_info.md) > | [get_flight_information](#classmavsdk_1_1_info_1a5ae8681909c3298b2df5c0722a30aa3c) () const | Get flight information of the system. +std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Identification](structmavsdk_1_1_info_1_1_identification.md) > | [get_identification](#classmavsdk_1_1_info_1a76739913366e334a4638aa187d7c40d4) () const | Get the identification of the system. +std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Product](structmavsdk_1_1_info_1_1_product.md) > | [get_product](#classmavsdk_1_1_info_1a508cf835acaed0fad69badda62206fed) () const | Get product information of the system. +std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Version](structmavsdk_1_1_info_1_1_version.md) > | [get_version](#classmavsdk_1_1_info_1a2ad33d89a7dd64192641bba03816a9f9) () const | Get the version information of the system. +std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), double > | [get_speed_factor](#classmavsdk_1_1_info_1a3cfeae67032ac870b8b97aa352cc50dc) () const | Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). +[FlightInformationHandle](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1aa3be384db51ec318510ae19650762efe) | [subscribe_flight_information](#classmavsdk_1_1_info_1adba1c5a12a7c144c1cc9af73b396aa39) (const [FlightInformationCallback](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1a73d05cffe26df98cdf8ba1eaa032476f) & callback) | Subscribe to 'flight information' updates. +void | [unsubscribe_flight_information](#classmavsdk_1_1_info_1a260ab1d6f2cf035fe8499ff52b915bd2) ([FlightInformationHandle](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1aa3be384db51ec318510ae19650762efe) handle) | Unsubscribe from subscribe_flight_information. +const [Info](classmavsdk_1_1_info.md) & | [operator=](#classmavsdk_1_1_info_1a64647fcd6c1d71ab5fd78e987ecb3ffa) (const [Info](classmavsdk_1_1_info.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -117,6 +121,26 @@ using mavsdk::Info::ResultCallback = std::function Callback type for asynchronous [Info](classmavsdk_1_1_info.md) calls. +### typedef FlightInformationCallback {#classmavsdk_1_1_info_1a73d05cffe26df98cdf8ba1eaa032476f} + +```cpp +using mavsdk::Info::FlightInformationCallback = std::function +``` + + +Callback type for subscribe_flight_information. + + +### typedef FlightInformationHandle {#classmavsdk_1_1_info_1aa3be384db51ec318510ae19650762efe} + +```cpp +using mavsdk::Info::FlightInformationHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_flight_information. + + ## Member Enumeration Documentation @@ -136,9 +160,9 @@ Value | Description ## Member Function Documentation -### get_flight_information() {#classmavsdk_1_1_info_1a915e0833d8c3c61fed9b9ad687caef77} +### get_flight_information() {#classmavsdk_1_1_info_1a5ae8681909c3298b2df5c0722a30aa3c} ```cpp -std::pair mavsdk::Info::get_flight_information() const +std::pair< Result, Info::FlightInfo > mavsdk::Info::get_flight_information() const ``` @@ -150,9 +174,9 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::FlightInfo](structmavsdk_1_1_info_1_1_flight_info.md) > - Result of request. -### get_identification() {#classmavsdk_1_1_info_1a812ed66265b7427bc781faec3f0fa89e} +### get_identification() {#classmavsdk_1_1_info_1a76739913366e334a4638aa187d7c40d4} ```cpp -std::pair mavsdk::Info::get_identification() const +std::pair< Result, Info::Identification > mavsdk::Info::get_identification() const ``` @@ -164,9 +188,9 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Identification](structmavsdk_1_1_info_1_1_identification.md) > - Result of request. -### get_product() {#classmavsdk_1_1_info_1ae60d71a6dcd7546d1bdc06a9c26e629f} +### get_product() {#classmavsdk_1_1_info_1a508cf835acaed0fad69badda62206fed} ```cpp -std::pair mavsdk::Info::get_product() const +std::pair< Result, Info::Product > mavsdk::Info::get_product() const ``` @@ -178,9 +202,9 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Product](structmavsdk_1_1_info_1_1_product.md) > - Result of request. -### get_version() {#classmavsdk_1_1_info_1a2403b975a73b2b52a455b96cdc899af3} +### get_version() {#classmavsdk_1_1_info_1a2ad33d89a7dd64192641bba03816a9f9} ```cpp -std::pair mavsdk::Info::get_version() const +std::pair< Result, Info::Version > mavsdk::Info::get_version() const ``` @@ -192,9 +216,9 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), [Info::Version](structmavsdk_1_1_info_1_1_version.md) > - Result of request. -### get_speed_factor() {#classmavsdk_1_1_info_1a3b372b3f6e4b167cb272ae68d3d172c6} +### get_speed_factor() {#classmavsdk_1_1_info_1a3cfeae67032ac870b8b97aa352cc50dc} ```cpp -std::pair mavsdk::Info::get_speed_factor() const +std::pair< Result, double > mavsdk::Info::get_speed_factor() const ``` @@ -206,9 +230,39 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1ab1798ed39271915800b25aaa05d1d45a), double > - Result of request. -### operator=() {#classmavsdk_1_1_info_1a586eb91fd65d602bad1d016dca42b435} +### subscribe_flight_information() {#classmavsdk_1_1_info_1adba1c5a12a7c144c1cc9af73b396aa39} +```cpp +FlightInformationHandle mavsdk::Info::subscribe_flight_information(const FlightInformationCallback &callback) +``` + + +Subscribe to 'flight information' updates. + + +**Parameters** + +* const [FlightInformationCallback](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1a73d05cffe26df98cdf8ba1eaa032476f)& **callback** - + +**Returns** + + [FlightInformationHandle](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1aa3be384db51ec318510ae19650762efe) - + +### unsubscribe_flight_information() {#classmavsdk_1_1_info_1a260ab1d6f2cf035fe8499ff52b915bd2} +```cpp +void mavsdk::Info::unsubscribe_flight_information(FlightInformationHandle handle) +``` + + +Unsubscribe from subscribe_flight_information. + + +**Parameters** + +* [FlightInformationHandle](classmavsdk_1_1_info.md#classmavsdk_1_1_info_1aa3be384db51ec318510ae19650762efe) **handle** - + +### operator=() {#classmavsdk_1_1_info_1a64647fcd6c1d71ab5fd78e987ecb3ffa} ```cpp -const Info& mavsdk::Info::operator=(const Info &)=delete +const Info & mavsdk::Info::operator=(const Info &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_log_files.md b/docs/en/cpp/api_reference/classmavsdk_1_1_log_files.md index 605e002738..348bb25418 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_log_files.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_log_files.md @@ -34,10 +34,10 @@ Type | Name | Description   | [~LogFiles](#classmavsdk_1_1_log_files_1a313ea62b9c45927c4140fb784578a5b9) () override | Destructor (internal use only).   | [LogFiles](#classmavsdk_1_1_log_files_1ae09021cd080dc45f63019ea76968801f) (const [LogFiles](classmavsdk_1_1_log_files.md) & other) | Copy constructor. void | [get_entries_async](#classmavsdk_1_1_log_files_1a6a922097850fb43fbb9d3348fe0b3bb7) (const [GetEntriesCallback](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1a0bb101777daba9e87cb33baf55389403) callback) | Get List of log files. -std::pair< [Result](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1a43e5425f17cd8a6830ff6fd952a724cd), std::vector< [LogFiles::Entry](structmavsdk_1_1_log_files_1_1_entry.md) > > | [get_entries](#classmavsdk_1_1_log_files_1ab06a17009589c57aa90ac31a24aa9064) () const | Get List of log files. +std::pair< [Result](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1a43e5425f17cd8a6830ff6fd952a724cd), std::vector< [LogFiles::Entry](structmavsdk_1_1_log_files_1_1_entry.md) > > | [get_entries](#classmavsdk_1_1_log_files_1a89164b17ff0a521b7ad67f3ef69b445c) () const | Get List of log files. void | [download_log_file_async](#classmavsdk_1_1_log_files_1a2d5eca47cfa3de13a317915cd261d642) ([Entry](structmavsdk_1_1_log_files_1_1_entry.md) entry, std::string path, const [DownloadLogFileCallback](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1af62400ee1e20bfbe948e1ec98255d236) & callback) | Download log file. [Result](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1a43e5425f17cd8a6830ff6fd952a724cd) | [erase_all_log_files](#classmavsdk_1_1_log_files_1a31cc0db36046c8211763a829b8f62414) () const | Erase all log files. -const [LogFiles](classmavsdk_1_1_log_files.md) & | [operator=](#classmavsdk_1_1_log_files_1a2ba9f188f7644a647f5dcdadb034e300) (const [LogFiles](classmavsdk_1_1_log_files.md) &)=delete | Equality operator (object is not copyable). +const [LogFiles](classmavsdk_1_1_log_files.md) & | [operator=](#classmavsdk_1_1_log_files_1a2122270cf236099a445e3b4fc31573aa) (const [LogFiles](classmavsdk_1_1_log_files.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -171,9 +171,9 @@ This function is non-blocking. See 'get_entries' for the blocking counterpart. * const [GetEntriesCallback](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1a0bb101777daba9e87cb33baf55389403) **callback** - -### get_entries() {#classmavsdk_1_1_log_files_1ab06a17009589c57aa90ac31a24aa9064} +### get_entries() {#classmavsdk_1_1_log_files_1a89164b17ff0a521b7ad67f3ef69b445c} ```cpp -std::pair > mavsdk::LogFiles::get_entries() const +std::pair< Result, std::vector< LogFiles::Entry > > mavsdk::LogFiles::get_entries() const ``` @@ -214,9 +214,9 @@ This function is blocking.  [Result](classmavsdk_1_1_log_files.md#classmavsdk_1_1_log_files_1a43e5425f17cd8a6830ff6fd952a724cd) - Result of request. -### operator=() {#classmavsdk_1_1_log_files_1a2ba9f188f7644a647f5dcdadb034e300} +### operator=() {#classmavsdk_1_1_log_files_1a2122270cf236099a445e3b4fc31573aa} ```cpp -const LogFiles& mavsdk::LogFiles::operator=(const LogFiles &)=delete +const LogFiles & mavsdk::LogFiles::operator=(const LogFiles &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_log_streaming.md b/docs/en/cpp/api_reference/classmavsdk_1_1_log_streaming.md new file mode 100644 index 0000000000..1775a28231 --- /dev/null +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_log_streaming.md @@ -0,0 +1,261 @@ +# mavsdk::LogStreaming Class Reference +`#include: log_streaming.h` + +---- + + +Provide log streaming data. + + +## Data Structures + + +struct [LogStreamingRaw](structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md) + +## Public Types + + +Type | Description +--- | --- +enum [Result](#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17) | Possible results returned for logging requests. +std::function< void([Result](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17))> [ResultCallback](#classmavsdk_1_1_log_streaming_1af5383eb2fda579379ab3c722d074f818) | Callback type for asynchronous [LogStreaming](classmavsdk_1_1_log_streaming.md) calls. +std::function< void([LogStreamingRaw](structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md))> [LogStreamingRawCallback](#classmavsdk_1_1_log_streaming_1af3197cf6a041f85c6ea879dcccbc354a) | Callback type for subscribe_log_streaming_raw. +[Handle](classmavsdk_1_1_handle.md)< [LogStreamingRaw](structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md) > [LogStreamingRawHandle](#classmavsdk_1_1_log_streaming_1af245af3fad21ca1198987babbd728925) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_log_streaming_raw. + +## Public Member Functions + + +Type | Name | Description +---: | --- | --- +  | [LogStreaming](#classmavsdk_1_1_log_streaming_1a16a64f4ea20ba98b5151b588fb84f5ee) ([System](classmavsdk_1_1_system.md) & system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). +  | [LogStreaming](#classmavsdk_1_1_log_streaming_1a8be3bbd9068f03c390fc78dd426058b4) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). +  | [~LogStreaming](#classmavsdk_1_1_log_streaming_1a2b99fc2e1f535afb8f107430d1fb1926) () override | Destructor (internal use only). +  | [LogStreaming](#classmavsdk_1_1_log_streaming_1a2e2dddc59ab55af1cf57479dc73c9842) (const [LogStreaming](classmavsdk_1_1_log_streaming.md) & other) | Copy constructor. +void | [start_log_streaming_async](#classmavsdk_1_1_log_streaming_1a00797f79a2d17db031be24184ca326ea) (const [ResultCallback](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af5383eb2fda579379ab3c722d074f818) callback) | Start streaming logging data. +[Result](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17) | [start_log_streaming](#classmavsdk_1_1_log_streaming_1aad5edb63b5b66bc9b4189c298ab5f957) () const | Start streaming logging data. +void | [stop_log_streaming_async](#classmavsdk_1_1_log_streaming_1a6d4db2bb2a2c869fcbc11d6c2124f02c) (const [ResultCallback](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af5383eb2fda579379ab3c722d074f818) callback) | Stop streaming logging data. +[Result](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17) | [stop_log_streaming](#classmavsdk_1_1_log_streaming_1a656b17357693c83e579104c5fd3281d8) () const | Stop streaming logging data. +[LogStreamingRawHandle](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af245af3fad21ca1198987babbd728925) | [subscribe_log_streaming_raw](#classmavsdk_1_1_log_streaming_1afeef206b7843bdd3d1a85806764b2110) (const [LogStreamingRawCallback](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af3197cf6a041f85c6ea879dcccbc354a) & callback) | Subscribe to logging messages. +void | [unsubscribe_log_streaming_raw](#classmavsdk_1_1_log_streaming_1a31b33a0318907668f6939cea52f02d5b) ([LogStreamingRawHandle](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af245af3fad21ca1198987babbd728925) handle) | Unsubscribe from subscribe_log_streaming_raw. +const [LogStreaming](classmavsdk_1_1_log_streaming.md) & | [operator=](#classmavsdk_1_1_log_streaming_1a51a20fe975a0cde08e077fe89d9b3a99) (const [LogStreaming](classmavsdk_1_1_log_streaming.md) &)=delete | Equality operator (object is not copyable). + + +## Constructor & Destructor Documentation + + +### LogStreaming() {#classmavsdk_1_1_log_streaming_1a16a64f4ea20ba98b5151b588fb84f5ee} +```cpp +mavsdk::LogStreaming::LogStreaming(System &system) +``` + + +Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). + +The plugin is typically created as shown below: + +```cpp +auto log_streaming = LogStreaming(system); +``` + +**Parameters** + +* [System](classmavsdk_1_1_system.md)& **system** - The specific system associated with this plugin. + +### LogStreaming() {#classmavsdk_1_1_log_streaming_1a8be3bbd9068f03c390fc78dd426058b4} +```cpp +mavsdk::LogStreaming::LogStreaming(std::shared_ptr< System > system) +``` + + +Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md). + +The plugin is typically created as shown below: + +```cpp +auto log_streaming = LogStreaming(system); +``` + +**Parameters** + +* std::shared_ptr< [System](classmavsdk_1_1_system.md) > **system** - The specific system associated with this plugin. + +### ~LogStreaming() {#classmavsdk_1_1_log_streaming_1a2b99fc2e1f535afb8f107430d1fb1926} +```cpp +mavsdk::LogStreaming::~LogStreaming() override +``` + + +Destructor (internal use only). + + +### LogStreaming() {#classmavsdk_1_1_log_streaming_1a2e2dddc59ab55af1cf57479dc73c9842} +```cpp +mavsdk::LogStreaming::LogStreaming(const LogStreaming &other) +``` + + +Copy constructor. + + +**Parameters** + +* const [LogStreaming](classmavsdk_1_1_log_streaming.md)& **other** - + +## Member Typdef Documentation + + +### typedef ResultCallback {#classmavsdk_1_1_log_streaming_1af5383eb2fda579379ab3c722d074f818} + +```cpp +using mavsdk::LogStreaming::ResultCallback = std::function +``` + + +Callback type for asynchronous [LogStreaming](classmavsdk_1_1_log_streaming.md) calls. + + +### typedef LogStreamingRawCallback {#classmavsdk_1_1_log_streaming_1af3197cf6a041f85c6ea879dcccbc354a} + +```cpp +using mavsdk::LogStreaming::LogStreamingRawCallback = std::function +``` + + +Callback type for subscribe_log_streaming_raw. + + +### typedef LogStreamingRawHandle {#classmavsdk_1_1_log_streaming_1af245af3fad21ca1198987babbd728925} + +```cpp +using mavsdk::LogStreaming::LogStreamingRawHandle = Handle +``` + + +[Handle](classmavsdk_1_1_handle.md) type for subscribe_log_streaming_raw. + + +## Member Enumeration Documentation + + +### enum Result {#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17} + + +Possible results returned for logging requests. + + +Value | Description +--- | --- + `Success` | Request succeeded. + `NoSystem` | No system connected. + `ConnectionError` | Connection error. + `Busy` | [System](classmavsdk_1_1_system.md) busy. + `CommandDenied` | Command denied. + `Timeout` | Timeout. + `Unsupported` | Unsupported. + `Unknown` | Unknown error. + +## Member Function Documentation + + +### start_log_streaming_async() {#classmavsdk_1_1_log_streaming_1a00797f79a2d17db031be24184ca326ea} +```cpp +void mavsdk::LogStreaming::start_log_streaming_async(const ResultCallback callback) +``` + + +Start streaming logging data. + +This function is non-blocking. See 'start_log_streaming' for the blocking counterpart. + +**Parameters** + +* const [ResultCallback](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af5383eb2fda579379ab3c722d074f818) **callback** - + +### start_log_streaming() {#classmavsdk_1_1_log_streaming_1aad5edb63b5b66bc9b4189c298ab5f957} +```cpp +Result mavsdk::LogStreaming::start_log_streaming() const +``` + + +Start streaming logging data. + +This function is blocking. See 'start_log_streaming_async' for the non-blocking counterpart. + +**Returns** + + [Result](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17) - Result of request. + +### stop_log_streaming_async() {#classmavsdk_1_1_log_streaming_1a6d4db2bb2a2c869fcbc11d6c2124f02c} +```cpp +void mavsdk::LogStreaming::stop_log_streaming_async(const ResultCallback callback) +``` + + +Stop streaming logging data. + +This function is non-blocking. See 'stop_log_streaming' for the blocking counterpart. + +**Parameters** + +* const [ResultCallback](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af5383eb2fda579379ab3c722d074f818) **callback** - + +### stop_log_streaming() {#classmavsdk_1_1_log_streaming_1a656b17357693c83e579104c5fd3281d8} +```cpp +Result mavsdk::LogStreaming::stop_log_streaming() const +``` + + +Stop streaming logging data. + +This function is blocking. See 'stop_log_streaming_async' for the non-blocking counterpart. + +**Returns** + + [Result](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1a29f3219817d4aefebf1a0d59cda39c17) - Result of request. + +### subscribe_log_streaming_raw() {#classmavsdk_1_1_log_streaming_1afeef206b7843bdd3d1a85806764b2110} +```cpp +LogStreamingRawHandle mavsdk::LogStreaming::subscribe_log_streaming_raw(const LogStreamingRawCallback &callback) +``` + + +Subscribe to logging messages. + + +**Parameters** + +* const [LogStreamingRawCallback](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af3197cf6a041f85c6ea879dcccbc354a)& **callback** - + +**Returns** + + [LogStreamingRawHandle](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af245af3fad21ca1198987babbd728925) - + +### unsubscribe_log_streaming_raw() {#classmavsdk_1_1_log_streaming_1a31b33a0318907668f6939cea52f02d5b} +```cpp +void mavsdk::LogStreaming::unsubscribe_log_streaming_raw(LogStreamingRawHandle handle) +``` + + +Unsubscribe from subscribe_log_streaming_raw. + + +**Parameters** + +* [LogStreamingRawHandle](classmavsdk_1_1_log_streaming.md#classmavsdk_1_1_log_streaming_1af245af3fad21ca1198987babbd728925) **handle** - + +### operator=() {#classmavsdk_1_1_log_streaming_1a51a20fe975a0cde08e077fe89d9b3a99} +```cpp +const LogStreaming & mavsdk::LogStreaming::operator=(const LogStreaming &)=delete +``` + + +Equality operator (object is not copyable). + + +**Parameters** + +* const [LogStreaming](classmavsdk_1_1_log_streaming.md)& - + +**Returns** + + const [LogStreaming](classmavsdk_1_1_log_streaming.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_manual_control.md b/docs/en/cpp/api_reference/classmavsdk_1_1_manual_control.md index aa0bda5f4e..5f60b18f4a 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_manual_control.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_manual_control.md @@ -29,7 +29,7 @@ void | [start_position_control_async](#classmavsdk_1_1_manual_control_1a2a3352c1 void | [start_altitude_control_async](#classmavsdk_1_1_manual_control_1abf7659d98949c01b634e421a9c2df079) (const [ResultCallback](classmavsdk_1_1_manual_control.md#classmavsdk_1_1_manual_control_1a08b010bafdf770d3e4ea6060f56a0f3b) callback) | Start altitude control. [Result](classmavsdk_1_1_manual_control.md#classmavsdk_1_1_manual_control_1a6c7dbd25e051b6e1369a65fd05a22799) | [start_altitude_control](#classmavsdk_1_1_manual_control_1a67609e46bafb34309d5b5d943a29f23c) () const | Start altitude control. [Result](classmavsdk_1_1_manual_control.md#classmavsdk_1_1_manual_control_1a6c7dbd25e051b6e1369a65fd05a22799) | [set_manual_control_input](#classmavsdk_1_1_manual_control_1a1b4b34db391d7238e33b821614fc1f29) (float x, float y, float z, float r)const | Set manual control input. -const [ManualControl](classmavsdk_1_1_manual_control.md) & | [operator=](#classmavsdk_1_1_manual_control_1aca51fff98c33fbd5201495101ddf1368) (const [ManualControl](classmavsdk_1_1_manual_control.md) &)=delete | Equality operator (object is not copyable). +const [ManualControl](classmavsdk_1_1_manual_control.md) & | [operator=](#classmavsdk_1_1_manual_control_1a4cc95d340ce5a6a4eb2309c67302fdb9) (const [ManualControl](classmavsdk_1_1_manual_control.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -222,9 +222,9 @@ This function is blocking.  [Result](classmavsdk_1_1_manual_control.md#classmavsdk_1_1_manual_control_1a6c7dbd25e051b6e1369a65fd05a22799) - Result of request. -### operator=() {#classmavsdk_1_1_manual_control_1aca51fff98c33fbd5201495101ddf1368} +### operator=() {#classmavsdk_1_1_manual_control_1a4cc95d340ce5a6a4eb2309c67302fdb9} ```cpp -const ManualControl& mavsdk::ManualControl::operator=(const ManualControl &)=delete +const ManualControl & mavsdk::ManualControl::operator=(const ManualControl &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mavlink_passthrough.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mavlink_passthrough.md index 405e5c00e3..41576ad332 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mavlink_passthrough.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mavlink_passthrough.md @@ -40,15 +40,15 @@ DEPRECATED [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavli [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793) | [send_command_long](#classmavsdk_1_1_mavlink_passthrough_1a7e258aa16b92195e5329e861fb18f8e9) (const [CommandLong](structmavsdk_1_1_mavlink_passthrough_1_1_command_long.md) & command) | Send a MAVLink command_long. [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793) | [send_command_int](#classmavsdk_1_1_mavlink_passthrough_1a654d67a3b136509c76e2ac804a656ada) (const [CommandInt](structmavsdk_1_1_mavlink_passthrough_1_1_command_int.md) & command) | Send a MAVLink command_long. mavlink_message_t | [make_command_ack_message](#classmavsdk_1_1_mavlink_passthrough_1aa08cb5d2f9aed795367cf7e05d58bdcc) (const uint8_t target_sysid, const uint8_t target_compid, const uint16_t command, MAV_RESULT result) | Create a command_ack. -std::pair< [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793), int32_t > | [get_param_int](#classmavsdk_1_1_mavlink_passthrough_1a19887d34580a7f1f9ef4bbea6cd3441b) (const std::string & name, std::optional< uint8_t > maybe_component_id, bool extended) | Request param (int). -std::pair< [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793), float > | [get_param_float](#classmavsdk_1_1_mavlink_passthrough_1aa91c943be90e319d01b75d2cd0aa39ab) (const std::string & name, std::optional< uint8_t > maybe_component_id, bool extended) | Request param (float). +std::pair< [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793), int32_t > | [get_param_int](#classmavsdk_1_1_mavlink_passthrough_1ad692f8b619f317151831bc53b4f6c168) (const std::string & name, std::optional< uint8_t > maybe_component_id, bool extended) | Request param (int). +std::pair< [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793), float > | [get_param_float](#classmavsdk_1_1_mavlink_passthrough_1a347f3921a786865c7bb62817b706c359) (const std::string & name, std::optional< uint8_t > maybe_component_id, bool extended) | Request param (float). [MessageHandle](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a2e283239c4429eaeb33deb5821833066) | [subscribe_message](#classmavsdk_1_1_mavlink_passthrough_1ae2ab2426bc0d844e931c266aa26c3607) (uint16_t message_id, const [MessageCallback](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a97f94c54e84fcce94d922fd7f4e3d231) & callback) | Subscribe to messages using message ID. void | [unsubscribe_message](#classmavsdk_1_1_mavlink_passthrough_1af4e722ae613e799b60020c30193656be) (uint16_t message_id, [MessageHandle](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a2e283239c4429eaeb33deb5821833066) handle) | Unsubscribe from subscribe_message. uint8_t | [get_our_sysid](#classmavsdk_1_1_mavlink_passthrough_1a985b269c1b78ec3e4e9d9468e46e19be) () const | Get our own system ID. uint8_t | [get_our_compid](#classmavsdk_1_1_mavlink_passthrough_1a85ddd016ab35d5f3f487b1362723d3cf) () const | Get our own component ID. uint8_t | [get_target_sysid](#classmavsdk_1_1_mavlink_passthrough_1a2867d1f37649d62e757bbac0a73b3ebd) () const | Get system ID of target. uint8_t | [get_target_compid](#classmavsdk_1_1_mavlink_passthrough_1a22ecab3905237a2f227f77bbab9afd17) () const | Get target component ID. -const [MavlinkPassthrough](classmavsdk_1_1_mavlink_passthrough.md) & | [operator=](#classmavsdk_1_1_mavlink_passthrough_1aa7f49a131a8facf4d05449ec03ce3643) (const [MavlinkPassthrough](classmavsdk_1_1_mavlink_passthrough.md) &)=delete | Equality operator (object is not copyable). +const [MavlinkPassthrough](classmavsdk_1_1_mavlink_passthrough.md) & | [operator=](#classmavsdk_1_1_mavlink_passthrough_1a39b74b37094511cc5bc910a2233d024e) (const [MavlinkPassthrough](classmavsdk_1_1_mavlink_passthrough.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -173,7 +173,9 @@ DEPRECATED Result mavsdk::MavlinkPassthrough::send_message(mavlink_message_t &me Send message (deprecated). -> **Note** This interface is deprecated. Instead the method [queue_message()](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1aa95592bc4da7d56d444b8b5cb5bce814) should be used. +::: info +This interface is deprecated. Instead the method [queue_message()](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1aa95592bc4da7d56d444b8b5cb5bce814) should be used. +::: **Parameters** @@ -191,7 +193,9 @@ Result mavsdk::MavlinkPassthrough::queue_message(std::function< mavlink_message_ Send message by queueing it. -> **Note** This interface replaces the previous send_message method. +::: info +This interface replaces the previous send_message method. +::: The interface changed in order to prevent accessing the internal MAVLink status from different threads and to make sure the seq numbers are not unique to[Mavsdk](classmavsdk_1_1_mavsdk.md) instances and server components. @@ -257,9 +261,9 @@ Create a command_ack.  mavlink_message_t - message to send. -### get_param_int() {#classmavsdk_1_1_mavlink_passthrough_1a19887d34580a7f1f9ef4bbea6cd3441b} +### get_param_int() {#classmavsdk_1_1_mavlink_passthrough_1ad692f8b619f317151831bc53b4f6c168} ```cpp -std::pair mavsdk::MavlinkPassthrough::get_param_int(const std::string &name, std::optional< uint8_t > maybe_component_id, bool extended) +std::pair< Result, int32_t > mavsdk::MavlinkPassthrough::get_param_int(const std::string &name, std::optional< uint8_t > maybe_component_id, bool extended) ``` @@ -276,9 +280,9 @@ Request param (int).  std::pair< [Result](classmavsdk_1_1_mavlink_passthrough.md#classmavsdk_1_1_mavlink_passthrough_1a265eacaeea064a31de3fe16d1e357793), int32_t > - -### get_param_float() {#classmavsdk_1_1_mavlink_passthrough_1aa91c943be90e319d01b75d2cd0aa39ab} +### get_param_float() {#classmavsdk_1_1_mavlink_passthrough_1a347f3921a786865c7bb62817b706c359} ```cpp -std::pair mavsdk::MavlinkPassthrough::get_param_float(const std::string &name, std::optional< uint8_t > maybe_component_id, bool extended) +std::pair< Result, float > mavsdk::MavlinkPassthrough::get_param_float(const std::string &name, std::optional< uint8_t > maybe_component_id, bool extended) ``` @@ -381,9 +385,9 @@ This defaults to the component ID of the autopilot (1) if available and otherwis  uint8_t - component ID of target. -### operator=() {#classmavsdk_1_1_mavlink_passthrough_1aa7f49a131a8facf4d05449ec03ce3643} +### operator=() {#classmavsdk_1_1_mavlink_passthrough_1a39b74b37094511cc5bc910a2233d024e} ```cpp -const MavlinkPassthrough& mavsdk::MavlinkPassthrough::operator=(const MavlinkPassthrough &)=delete +const MavlinkPassthrough & mavsdk::MavlinkPassthrough::operator=(const MavlinkPassthrough &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk.md index 0381ee2055..19db0f9b04 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk.md @@ -10,7 +10,7 @@ This is the main class of MAVSDK (a MAVLink API Library). It is used to discover vehicles and manage active connections. -An instance of this class must be created (first) in order to use the library. The instance must be destroyed after use in order to break connections and release all resources. +An instance of this class must be created and kept alive in order to use the library. The instance can be destroyed after use in order to break connections and release all resources. ## Data Structures @@ -18,13 +18,16 @@ An instance of this class must be created (first) in order to use the library. T struct [Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) +struct [ConnectionError](structmavsdk_1_1_mavsdk_1_1_connection_error.md) + ## Public Types Type | Description --- | --- -enum [ComponentType](#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) | ComponentType of configurations, used for automatic ID setting. [Handle](classmavsdk_1_1_handle.md)<> [ConnectionHandle](#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) | [Handle](classmavsdk_1_1_handle.md) type to remove a connection. +std::function< void([ConnectionError](structmavsdk_1_1_mavsdk_1_1_connection_error.md))> [ConnectionErrorCallback](#classmavsdk_1_1_mavsdk_1ac71d182538bee6fb3ab007edafac5d5f) | +[Handle](classmavsdk_1_1_handle.md)< [ConnectionError](structmavsdk_1_1_mavsdk_1_1_connection_error.md) > [ConnectionErrorHandle](#classmavsdk_1_1_mavsdk_1aeb442a462d03662e4c152509fd0c203b) | [Handle](classmavsdk_1_1_handle.md) type to remove a connection error subscription. std::function< void()> [NewSystemCallback](#classmavsdk_1_1_mavsdk_1a7a283c6a75e852a56be4c5862f8a3fab) | Callback type discover and timeout notifications. [Handle](classmavsdk_1_1_handle.md)<> [NewSystemHandle](#classmavsdk_1_1_mavsdk_1ae0727f2bed9cbf276d161ada0a432b8c) | [Handle](classmavsdk_1_1_handle.md) type to unsubscribe from subscribe_on_new_system. @@ -38,46 +41,22 @@ Type | Name | Description   | [~Mavsdk](#classmavsdk_1_1_mavsdk_1ac1549f715d6857711b9b9e364a4ca351) () | Destructor. std::string | [version](#classmavsdk_1_1_mavsdk_1a8fdb97695762d06fd2bccfc6309943fa) () const | Returns the version of MAVSDK. [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | [add_any_connection](#classmavsdk_1_1_mavsdk_1a405041a5043c610c86540de090626d97) (const std::string & connection_url, [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds Connection via URL. -std::pair< [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992), [ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) > | [add_any_connection_with_handle](#classmavsdk_1_1_mavsdk_1ad1dc8afaafea8f7e900c990552e6fdfb) (const std::string & connection_url, [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds Connection via URL Additionally returns a handle to remove the connection later. -[ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | [add_udp_connection](#classmavsdk_1_1_mavsdk_1aa43dfb00d5118d26ae5aabd0f9ba56b2) (int local_port=[DEFAULT_UDP_PORT](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1affddcc7c7849ed86a0c7dab1166e657a), [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds a UDP connection to the specified port number. -[ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | [add_udp_connection](#classmavsdk_1_1_mavsdk_1a98fd1c01bd366b27084810875a1b94c1) (const std::string & local_ip, int local_port=[DEFAULT_UDP_PORT](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1affddcc7c7849ed86a0c7dab1166e657a), [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds a UDP connection to the specified port number and local interface. -[ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | [setup_udp_remote](#classmavsdk_1_1_mavsdk_1adb2a69282a5d3766fd6251662c28616d) (const std::string & remote_ip, int remote_port, [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Sets up instance to send heartbeats to the specified remote interface and port number. -[ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | [add_tcp_connection](#classmavsdk_1_1_mavsdk_1a50ecebb9ee710b9a044d2d5eb57645e4) (const std::string & remote_ip, int remote_port=[DEFAULT_TCP_REMOTE_PORT](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a52a6a9e0acd6c0ade566208d253427bd), [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds a TCP connection with a specific IP address and port number. -[ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | [add_serial_connection](#classmavsdk_1_1_mavsdk_1a669ddeec7af571fdbde9f31e343d50ac) (const std::string & dev_path, int baudrate=[DEFAULT_SERIAL_BAUDRATE](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a870d15142914f1db564c12f385d5489b), bool flow_control=false, [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds a serial connection with a specific port (COM or UART dev node) and baudrate as specified. +std::pair< [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992), [ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) > | [add_any_connection_with_handle](#classmavsdk_1_1_mavsdk_1ad12297d30ec1bbe4750f7cf4efbbed57) (const std::string & connection_url, [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) forwarding_option=ForwardingOption::ForwardingOff) | Adds Connection via URL Additionally returns a handle to remove the connection later. void | [remove_connection](#classmavsdk_1_1_mavsdk_1a23cf630bb123aa53b0e99c6bd83ad013) ([ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) handle) | -std::vector< std::shared_ptr< [System](classmavsdk_1_1_system.md) > > | [systems](#classmavsdk_1_1_mavsdk_1a0d0bc4cdab14d96877b52baec5113fa8) () const | Get a vector of systems which have been discovered or set-up. -std::optional< std::shared_ptr< [System](classmavsdk_1_1_system.md) > > | [first_autopilot](#classmavsdk_1_1_mavsdk_1a30b5c588643d19f1cfa9a7be47acb52c) (double timeout_s)const | Get the first autopilot that has been discovered. +[ConnectionErrorHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1aeb442a462d03662e4c152509fd0c203b) | [subscribe_connection_errors](#classmavsdk_1_1_mavsdk_1a8f50fffac65a35857a88da2fd42f9c54) ([ConnectionErrorCallback](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac71d182538bee6fb3ab007edafac5d5f) callback) | +void | [unsubscribe_connection_errors](#classmavsdk_1_1_mavsdk_1a377ec6517ee75981ceb2f26b30e59fbd) ([ConnectionErrorHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1aeb442a462d03662e4c152509fd0c203b) handle) | +std::vector< std::shared_ptr< [System](classmavsdk_1_1_system.md) > > | [systems](#classmavsdk_1_1_mavsdk_1aca9c72b300d384341b00ff9ba2c6e5c5) () const | Get a vector of systems which have been discovered or set-up. +std::optional< std::shared_ptr< [System](classmavsdk_1_1_system.md) > > | [first_autopilot](#classmavsdk_1_1_mavsdk_1aa1bcb865693dbd140478e75ce58699b7) (double timeout_s)const | Get the first autopilot that has been discovered. void | [set_configuration](#classmavsdk_1_1_mavsdk_1acaeea86253493dc15b6540d2100a1b86) ([Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) configuration) | Set [Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) of SDK. void | [set_timeout_s](#classmavsdk_1_1_mavsdk_1a765f37b61462addcfd961e720585d2c6) (double timeout_s) | Set timeout of MAVLink transfers. -void | [set_system_status](#classmavsdk_1_1_mavsdk_1a693eac9fce2e9a330a3b9213ac9faae4) (uint8_t system_status) | Set system status of this MAVLink entity. [NewSystemHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ae0727f2bed9cbf276d161ada0a432b8c) | [subscribe_on_new_system](#classmavsdk_1_1_mavsdk_1a5b7c958ad2e4529dc7b950ab26618575) (const [NewSystemCallback](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a7a283c6a75e852a56be4c5862f8a3fab) & callback) | Get notification about a change in systems. void | [unsubscribe_on_new_system](#classmavsdk_1_1_mavsdk_1ad7f77f1295a700ee73cccc345019c1ff) ([NewSystemHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ae0727f2bed9cbf276d161ada0a432b8c) handle) | unsubscribe from subscribe_on_new_system. -std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > | [server_component](#classmavsdk_1_1_mavsdk_1a5ad97e4af7de0f253cca8af7e76b68b6) (unsigned instance=0) | Get server component with default type of [Mavsdk](classmavsdk_1_1_mavsdk.md) instance. -std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > | [server_component_by_type](#classmavsdk_1_1_mavsdk_1a669a7ec5ed40dec9fde7e7a080fa7f2d) ([ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) component_type, unsigned instance=0) | Get server component by a high level type. -std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > | [server_component_by_id](#classmavsdk_1_1_mavsdk_1a117e6dc31b9124b6d535aa363283f8d7) (uint8_t component_id) | Get server component by the low MAVLink component ID. +std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > | [server_component](#classmavsdk_1_1_mavsdk_1a693a2f665c35d6b01d6144819d353280) (unsigned instance=0) | Get server component with default type of [Mavsdk](classmavsdk_1_1_mavsdk.md) instance. +std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > | [server_component_by_type](#classmavsdk_1_1_mavsdk_1a547fc7e18434473ea3e0e51ab3305abb) ([ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) component_type, unsigned instance=0) | Get server component by a high level type. +std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > | [server_component_by_id](#classmavsdk_1_1_mavsdk_1adef7d0d7422bcddbda629a404fb33ae2) (uint8_t component_id) | Get server component by the low MAVLink component ID. void | [intercept_incoming_messages_async](#classmavsdk_1_1_mavsdk_1ac80c8909958533131cbdbc61d061794f) (std::function< bool(mavlink_message_t &)> callback) | Intercept incoming messages. void | [intercept_outgoing_messages_async](#classmavsdk_1_1_mavsdk_1a040ee5c1d41e71c0d63cf8f76d2db275) (std::function< bool(mavlink_message_t &)> callback) | Intercept outgoing messages. -## Static Public Attributes - - -static constexpr auto [DEFAULT_UDP_BIND_IP](#classmavsdk_1_1_mavsdk_1ac46b2c27d9c428ec46092f10774482fa) = "0.0.0.0" - Default UDP bind IP (accepts any incoming connections). - - -static constexpr int [DEFAULT_UDP_PORT](#classmavsdk_1_1_mavsdk_1affddcc7c7849ed86a0c7dab1166e657a) = 14540 - Default UDP bind port (same port as used by MAVROS). - - -static constexpr auto [DEFAULT_TCP_REMOTE_IP](#classmavsdk_1_1_mavsdk_1a0154aac9d933fa212a50dc687816fbad) = "127.0.0.1" - Default TCP remote IP (localhost). - - -static constexpr int [DEFAULT_TCP_REMOTE_PORT](#classmavsdk_1_1_mavsdk_1a52a6a9e0acd6c0ade566208d253427bd) = 5760 - Default TCP remote port. - - -static constexpr int [DEFAULT_SERIAL_BAUDRATE](#classmavsdk_1_1_mavsdk_1a870d15142914f1db564c12f385d5489b) = 57600 - Default serial baudrate. - - -static constexpr double [DEFAULT_TIMEOUT_S](#classmavsdk_1_1_mavsdk_1a74f7b4d32d9551bb9c11ce8668f634a6) = 0.5 - Default internal timeout in seconds. - ## Constructor & Destructor Documentation @@ -90,7 +69,9 @@ mavsdk::Mavsdk::Mavsdk()=delete Default constructor without configuration, no longer recommended. -> **Note** This has been removed because MAVSDK used to identify itself as a ground station by default which isn't always the safest choice. For instance, when MAVSDK is used on a companion computer (set as a ground station) it means that the appropriate failsafe doesn't trigger. +::: info +This has been removed because MAVSDK used to identify itself as a ground station by default which isn't always the safest choice. For instance, when MAVSDK is used on a companion computer (set as a ground station) it means that the appropriate failsafe doesn't trigger. +::: ### Mavsdk() {#classmavsdk_1_1_mavsdk_1a02b160aa2717f7064d2517e00065e6ac} ```cpp @@ -128,42 +109,44 @@ using mavsdk::Mavsdk::ConnectionHandle = Handle<> [Handle](classmavsdk_1_1_handle.md) type to remove a connection. -### typedef NewSystemCallback {#classmavsdk_1_1_mavsdk_1a7a283c6a75e852a56be4c5862f8a3fab} +### typedef ConnectionErrorCallback {#classmavsdk_1_1_mavsdk_1ac71d182538bee6fb3ab007edafac5d5f} ```cpp -using mavsdk::Mavsdk::NewSystemCallback = std::function +using mavsdk::Mavsdk::ConnectionErrorCallback = std::function ``` -Callback type discover and timeout notifications. +Connection Error callback type - -### typedef NewSystemHandle {#classmavsdk_1_1_mavsdk_1ae0727f2bed9cbf276d161ada0a432b8c} +### typedef ConnectionErrorHandle {#classmavsdk_1_1_mavsdk_1aeb442a462d03662e4c152509fd0c203b} ```cpp -using mavsdk::Mavsdk::NewSystemHandle = Handle<> +using mavsdk::Mavsdk::ConnectionErrorHandle = Handle ``` -[Handle](classmavsdk_1_1_handle.md) type to unsubscribe from subscribe_on_new_system. +[Handle](classmavsdk_1_1_handle.md) type to remove a connection error subscription. -## Member Enumeration Documentation +### typedef NewSystemCallback {#classmavsdk_1_1_mavsdk_1a7a283c6a75e852a56be4c5862f8a3fab} +```cpp +using mavsdk::Mavsdk::NewSystemCallback = std::function +``` -### enum ComponentType {#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746} +Callback type discover and timeout notifications. -ComponentType of configurations, used for automatic ID setting. +### typedef NewSystemHandle {#classmavsdk_1_1_mavsdk_1ae0727f2bed9cbf276d161ada0a432b8c} + +```cpp +using mavsdk::Mavsdk::NewSystemHandle = Handle<> +``` + + +[Handle](classmavsdk_1_1_handle.md) type to unsubscribe from subscribe_on_new_system. -Value | Description ---- | --- - `Autopilot` | SDK is used as an autopilot. - `GroundStation` | SDK is used as a ground station. - `CompanionComputer` | SDK is used as a companion computer on board the MAV. - `Camera` | SDK is used as a camera. - `Custom` | SDK is used in a custom configuration, no automatic ID will be provided. ## Member Function Documentation @@ -191,24 +174,37 @@ ConnectionResult mavsdk::Mavsdk::add_any_connection(const std::string &connectio Adds Connection via URL. Supports connection: Serial, TCP or UDP. Connection URL format should be: + +
    -
  • UDP: udp://[host][:bind_port]

    +
  • UDP in (server): udpin://our_ip:port

    +
  • +
  • UDP out (client): udpout://remote_ip:port

    +
  • +
  • TCP in (server): tcpin://our_ip:port

    +
  • +
  • TCP out (client): tcpout://remote_ip:port

  • -
  • TCP: tcp://[host][:remote_port]

    +
  • Serial: serial://dev_node:baudrate

  • -
  • Serial: serial://dev_node[:baudrate]

    +
  • Serial with flow control: serial_flowcontrol://dev_node:baudrate

-For UDP, the host can be set to either: +For UDP in and TCP in (as server), our IP can be set to:
    -
  • zero IP: 0.0.0.0 -> behave like a server and listen for heartbeats.

    +
  • 0.0.0.0: listen on all interfaces

  • -
  • some IP: 192.168.1.12 -> behave like a client, initiate connection and start sending heartbeats.

    +
  • 127.0.0.1: listen on loopback (local) interface only

    +
  • +
  • Our IP: (e.g. 192.168.1.12): listen only on the network interface with this IP.

+ +For UDP out and TCP out, the IP needs to be set to the remote IP, where the MAVLink messages are to be sent to. + **Parameters** * const std::string& **connection_url** - connection URL string. @@ -218,154 +214,104 @@ For UDP, the host can be set to either:  [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) - The result of adding the connection. -### add_any_connection_with_handle() {#classmavsdk_1_1_mavsdk_1ad1dc8afaafea8f7e900c990552e6fdfb} +### add_any_connection_with_handle() {#classmavsdk_1_1_mavsdk_1ad12297d30ec1bbe4750f7cf4efbbed57} ```cpp -std::pair mavsdk::Mavsdk::add_any_connection_with_handle(const std::string &connection_url, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) +std::pair< ConnectionResult, ConnectionHandle > mavsdk::Mavsdk::add_any_connection_with_handle(const std::string &connection_url, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) ``` Adds Connection via URL Additionally returns a handle to remove the connection later. Supports connection: Serial, TCP or UDP. Connection URL format should be: + +
    -
  • UDP: udp://[host][:bind_port]

    +
  • UDP in (server): udpin://our_ip:port

  • -
  • TCP: tcp://[host][:remote_port]

    +
  • UDP out (client): udpout://remote_ip:port

  • -
  • Serial: serial://dev_node[:baudrate]

    +
  • TCP in (server): tcpin://our_ip:port

    +
  • +
  • TCP out (client): tcpout://remote_ip:port

    +
  • +
  • Serial: serial://dev_node:baudrate

    +
  • +
  • Serial with flow control: serial_flowcontrol://dev_node:baudrate

-For UDP, the host can be set to either: +For UDP in and TCP in (as server), our IP can be set to:
    -
  • zero IP: 0.0.0.0 -> behave like a server and listen for heartbeats.

    +
  • 0.0.0.0: listen on all interfaces

  • -
  • some IP: 192.168.1.12 -> behave like a client, initiate connection and start sending heartbeats.

    +
  • 127.0.0.1: listen on loopback (local) interface only

    +
  • +
  • Our IP: (e.g. 192.168.1.12): listen only on the network interface with this IP.

-**Parameters** - -* const std::string& **connection_url** - connection URL string. -* [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) **forwarding_option** - message forwarding option (when multiple interfaces are used). - -**Returns** - - std::pair< [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992), [ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) > - A pair containing the result of adding the connection as well as a handle to remove it later. - -### add_udp_connection() {#classmavsdk_1_1_mavsdk_1aa43dfb00d5118d26ae5aabd0f9ba56b2} -```cpp -ConnectionResult mavsdk::Mavsdk::add_udp_connection(int local_port=DEFAULT_UDP_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) -``` - -Adds a UDP connection to the specified port number. - -Any incoming connections are accepted (0.0.0.0). +For UDP out and TCP out, the IP needs to be set to the remote IP, where the MAVLink messages are to be sent to. **Parameters** -* int **local_port** - The local UDP port to listen to (defaults to 14540, the same as MAVROS). -* [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) **forwarding_option** - message forwarding option (when multiple interfaces are used). - -**Returns** - - [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) - The result of adding the connection. - -### add_udp_connection() {#classmavsdk_1_1_mavsdk_1a98fd1c01bd366b27084810875a1b94c1} -```cpp -ConnectionResult mavsdk::Mavsdk::add_udp_connection(const std::string &local_ip, int local_port=DEFAULT_UDP_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) -``` - - -Adds a UDP connection to the specified port number and local interface. - -To accept only local connections of the machine, use 127.0.0.1. For any incoming connections, use 0.0.0.0. - -**Parameters** - -* const std::string& **local_ip** - The local UDP IP address to listen to. -* int **local_port** - The local UDP port to listen to (defaults to 14540, the same as MAVROS). +* const std::string& **connection_url** - connection URL string. * [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) **forwarding_option** - message forwarding option (when multiple interfaces are used). **Returns** - [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) - The result of adding the connection. + std::pair< [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992), [ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) > - A pair containing the result of adding the connection as well as a handle to remove it later. -### setup_udp_remote() {#classmavsdk_1_1_mavsdk_1adb2a69282a5d3766fd6251662c28616d} +### remove_connection() {#classmavsdk_1_1_mavsdk_1a23cf630bb123aa53b0e99c6bd83ad013} ```cpp -ConnectionResult mavsdk::Mavsdk::setup_udp_remote(const std::string &remote_ip, int remote_port, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) +void mavsdk::Mavsdk::remove_connection(ConnectionHandle handle) ``` -Sets up instance to send heartbeats to the specified remote interface and port number. - +Remove connection again. **Parameters** -* const std::string& **remote_ip** - The remote UDP IP address to report to. -* int **remote_port** - The local UDP port to report to. -* [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) **forwarding_option** - message forwarding option (when multiple interfaces are used). - -**Returns** - - [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) - The result of operation. +* [ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) **handle** - [Handle](classmavsdk_1_1_handle.md) returned when connection was added. -### add_tcp_connection() {#classmavsdk_1_1_mavsdk_1a50ecebb9ee710b9a044d2d5eb57645e4} +### subscribe_connection_errors() {#classmavsdk_1_1_mavsdk_1a8f50fffac65a35857a88da2fd42f9c54} ```cpp -ConnectionResult mavsdk::Mavsdk::add_tcp_connection(const std::string &remote_ip, int remote_port=DEFAULT_TCP_REMOTE_PORT, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) +ConnectionErrorHandle mavsdk::Mavsdk::subscribe_connection_errors(ConnectionErrorCallback callback) ``` -Adds a TCP connection with a specific IP address and port number. - +Subscribe to connection errors. -**Parameters** - -* const std::string& **remote_ip** - Remote IP address to connect to. -* int **remote_port** - The TCP port to connect to (defaults to 5760). -* [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) **forwarding_option** - message forwarding option (when multiple interfaces are used). - -**Returns** - - [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) - The result of adding the connection. - -### add_serial_connection() {#classmavsdk_1_1_mavsdk_1a669ddeec7af571fdbde9f31e343d50ac} -```cpp -ConnectionResult mavsdk::Mavsdk::add_serial_connection(const std::string &dev_path, int baudrate=DEFAULT_SERIAL_BAUDRATE, bool flow_control=false, ForwardingOption forwarding_option=ForwardingOption::ForwardingOff) -``` +This will trigger when messages fail to be sent which can help diagnosing network interfaces or serial devices disappearing. -Adds a serial connection with a specific port (COM or UART dev node) and baudrate as specified. +Usually, an error will require to remove a connection and add it fresh. **Parameters** -* const std::string& **dev_path** - COM or UART dev node name/path (e.g. "/dev/ttyS0", or "COM3" on Windows). -* int **baudrate** - Baudrate of the serial port (defaults to 57600). -* bool **flow_control** - enable/disable flow control. -* [ForwardingOption](namespacemavsdk.md#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) **forwarding_option** - message forwarding option (when multiple interfaces are used). +* [ConnectionErrorCallback](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac71d182538bee6fb3ab007edafac5d5f) **callback** - Callback to subscribe. **Returns** - [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) - The result of adding the connection. + [ConnectionErrorHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1aeb442a462d03662e4c152509fd0c203b) - [Handle](classmavsdk_1_1_handle.md) to unsubscribe again. -### remove_connection() {#classmavsdk_1_1_mavsdk_1a23cf630bb123aa53b0e99c6bd83ad013} +### unsubscribe_connection_errors() {#classmavsdk_1_1_mavsdk_1a377ec6517ee75981ceb2f26b30e59fbd} ```cpp -void mavsdk::Mavsdk::remove_connection(ConnectionHandle handle) +void mavsdk::Mavsdk::unsubscribe_connection_errors(ConnectionErrorHandle handle) ``` -Remove connection again. +Unsubscribe from connection errors. **Parameters** -* [ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) **handle** - [Handle](classmavsdk_1_1_handle.md) returned when connection was added. +* [ConnectionErrorHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1aeb442a462d03662e4c152509fd0c203b) **handle** - [Handle](classmavsdk_1_1_handle.md) to unsubscribe. -### systems() {#classmavsdk_1_1_mavsdk_1a0d0bc4cdab14d96877b52baec5113fa8} +### systems() {#classmavsdk_1_1_mavsdk_1aca9c72b300d384341b00ff9ba2c6e5c5} ```cpp -std::vector > mavsdk::Mavsdk::systems() const +std::vector< std::shared_ptr< System > > mavsdk::Mavsdk::systems() const ``` @@ -376,15 +322,17 @@ Get a vector of systems which have been discovered or set-up.  std::vector< std::shared_ptr< [System](classmavsdk_1_1_system.md) > > - The vector of systems which are available. -### first_autopilot() {#classmavsdk_1_1_mavsdk_1a30b5c588643d19f1cfa9a7be47acb52c} +### first_autopilot() {#classmavsdk_1_1_mavsdk_1aa1bcb865693dbd140478e75ce58699b7} ```cpp -std::optional > mavsdk::Mavsdk::first_autopilot(double timeout_s) const +std::optional< std::shared_ptr< System > > mavsdk::Mavsdk::first_autopilot(double timeout_s) const ``` Get the first autopilot that has been discovered. -> **Note** This requires a MAVLink component with component ID 1 sending heartbeats. +::: info +This requires a MAVLink component with component ID 1 sending heartbeats. +::: **Parameters** @@ -422,20 +370,6 @@ The default timeout used is generally DEFAULT_SERIAL_BAUDRATE (0.5 seconds) seco * double **timeout_s** - -### set_system_status() {#classmavsdk_1_1_mavsdk_1a693eac9fce2e9a330a3b9213ac9faae4} -```cpp -void mavsdk::Mavsdk::set_system_status(uint8_t system_status) -``` - - -Set system status of this MAVLink entity. - -The default system status is MAV_STATE_UNINIT. - -**Parameters** - -* uint8_t **system_status** - system status. - ### subscribe_on_new_system() {#classmavsdk_1_1_mavsdk_1a5b7c958ad2e4529dc7b950ab26618575} ```cpp NewSystemHandle mavsdk::Mavsdk::subscribe_on_new_system(const NewSystemCallback &callback) @@ -467,9 +401,9 @@ unsubscribe from subscribe_on_new_system. * [NewSystemHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ae0727f2bed9cbf276d161ada0a432b8c) **handle** - [Handle](classmavsdk_1_1_handle.md) received on subscription. -### server_component() {#classmavsdk_1_1_mavsdk_1a5ad97e4af7de0f253cca8af7e76b68b6} +### server_component() {#classmavsdk_1_1_mavsdk_1a693a2f665c35d6b01d6144819d353280} ```cpp -std::shared_ptr mavsdk::Mavsdk::server_component(unsigned instance=0) +std::shared_ptr< ServerComponent > mavsdk::Mavsdk::server_component(unsigned instance=0) ``` @@ -484,9 +418,9 @@ Get server component with default type of [Mavsdk](classmavsdk_1_1_mavsdk.md) in  std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > - A valid shared pointer to a server component if it was successful, an empty pointer otherwise. -### server_component_by_type() {#classmavsdk_1_1_mavsdk_1a669a7ec5ed40dec9fde7e7a080fa7f2d} +### server_component_by_type() {#classmavsdk_1_1_mavsdk_1a547fc7e18434473ea3e0e51ab3305abb} ```cpp -std::shared_ptr mavsdk::Mavsdk::server_component_by_type(ComponentType component_type, unsigned instance=0) +std::shared_ptr< ServerComponent > mavsdk::Mavsdk::server_component_by_type(ComponentType component_type, unsigned instance=0) ``` @@ -496,16 +430,16 @@ This represents a server component of the MAVSDK instance. **Parameters** -* [ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) **component_type** - The high level type of the component. +* [ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) **component_type** - The high level type of the component. * unsigned **instance** - The instance of the component if there are multiple, starting at 0. **Returns**  std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > - A valid shared pointer to a server component if it was successful, an empty pointer otherwise. -### server_component_by_id() {#classmavsdk_1_1_mavsdk_1a117e6dc31b9124b6d535aa363283f8d7} +### server_component_by_id() {#classmavsdk_1_1_mavsdk_1adef7d0d7422bcddbda629a404fb33ae2} ```cpp -std::shared_ptr mavsdk::Mavsdk::server_component_by_id(uint8_t component_id) +std::shared_ptr< ServerComponent > mavsdk::Mavsdk::server_component_by_id(uint8_t component_id) ``` @@ -532,7 +466,9 @@ Intercept incoming messages. This is a hook which allows to change or drop MAVLink messages as they are received before they get forwarded any subscribers. -> **Note** This functionality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols. +::: info +This functionality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols. +::: **Parameters** @@ -549,71 +485,10 @@ Intercept outgoing messages. This is a hook which allows to change or drop MAVLink messages before they are sent. -> **Note** This functionality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols. +::: info +This functionality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols. +::: **Parameters** -* std::function< bool(mavlink_message_t &)> **callback** - Callback to be called for each outgoing message. To drop a message, return 'false' from the callback. - -## Field Documentation - - -### DEFAULT_UDP_BIND_IP {#classmavsdk_1_1_mavsdk_1ac46b2c27d9c428ec46092f10774482fa} - -```cpp -constexpr auto mavsdk::Mavsdk::DEFAULT_UDP_BIND_IP = "0.0.0.0" -``` - - -Default UDP bind IP (accepts any incoming connections). - - -### DEFAULT_UDP_PORT {#classmavsdk_1_1_mavsdk_1affddcc7c7849ed86a0c7dab1166e657a} - -```cpp -constexpr int mavsdk::Mavsdk::DEFAULT_UDP_PORT = 14540 -``` - - -Default UDP bind port (same port as used by MAVROS). - - -### DEFAULT_TCP_REMOTE_IP {#classmavsdk_1_1_mavsdk_1a0154aac9d933fa212a50dc687816fbad} - -```cpp -constexpr auto mavsdk::Mavsdk::DEFAULT_TCP_REMOTE_IP = "127.0.0.1" -``` - - -Default TCP remote IP (localhost). - - -### DEFAULT_TCP_REMOTE_PORT {#classmavsdk_1_1_mavsdk_1a52a6a9e0acd6c0ade566208d253427bd} - -```cpp -constexpr int mavsdk::Mavsdk::DEFAULT_TCP_REMOTE_PORT = 5760 -``` - - -Default TCP remote port. - - -### DEFAULT_SERIAL_BAUDRATE {#classmavsdk_1_1_mavsdk_1a870d15142914f1db564c12f385d5489b} - -```cpp -constexpr int mavsdk::Mavsdk::DEFAULT_SERIAL_BAUDRATE = 57600 -``` - - -Default serial baudrate. - - -### DEFAULT_TIMEOUT_S {#classmavsdk_1_1_mavsdk_1a74f7b4d32d9551bb9c11ce8668f634a6} - -```cpp -constexpr double mavsdk::Mavsdk::DEFAULT_TIMEOUT_S = 0.5 -``` - - -Default internal timeout in seconds. - +* std::function< bool(mavlink_message_t &)> **callback** - Callback to be called for each outgoing message. To drop a message, return 'false' from the callback. \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk_1_1_configuration.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk_1_1_configuration.md index 74ff60acc9..c56b0ad840 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk_1_1_configuration.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk_1_1_configuration.md @@ -13,7 +13,7 @@ Possible configurations. Type | Name | Description ---: | --- | ---   | [Configuration](#classmavsdk_1_1_mavsdk_1_1_configuration_1a10477130d041107e76efd1f94e65b503) (uint8_t system_id, uint8_t component_id, bool always_send_heartbeats) | Create new [Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) via manually configured system and component ID. -  | [Configuration](#classmavsdk_1_1_mavsdk_1_1_configuration_1abcc015ee6be8abc2da2c967bbbda9fed) ([ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) component_type) | Create new [Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) using a component type. In this mode, the system and component ID will be automatically chosen. +  | [Configuration](#classmavsdk_1_1_mavsdk_1_1_configuration_1abcc015ee6be8abc2da2c967bbbda9fed) ([ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) component_type) | Create new [Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) using a component type. In this mode, the system and component ID will be automatically chosen.   | [Configuration](#classmavsdk_1_1_mavsdk_1_1_configuration_1a1a65e2e31f06bec1f6692a933c95b03c) ()=delete |   | [~Configuration](#classmavsdk_1_1_mavsdk_1_1_configuration_1a31cad2329ee14898752638d9c3759da9) ()=default | uint8_t | [get_system_id](#classmavsdk_1_1_mavsdk_1_1_configuration_1a0497bdda816b674b1418ab07889ca781) () const | Get the system id of this configuration. @@ -22,8 +22,10 @@ uint8_t | [get_component_id](#classmavsdk_1_1_mavsdk_1_1_configuration_1adfcae3d void | [set_component_id](#classmavsdk_1_1_mavsdk_1_1_configuration_1aa590fbafa8ca104e1a004ca537f5798e) (uint8_t component_id) | Set the component id of this configuration. bool | [get_always_send_heartbeats](#classmavsdk_1_1_mavsdk_1_1_configuration_1a0aa9008fe5a7498f374dbd2adad5f137) () const | Get whether to send heartbeats by default. void | [set_always_send_heartbeats](#classmavsdk_1_1_mavsdk_1_1_configuration_1a0ad68b52763e205012b34faa5120a792) (bool always_send_heartbeats) | Set whether to send heartbeats by default. -[ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) | [get_component_type](#classmavsdk_1_1_mavsdk_1_1_configuration_1a81d3645816f8a3072044498c3f539d12) () const | Component type of this configuration, used for automatic ID set. -void | [set_component_type](#classmavsdk_1_1_mavsdk_1_1_configuration_1a06461b86734eaa9544e80a4a907c9754) ([ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) component_type) | Set the component type of this configuration. +[ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) | [get_component_type](#classmavsdk_1_1_mavsdk_1_1_configuration_1a81d3645816f8a3072044498c3f539d12) () const | Component type of this configuration, used for automatic ID set. +void | [set_component_type](#classmavsdk_1_1_mavsdk_1_1_configuration_1a06461b86734eaa9544e80a4a907c9754) ([ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) component_type) | Set the component type of this configuration. +uint8_t | [get_mav_type](#classmavsdk_1_1_mavsdk_1_1_configuration_1aafe9e8fc11dd0b688a836c123357e9ba) () const | Get the mav type (vehicle type) of this configuration. +void | [set_mav_type](#classmavsdk_1_1_mavsdk_1_1_configuration_1a16db98d8802c3427b1be10f0b72b977b) (uint8_t mav_type) | Set the mav type (vehicle type) of this configuration. ## Constructor & Destructor Documentation @@ -55,7 +57,7 @@ Create new [Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) using a **Parameters** -* [ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) **component_type** - the component type, used for automatically choosing ids. +* [ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) **component_type** - the component type, used for automatically choosing ids. ### Configuration() {#classmavsdk_1_1_mavsdk_1_1_configuration_1a1a65e2e31f06bec1f6692a933c95b03c} ```cpp @@ -161,7 +163,7 @@ Component type of this configuration, used for automatic ID set. **Returns** - [ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) - + [ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) - ### set_component_type() {#classmavsdk_1_1_mavsdk_1_1_configuration_1a06461b86734eaa9544e80a4a907c9754} ```cpp @@ -174,4 +176,30 @@ Set the component type of this configuration. **Parameters** -* [ComponentType](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac9e9d48bbf840dad8705323b224b1746) **component_type** - \ No newline at end of file +* [ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) **component_type** - + +### get_mav_type() {#classmavsdk_1_1_mavsdk_1_1_configuration_1aafe9e8fc11dd0b688a836c123357e9ba} +```cpp +uint8_t mavsdk::Mavsdk::Configuration::get_mav_type() const +``` + + +Get the mav type (vehicle type) of this configuration. + + +**Returns** + + uint8_t - `uint8_t` the mav type stored in this configuration + +### set_mav_type() {#classmavsdk_1_1_mavsdk_1_1_configuration_1a16db98d8802c3427b1be10f0b72b977b} +```cpp +void mavsdk::Mavsdk::Configuration::set_mav_type(uint8_t mav_type) +``` + + +Set the mav type (vehicle type) of this configuration. + + +**Parameters** + +* uint8_t **mav_type** - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mission.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mission.md index b3bca7e413..9a345bb070 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mission.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mission.md @@ -47,7 +47,7 @@ void | [upload_mission_async](#classmavsdk_1_1_mission_1a250fc4758d47ec12e025c32 void | [upload_mission_with_progress_async](#classmavsdk_1_1_mission_1a0faa587e80a59e8c40d7fc135650749c) ([MissionPlan](structmavsdk_1_1_mission_1_1_mission_plan.md) mission_plan, const [UploadMissionWithProgressCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1a559c82c81b3b7694973da8a65af24837) & callback) | Upload a list of mission items to the system and report upload progress. [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) | [cancel_mission_upload](#classmavsdk_1_1_mission_1ab82609426bef51202b2107d33412378c) () const | Cancel an ongoing mission upload. void | [download_mission_async](#classmavsdk_1_1_mission_1a04e7e7074273b4591a820894c5c4ad43) (const [DownloadMissionCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1af40f70b9b4c91aa280bf75fbfc333b3b) callback) | Download a list of mission items from the system (asynchronous). -std::pair< [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6), [Mission::MissionPlan](structmavsdk_1_1_mission_1_1_mission_plan.md) > | [download_mission](#classmavsdk_1_1_mission_1a23e9f7da32f42bcce7ef16ea8044fe53) () const | Download a list of mission items from the system (asynchronous). +std::pair< [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6), [Mission::MissionPlan](structmavsdk_1_1_mission_1_1_mission_plan.md) > | [download_mission](#classmavsdk_1_1_mission_1adef2001c0053c669bcc5522619ac90f9) () const | Download a list of mission items from the system (asynchronous). void | [download_mission_with_progress_async](#classmavsdk_1_1_mission_1a5b6b93482f2599c08d75d27a31a4f1d9) (const [DownloadMissionWithProgressCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ae73dbe775ceaba81183cebdaa1b6779e) & callback) | Download a list of mission items from the system (asynchronous) and report progress. [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) | [cancel_mission_download](#classmavsdk_1_1_mission_1a0eaaeffe0354156b5abed892f0950bcc) () const | Cancel an ongoing mission download. void | [start_mission_async](#classmavsdk_1_1_mission_1a31ca2fc6b9fe4802dbc3fbebad0bb5d7) (const [ResultCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1a30091e79f5b67ade138e5be9d65b6591) callback) | Start the mission. @@ -58,13 +58,13 @@ void | [clear_mission_async](#classmavsdk_1_1_mission_1a51d04a808743915e3cac7f35 [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) | [clear_mission](#classmavsdk_1_1_mission_1a3c3f5eac6e864873f4bb0390d1ee9306) () const | Clear the mission saved on the vehicle. void | [set_current_mission_item_async](#classmavsdk_1_1_mission_1a81aa356215cb2131c2480dc121a6af7b) (int32_t index, const [ResultCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1a30091e79f5b67ade138e5be9d65b6591) callback) | Sets the mission item index to go to. [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) | [set_current_mission_item](#classmavsdk_1_1_mission_1a419397edcf63771ddd59a6af231bc8d2) (int32_t index)const | Sets the mission item index to go to. -std::pair< [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6), bool > | [is_mission_finished](#classmavsdk_1_1_mission_1a1ecf4f8798ab9ae96882dfbd34f23466) () const | Check if the mission has been finished. +std::pair< [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6), bool > | [is_mission_finished](#classmavsdk_1_1_mission_1a8fe0296995ffd2130dceb338f6deb3cf) () const | Check if the mission has been finished. [MissionProgressHandle](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1aded0ba06c787ad2f30f401a30b240c8a) | [subscribe_mission_progress](#classmavsdk_1_1_mission_1ac6d3e78de0ea2e6c1db2eaa5f3418660) (const [MissionProgressCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1a67e8d00b1b20affca59fd4338c34c0e2) & callback) | Subscribe to mission progress updates. void | [unsubscribe_mission_progress](#classmavsdk_1_1_mission_1a2b8bc4dd210506a703afa926f8406880) ([MissionProgressHandle](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1aded0ba06c787ad2f30f401a30b240c8a) handle) | Unsubscribe from subscribe_mission_progress. [MissionProgress](structmavsdk_1_1_mission_1_1_mission_progress.md) | [mission_progress](#classmavsdk_1_1_mission_1a5570443e7c1f08cff1759980ff44b40e) () const | Poll for '[MissionProgress](structmavsdk_1_1_mission_1_1_mission_progress.md)' (blocking). -std::pair< [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6), bool > | [get_return_to_launch_after_mission](#classmavsdk_1_1_mission_1a38d17268541ba81d494976caa4a08661) () const | Get whether to trigger Return-to-Launch (RTL) after mission is complete. +std::pair< [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6), bool > | [get_return_to_launch_after_mission](#classmavsdk_1_1_mission_1a15ecbb4a95da4d33b80a78b9d8ec722b) () const | Get whether to trigger Return-to-Launch (RTL) after mission is complete. [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) | [set_return_to_launch_after_mission](#classmavsdk_1_1_mission_1ab4adb09283b3fa64a8829f9a6e34cf37) (bool enable)const | Set whether to trigger Return-to-Launch (RTL) after the mission is complete. -const [Mission](classmavsdk_1_1_mission.md) & | [operator=](#classmavsdk_1_1_mission_1a30d49ea769f358cb4e4fe3056728838c) (const [Mission](classmavsdk_1_1_mission.md) &)=delete | Equality operator (object is not copyable). +const [Mission](classmavsdk_1_1_mission.md) & | [operator=](#classmavsdk_1_1_mission_1a264bcda67c38e8e447ce36eee662924e) (const [Mission](classmavsdk_1_1_mission.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -307,9 +307,9 @@ This function is non-blocking. See 'download_mission' for the blocking counterpa * const [DownloadMissionCallback](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1af40f70b9b4c91aa280bf75fbfc333b3b) **callback** - -### download_mission() {#classmavsdk_1_1_mission_1a23e9f7da32f42bcce7ef16ea8044fe53} +### download_mission() {#classmavsdk_1_1_mission_1adef2001c0053c669bcc5522619ac90f9} ```cpp -std::pair mavsdk::Mission::download_mission() const +std::pair< Result, Mission::MissionPlan > mavsdk::Mission::download_mission() const ``` @@ -493,9 +493,9 @@ This function is blocking. See 'set_current_mission_item_async' for the non-bloc  [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) - Result of request. -### is_mission_finished() {#classmavsdk_1_1_mission_1a1ecf4f8798ab9ae96882dfbd34f23466} +### is_mission_finished() {#classmavsdk_1_1_mission_1a8fe0296995ffd2130dceb338f6deb3cf} ```cpp -std::pair mavsdk::Mission::is_mission_finished() const +std::pair< Result, bool > mavsdk::Mission::is_mission_finished() const ``` @@ -550,9 +550,9 @@ Poll for '[MissionProgress](structmavsdk_1_1_mission_1_1_mission_progress.md)' (  [MissionProgress](structmavsdk_1_1_mission_1_1_mission_progress.md) - One [MissionProgress](structmavsdk_1_1_mission_1_1_mission_progress.md) update. -### get_return_to_launch_after_mission() {#classmavsdk_1_1_mission_1a38d17268541ba81d494976caa4a08661} +### get_return_to_launch_after_mission() {#classmavsdk_1_1_mission_1a15ecbb4a95da4d33b80a78b9d8ec722b} ```cpp -std::pair mavsdk::Mission::get_return_to_launch_after_mission() const +std::pair< Result, bool > mavsdk::Mission::get_return_to_launch_after_mission() const ``` @@ -588,9 +588,9 @@ This function is blocking.  [Result](classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1ab3114c63db76bdc37460939a1f3316f6) - Result of request. -### operator=() {#classmavsdk_1_1_mission_1a30d49ea769f358cb4e4fe3056728838c} +### operator=() {#classmavsdk_1_1_mission_1a264bcda67c38e8e447ce36eee662924e} ```cpp -const Mission& mavsdk::Mission::operator=(const Mission &)=delete +const Mission & mavsdk::Mission::operator=(const Mission &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw.md index d8c42bd7a3..bfa0aaebfa 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw.md @@ -24,6 +24,8 @@ Type | Description enum [Result](#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf) | Possible results returned for action requests. std::function< void([Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf))> [ResultCallback](#classmavsdk_1_1_mission_raw_1a1a36a84f17dca07e1da49c13abbc9564) | Callback type for asynchronous [MissionRaw](classmavsdk_1_1_mission_raw.md) calls. std::function< void([Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) >)> [DownloadMissionCallback](#classmavsdk_1_1_mission_raw_1a016633e6338744da02ac7cb6da28880a) | Callback type for download_mission_async. +std::function< void([Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) >)> [DownloadGeofenceCallback](#classmavsdk_1_1_mission_raw_1a3e75d493ec08fec9d9faa597238c11be) | Callback type for download_geofence_async. +std::function< void([Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) >)> [DownloadRallypointsCallback](#classmavsdk_1_1_mission_raw_1a473abce54f89efe05d5ac051c9d8a5dc) | Callback type for download_rallypoints_async. std::function< void([MissionProgress](structmavsdk_1_1_mission_raw_1_1_mission_progress.md))> [MissionProgressCallback](#classmavsdk_1_1_mission_raw_1a9dd594878925da494b4add6acc3184fc) | Callback type for subscribe_mission_progress. [Handle](classmavsdk_1_1_handle.md)< [MissionProgress](structmavsdk_1_1_mission_raw_1_1_mission_progress.md) > [MissionProgressHandle](#classmavsdk_1_1_mission_raw_1a34e0eaf9922daa5d27d2b044eae7885c) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_mission_progress. std::function< void(bool)> [MissionChangedCallback](#classmavsdk_1_1_mission_raw_1ac22d81eefc5e883cdb6baf792a7487e6) | Callback type for subscribe_mission_changed. @@ -46,7 +48,11 @@ void | [upload_rally_points_async](#classmavsdk_1_1_mission_raw_1a2c5d52246a8ad1 [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf) | [upload_rally_points](#classmavsdk_1_1_mission_raw_1a02fc4f293a8094df5dbd7ea0d2184739) (std::vector< [MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > mission_items)const | Upload a list of rally point items to the system. [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf) | [cancel_mission_upload](#classmavsdk_1_1_mission_raw_1aa353e3fa6e836305248be131dbe19273) () const | Cancel an ongoing mission upload. void | [download_mission_async](#classmavsdk_1_1_mission_raw_1a7e27b0fb58889ca5cb1202276c0e0669) (const [DownloadMissionCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a016633e6338744da02ac7cb6da28880a) callback) | Download a list of raw mission items from the system (asynchronous). -std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > | [download_mission](#classmavsdk_1_1_mission_raw_1a2cc470785c486d1b7fdaaa2e3fbff809) () const | Download a list of raw mission items from the system (asynchronous). +std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > | [download_mission](#classmavsdk_1_1_mission_raw_1a18138bc7cbc6c6c16fde44e2fa53a459) () const | Download a list of raw mission items from the system (asynchronous). +void | [download_geofence_async](#classmavsdk_1_1_mission_raw_1acc681495c318043334691ab9ccd6778d) (const [DownloadGeofenceCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a3e75d493ec08fec9d9faa597238c11be) callback) | Download a list of raw geofence items from the system (asynchronous). +std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > | [download_geofence](#classmavsdk_1_1_mission_raw_1ae2d3d743e00312e07ca3893ab27f0138) () const | Download a list of raw geofence items from the system (asynchronous). +void | [download_rallypoints_async](#classmavsdk_1_1_mission_raw_1a38e58cdecc1737936bec5d046c8eb511) (const [DownloadRallypointsCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a473abce54f89efe05d5ac051c9d8a5dc) callback) | Download a list of raw rallypoint items from the system (asynchronous). +std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > | [download_rallypoints](#classmavsdk_1_1_mission_raw_1a0cb3895f91bb2042c9d3282b09c442af) () const | Download a list of raw rallypoint items from the system (asynchronous). [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf) | [cancel_mission_download](#classmavsdk_1_1_mission_raw_1a7c554999ca66c5434ef1fa334d949e5a) () const | Cancel an ongoing mission download. void | [start_mission_async](#classmavsdk_1_1_mission_raw_1acca64e0a08978f5721be8fa955b1bb0f) (const [ResultCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a1a36a84f17dca07e1da49c13abbc9564) callback) | Start the mission. [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf) | [start_mission](#classmavsdk_1_1_mission_raw_1af1b010b0f28b284a94eba88198ee15f8) () const | Start the mission. @@ -59,11 +65,11 @@ void | [set_current_mission_item_async](#classmavsdk_1_1_mission_raw_1a5540d6ca6 [MissionProgressHandle](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a34e0eaf9922daa5d27d2b044eae7885c) | [subscribe_mission_progress](#classmavsdk_1_1_mission_raw_1a88a3c4b26418e734a547f251706988d2) (const [MissionProgressCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a9dd594878925da494b4add6acc3184fc) & callback) | Subscribe to mission progress updates. void | [unsubscribe_mission_progress](#classmavsdk_1_1_mission_raw_1ac46f08b52706f45956cf3b01df381835) ([MissionProgressHandle](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a34e0eaf9922daa5d27d2b044eae7885c) handle) | Unsubscribe from subscribe_mission_progress. [MissionProgress](structmavsdk_1_1_mission_raw_1_1_mission_progress.md) | [mission_progress](#classmavsdk_1_1_mission_raw_1a3200dea1094926a4dd54f079f21b94e1) () const | Poll for '[MissionProgress](structmavsdk_1_1_mission_raw_1_1_mission_progress.md)' (blocking). -[MissionChangedHandle](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a46da6d8a53822fd5fbd7b2a414624c5c) | [subscribe_mission_changed](#classmavsdk_1_1_mission_raw_1ad4a2991e1a8f9423270af4220309edfb) (const [MissionChangedCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1ac22d81eefc5e883cdb6baf792a7487e6) & callback) |
  • Subscribes to mission changed.

+[MissionChangedHandle](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a46da6d8a53822fd5fbd7b2a414624c5c) | [subscribe_mission_changed](#classmavsdk_1_1_mission_raw_1ad4a2991e1a8f9423270af4220309edfb) (const [MissionChangedCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1ac22d81eefc5e883cdb6baf792a7487e6) & callback) | Subscribes to mission changed. void | [unsubscribe_mission_changed](#classmavsdk_1_1_mission_raw_1ac6cd7602b2e5b46ad0ea1cf8bf602a0c) ([MissionChangedHandle](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a46da6d8a53822fd5fbd7b2a414624c5c) handle) | Unsubscribe from subscribe_mission_changed. -std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), [MissionRaw::MissionImportData](structmavsdk_1_1_mission_raw_1_1_mission_import_data.md) > | [import_qgroundcontrol_mission](#classmavsdk_1_1_mission_raw_1a43345b21cf9dedf594f62ec7ad963ce8) (std::string qgc_plan_path)const | Import a QGroundControl missions in JSON .plan format, from a file. -std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), [MissionRaw::MissionImportData](structmavsdk_1_1_mission_raw_1_1_mission_import_data.md) > | [import_qgroundcontrol_mission_from_string](#classmavsdk_1_1_mission_raw_1ab0a0d18b65beced6112b2f27556fae37) (std::string qgc_plan)const | Import a QGroundControl missions in JSON .plan format, from a string. -const [MissionRaw](classmavsdk_1_1_mission_raw.md) & | [operator=](#classmavsdk_1_1_mission_raw_1a0cfdf21bad5478c91cf18207b6a21ad3) (const [MissionRaw](classmavsdk_1_1_mission_raw.md) &)=delete | Equality operator (object is not copyable). +std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), [MissionRaw::MissionImportData](structmavsdk_1_1_mission_raw_1_1_mission_import_data.md) > | [import_qgroundcontrol_mission](#classmavsdk_1_1_mission_raw_1a2a4ca261c37737e691c6954693d6d0a5) (std::string qgc_plan_path)const | Import a QGroundControl missions in JSON .plan format, from a file. +std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), [MissionRaw::MissionImportData](structmavsdk_1_1_mission_raw_1_1_mission_import_data.md) > | [import_qgroundcontrol_mission_from_string](#classmavsdk_1_1_mission_raw_1a4a1b55650120d8af0ce7fa037f6b5ce9) (std::string qgc_plan)const | Import a QGroundControl missions in JSON .plan format, from a string. +const [MissionRaw](classmavsdk_1_1_mission_raw.md) & | [operator=](#classmavsdk_1_1_mission_raw_1a2b8cdc1fbee72224a9ef6eb9266b2e2a) (const [MissionRaw](classmavsdk_1_1_mission_raw.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -150,6 +156,26 @@ using mavsdk::MissionRaw::DownloadMissionCallback = std::function)> +``` + + +Callback type for download_geofence_async. + + +### typedef DownloadRallypointsCallback {#classmavsdk_1_1_mission_raw_1a473abce54f89efe05d5ac051c9d8a5dc} + +```cpp +using mavsdk::MissionRaw::DownloadRallypointsCallback = std::function)> +``` + + +Callback type for download_rallypoints_async. + + ### typedef MissionProgressCallback {#classmavsdk_1_1_mission_raw_1a9dd594878925da494b4add6acc3184fc} ```cpp @@ -357,9 +383,9 @@ This function is non-blocking. See 'download_mission' for the blocking counterpa * const [DownloadMissionCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a016633e6338744da02ac7cb6da28880a) **callback** - -### download_mission() {#classmavsdk_1_1_mission_raw_1a2cc470785c486d1b7fdaaa2e3fbff809} +### download_mission() {#classmavsdk_1_1_mission_raw_1a18138bc7cbc6c6c16fde44e2fa53a459} ```cpp -std::pair > mavsdk::MissionRaw::download_mission() const +std::pair< Result, std::vector< MissionRaw::MissionItem > > mavsdk::MissionRaw::download_mission() const ``` @@ -371,6 +397,62 @@ This function is blocking. See 'download_mission_async' for the non-blocking cou  std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > - Result of request. +### download_geofence_async() {#classmavsdk_1_1_mission_raw_1acc681495c318043334691ab9ccd6778d} +```cpp +void mavsdk::MissionRaw::download_geofence_async(const DownloadGeofenceCallback callback) +``` + + +Download a list of raw geofence items from the system (asynchronous). + +This function is non-blocking. See 'download_geofence' for the blocking counterpart. + +**Parameters** + +* const [DownloadGeofenceCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a3e75d493ec08fec9d9faa597238c11be) **callback** - + +### download_geofence() {#classmavsdk_1_1_mission_raw_1ae2d3d743e00312e07ca3893ab27f0138} +```cpp +std::pair< Result, std::vector< MissionRaw::MissionItem > > mavsdk::MissionRaw::download_geofence() const +``` + + +Download a list of raw geofence items from the system (asynchronous). + +This function is blocking. See 'download_geofence_async' for the non-blocking counterpart. + +**Returns** + + std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > - Result of request. + +### download_rallypoints_async() {#classmavsdk_1_1_mission_raw_1a38e58cdecc1737936bec5d046c8eb511} +```cpp +void mavsdk::MissionRaw::download_rallypoints_async(const DownloadRallypointsCallback callback) +``` + + +Download a list of raw rallypoint items from the system (asynchronous). + +This function is non-blocking. See 'download_rallypoints' for the blocking counterpart. + +**Parameters** + +* const [DownloadRallypointsCallback](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a473abce54f89efe05d5ac051c9d8a5dc) **callback** - + +### download_rallypoints() {#classmavsdk_1_1_mission_raw_1a0cb3895f91bb2042c9d3282b09c442af} +```cpp +std::pair< Result, std::vector< MissionRaw::MissionItem > > mavsdk::MissionRaw::download_rallypoints() const +``` + + +Download a list of raw rallypoint items from the system (asynchronous). + +This function is blocking. See 'download_rallypoints_async' for the non-blocking counterpart. + +**Returns** + + std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), std::vector< [MissionRaw::MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) > > - Result of request. + ### cancel_mission_download() {#classmavsdk_1_1_mission_raw_1a7c554999ca66c5434ef1fa334d949e5a} ```cpp Result mavsdk::MissionRaw::cancel_mission_download() const @@ -569,10 +651,7 @@ MissionChangedHandle mavsdk::MissionRaw::subscribe_mission_changed(const Mission ``` -
    -
  • Subscribes to mission changed.

    -
  • -
+Subscribes to mission changed. This notification can be used to be informed if a ground station has been uploaded or changed by a ground station or companion computer. @@ -597,9 +676,9 @@ Unsubscribe from subscribe_mission_changed. * [MissionChangedHandle](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a46da6d8a53822fd5fbd7b2a414624c5c) **handle** - -### import_qgroundcontrol_mission() {#classmavsdk_1_1_mission_raw_1a43345b21cf9dedf594f62ec7ad963ce8} +### import_qgroundcontrol_mission() {#classmavsdk_1_1_mission_raw_1a2a4ca261c37737e691c6954693d6d0a5} ```cpp -std::pair mavsdk::MissionRaw::import_qgroundcontrol_mission(std::string qgc_plan_path) const +std::pair< Result, MissionRaw::MissionImportData > mavsdk::MissionRaw::import_qgroundcontrol_mission(std::string qgc_plan_path) const ``` @@ -626,9 +705,9 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), [MissionRaw::MissionImportData](structmavsdk_1_1_mission_raw_1_1_mission_import_data.md) > - Result of request. -### import_qgroundcontrol_mission_from_string() {#classmavsdk_1_1_mission_raw_1ab0a0d18b65beced6112b2f27556fae37} +### import_qgroundcontrol_mission_from_string() {#classmavsdk_1_1_mission_raw_1a4a1b55650120d8af0ce7fa037f6b5ce9} ```cpp -std::pair mavsdk::MissionRaw::import_qgroundcontrol_mission_from_string(std::string qgc_plan) const +std::pair< Result, MissionRaw::MissionImportData > mavsdk::MissionRaw::import_qgroundcontrol_mission_from_string(std::string qgc_plan) const ``` @@ -655,9 +734,9 @@ This function is blocking.  std::pair< [Result](classmavsdk_1_1_mission_raw.md#classmavsdk_1_1_mission_raw_1a7ea2a624818ebb5a3e209cc275d58eaf), [MissionRaw::MissionImportData](structmavsdk_1_1_mission_raw_1_1_mission_import_data.md) > - Result of request. -### operator=() {#classmavsdk_1_1_mission_raw_1a0cfdf21bad5478c91cf18207b6a21ad3} +### operator=() {#classmavsdk_1_1_mission_raw_1a2b8cdc1fbee72224a9ef6eb9266b2e2a} ```cpp -const MissionRaw& mavsdk::MissionRaw::operator=(const MissionRaw &)=delete +const MissionRaw & mavsdk::MissionRaw::operator=(const MissionRaw &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw_server.md index 0630db869c..616f1aec8b 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw_server.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mission_raw_server.md @@ -40,15 +40,12 @@ Type | Name | Description   | [MissionRawServer](#classmavsdk_1_1_mission_raw_server_1a14b11b78ba44bdda6fb718ed13e1ab77) (const [MissionRawServer](classmavsdk_1_1_mission_raw_server.md) & other) | Copy constructor. [IncomingMissionHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a71173397d112f738fd05014ccc0952ff) | [subscribe_incoming_mission](#classmavsdk_1_1_mission_raw_server_1aede616f945d7c59d2da6afad830f377b) (const [IncomingMissionCallback](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1ac8bb83c581ff08945314e51973728693) & callback) | Subscribe to when a new mission is uploaded (asynchronous). void | [unsubscribe_incoming_mission](#classmavsdk_1_1_mission_raw_server_1a93107d6ee73d03edc0050401c5a5f169) ([IncomingMissionHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a71173397d112f738fd05014ccc0952ff) handle) | Unsubscribe from subscribe_incoming_mission. -[MissionPlan](structmavsdk_1_1_mission_raw_server_1_1_mission_plan.md) | [incoming_mission](#classmavsdk_1_1_mission_raw_server_1ae7c20d621170e5454953513526241577) () const | Poll for '[MissionPlan](structmavsdk_1_1_mission_raw_server_1_1_mission_plan.md)' (blocking). [CurrentItemChangedHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a490cab4b8b06fd5d6eb8e759427f5b47) | [subscribe_current_item_changed](#classmavsdk_1_1_mission_raw_server_1a287af1e5ca18de2e84345b4f5f8fa386) (const [CurrentItemChangedCallback](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1aca7ac64b6e39e612d05ff6497cd572b1) & callback) | Subscribe to when a new current item is set. void | [unsubscribe_current_item_changed](#classmavsdk_1_1_mission_raw_server_1a8c693a86be890f78a5a10cee9a36dc6c) ([CurrentItemChangedHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a490cab4b8b06fd5d6eb8e759427f5b47) handle) | Unsubscribe from subscribe_current_item_changed. -[MissionItem](structmavsdk_1_1_mission_raw_server_1_1_mission_item.md) | [current_item_changed](#classmavsdk_1_1_mission_raw_server_1af2bbab99a8a2e1dd1dfebceb439f2ad1) () const | Poll for '[MissionItem](structmavsdk_1_1_mission_raw_server_1_1_mission_item.md)' (blocking). void | [set_current_item_complete](#classmavsdk_1_1_mission_raw_server_1a496791a14c2bdc1e9917f5d04622330a) () const | Set Current item as completed. [ClearAllHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a59022e22386a18e9d51f88e6ed3cf120) | [subscribe_clear_all](#classmavsdk_1_1_mission_raw_server_1a9b08ba6c1607618e67fd1ec723883415) (const [ClearAllCallback](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1ae9d7d9d863d1552274440d091e2ec869) & callback) | Subscribe when a MISSION_CLEAR_ALL is received. void | [unsubscribe_clear_all](#classmavsdk_1_1_mission_raw_server_1af337c8126b52d78436605a3b2e558397) ([ClearAllHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a59022e22386a18e9d51f88e6ed3cf120) handle) | Unsubscribe from subscribe_clear_all. -uint32_t | [clear_all](#classmavsdk_1_1_mission_raw_server_1a307e0f39d704ae9aeb227a27092bf435) () const | Poll for 'uint32_t' (blocking). -const [MissionRawServer](classmavsdk_1_1_mission_raw_server.md) & | [operator=](#classmavsdk_1_1_mission_raw_server_1aad0690db8cec599b271d4f62e8ecd975) (const [MissionRawServer](classmavsdk_1_1_mission_raw_server.md) &)=delete | Equality operator (object is not copyable). +const [MissionRawServer](classmavsdk_1_1_mission_raw_server.md) & | [operator=](#classmavsdk_1_1_mission_raw_server_1a9d589d816286937b2c9c5d29451f0f91) (const [MissionRawServer](classmavsdk_1_1_mission_raw_server.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -225,19 +222,6 @@ Unsubscribe from subscribe_incoming_mission. * [IncomingMissionHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a71173397d112f738fd05014ccc0952ff) **handle** - -### incoming_mission() {#classmavsdk_1_1_mission_raw_server_1ae7c20d621170e5454953513526241577} -```cpp -MissionPlan mavsdk::MissionRawServer::incoming_mission() const -``` - - -Poll for '[MissionPlan](structmavsdk_1_1_mission_raw_server_1_1_mission_plan.md)' (blocking). - - -**Returns** - - [MissionPlan](structmavsdk_1_1_mission_raw_server_1_1_mission_plan.md) - One [MissionPlan](structmavsdk_1_1_mission_raw_server_1_1_mission_plan.md) update. - ### subscribe_current_item_changed() {#classmavsdk_1_1_mission_raw_server_1a287af1e5ca18de2e84345b4f5f8fa386} ```cpp CurrentItemChangedHandle mavsdk::MissionRawServer::subscribe_current_item_changed(const CurrentItemChangedCallback &callback) @@ -268,19 +252,6 @@ Unsubscribe from subscribe_current_item_changed. * [CurrentItemChangedHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a490cab4b8b06fd5d6eb8e759427f5b47) **handle** - -### current_item_changed() {#classmavsdk_1_1_mission_raw_server_1af2bbab99a8a2e1dd1dfebceb439f2ad1} -```cpp -MissionItem mavsdk::MissionRawServer::current_item_changed() const -``` - - -Poll for '[MissionItem](structmavsdk_1_1_mission_raw_server_1_1_mission_item.md)' (blocking). - - -**Returns** - - [MissionItem](structmavsdk_1_1_mission_raw_server_1_1_mission_item.md) - One [MissionItem](structmavsdk_1_1_mission_raw_server_1_1_mission_item.md) update. - ### set_current_item_complete() {#classmavsdk_1_1_mission_raw_server_1a496791a14c2bdc1e9917f5d04622330a} ```cpp void mavsdk::MissionRawServer::set_current_item_complete() const @@ -321,22 +292,9 @@ Unsubscribe from subscribe_clear_all. * [ClearAllHandle](classmavsdk_1_1_mission_raw_server.md#classmavsdk_1_1_mission_raw_server_1a59022e22386a18e9d51f88e6ed3cf120) **handle** - -### clear_all() {#classmavsdk_1_1_mission_raw_server_1a307e0f39d704ae9aeb227a27092bf435} -```cpp -uint32_t mavsdk::MissionRawServer::clear_all() const -``` - - -Poll for 'uint32_t' (blocking). - - -**Returns** - - uint32_t - One uint32_t update. - -### operator=() {#classmavsdk_1_1_mission_raw_server_1aad0690db8cec599b271d4f62e8ecd975} +### operator=() {#classmavsdk_1_1_mission_raw_server_1a9d589d816286937b2c9c5d29451f0f91} ```cpp -const MissionRawServer& mavsdk::MissionRawServer::operator=(const MissionRawServer &)=delete +const MissionRawServer & mavsdk::MissionRawServer::operator=(const MissionRawServer &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_mocap.md b/docs/en/cpp/api_reference/classmavsdk_1_1_mocap.md index 4861cb401c..55ca24a246 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_mocap.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_mocap.md @@ -4,10 +4,7 @@ ---- -
    -
  • Allows interfacing a vehicle with a motion capture system in order to allow navigation without global positioning sources available (e.g. indoors, or when flying under a bridge. etc.).

    -
  • -
+Allows interfacing a vehicle with a motion capture system in order to allow navigation without global positioning sources available (e.g. indoors, or when flying under a bridge. etc.). ## Data Structures @@ -51,7 +48,7 @@ Type | Name | Description [Result](classmavsdk_1_1_mocap.md#classmavsdk_1_1_mocap_1a3af8c27b8ad9a4567feb1045e82884d5) | [set_vision_position_estimate](#classmavsdk_1_1_mocap_1a22d007409839e28a45d7b10f10e22fd6) ([VisionPositionEstimate](structmavsdk_1_1_mocap_1_1_vision_position_estimate.md) vision_position_estimate)const | Send Global position/attitude estimate from a vision source. [Result](classmavsdk_1_1_mocap.md#classmavsdk_1_1_mocap_1a3af8c27b8ad9a4567feb1045e82884d5) | [set_attitude_position_mocap](#classmavsdk_1_1_mocap_1a5f9a63d8bbed750056e139640b38cd7f) ([AttitudePositionMocap](structmavsdk_1_1_mocap_1_1_attitude_position_mocap.md) attitude_position_mocap)const | Send motion capture attitude and position. [Result](classmavsdk_1_1_mocap.md#classmavsdk_1_1_mocap_1a3af8c27b8ad9a4567feb1045e82884d5) | [set_odometry](#classmavsdk_1_1_mocap_1a149fa242e0b01bc0aee9204118b00f59) ([Odometry](structmavsdk_1_1_mocap_1_1_odometry.md) odometry)const | Send odometry information with an external interface. -const [Mocap](classmavsdk_1_1_mocap.md) & | [operator=](#classmavsdk_1_1_mocap_1adf2f33e3befbec23f43e066946050eab) (const [Mocap](classmavsdk_1_1_mocap.md) &)=delete | Equality operator (object is not copyable). +const [Mocap](classmavsdk_1_1_mocap.md) & | [operator=](#classmavsdk_1_1_mocap_1afb0d68876155a6990317b3b620f018f7) (const [Mocap](classmavsdk_1_1_mocap.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -203,9 +200,9 @@ This function is blocking.  [Result](classmavsdk_1_1_mocap.md#classmavsdk_1_1_mocap_1a3af8c27b8ad9a4567feb1045e82884d5) - Result of request. -### operator=() {#classmavsdk_1_1_mocap_1adf2f33e3befbec23f43e066946050eab} +### operator=() {#classmavsdk_1_1_mocap_1afb0d68876155a6990317b3b620f018f7} ```cpp -const Mocap& mavsdk::Mocap::operator=(const Mocap &)=delete +const Mocap & mavsdk::Mocap::operator=(const Mocap &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_offboard.md b/docs/en/cpp/api_reference/classmavsdk_1_1_offboard.md index 935fdcfdbd..792b9c84ee 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_offboard.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_offboard.md @@ -4,10 +4,7 @@ ---- -
    -
  • Control a drone with position, velocity, attitude or motor commands.

    -
  • -
+Control a drone with position, velocity, attitude or motor commands. The module is called offboard because the commands can be sent from external sources as opposed to onboard control right inside the autopilot "board". @@ -69,7 +66,7 @@ bool | [is_active](#classmavsdk_1_1_offboard_1aa5e0f3c02a03f2667f82d5e162221ff5) [Result](classmavsdk_1_1_offboard.md#classmavsdk_1_1_offboard_1a2d4d594301d8c756429457b0982130e9) | [set_position_velocity_ned](#classmavsdk_1_1_offboard_1ae422165680b434eed74e84cc901e3a33) ([PositionNedYaw](structmavsdk_1_1_offboard_1_1_position_ned_yaw.md) position_ned_yaw, [VelocityNedYaw](structmavsdk_1_1_offboard_1_1_velocity_ned_yaw.md) velocity_ned_yaw)const | Set the position in NED coordinates, with the velocity to be used as feed-forward. [Result](classmavsdk_1_1_offboard.md#classmavsdk_1_1_offboard_1a2d4d594301d8c756429457b0982130e9) | [set_position_velocity_acceleration_ned](#classmavsdk_1_1_offboard_1a845aab746fc078d1ee2848df33c04eb9) ([PositionNedYaw](structmavsdk_1_1_offboard_1_1_position_ned_yaw.md) position_ned_yaw, [VelocityNedYaw](structmavsdk_1_1_offboard_1_1_velocity_ned_yaw.md) velocity_ned_yaw, [AccelerationNed](structmavsdk_1_1_offboard_1_1_acceleration_ned.md) acceleration_ned)const | Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward. [Result](classmavsdk_1_1_offboard.md#classmavsdk_1_1_offboard_1a2d4d594301d8c756429457b0982130e9) | [set_acceleration_ned](#classmavsdk_1_1_offboard_1ac0d471609df13c79a37e0e352be71d03) ([AccelerationNed](structmavsdk_1_1_offboard_1_1_acceleration_ned.md) acceleration_ned)const | Set the acceleration in NED coordinates. -const [Offboard](classmavsdk_1_1_offboard.md) & | [operator=](#classmavsdk_1_1_offboard_1acb01657624668251c0a022bc3f8135cd) (const [Offboard](classmavsdk_1_1_offboard.md) &)=delete | Equality operator (object is not copyable). +const [Offboard](classmavsdk_1_1_offboard.md) & | [operator=](#classmavsdk_1_1_offboard_1a69747733dbdc9b60a8b37006674eda53) (const [Offboard](classmavsdk_1_1_offboard.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -435,9 +432,9 @@ This function is blocking.  [Result](classmavsdk_1_1_offboard.md#classmavsdk_1_1_offboard_1a2d4d594301d8c756429457b0982130e9) - Result of request. -### operator=() {#classmavsdk_1_1_offboard_1acb01657624668251c0a022bc3f8135cd} +### operator=() {#classmavsdk_1_1_offboard_1a69747733dbdc9b60a8b37006674eda53} ```cpp -const Offboard& mavsdk::Offboard::operator=(const Offboard &)=delete +const Offboard & mavsdk::Offboard::operator=(const Offboard &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_param.md b/docs/en/cpp/api_reference/classmavsdk_1_1_param.md index 140524eb47..70d63f148d 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_param.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_param.md @@ -36,15 +36,15 @@ Type | Name | Description   | [Param](#classmavsdk_1_1_param_1a08e40eaf4052555d28f2404cc7ede680) (std::shared_ptr< [System](classmavsdk_1_1_system.md) > system) | Constructor. Creates the plugin for a specific [System](classmavsdk_1_1_system.md).   | [~Param](#classmavsdk_1_1_param_1a33f67b5c3daea8ca3af8c573f4e07153) () override | Destructor (internal use only).   | [Param](#classmavsdk_1_1_param_1ab7a03a825118c944d31c562594826f72) (const [Param](classmavsdk_1_1_param.md) & other) | Copy constructor. -std::pair< [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df), int32_t > | [get_param_int](#classmavsdk_1_1_param_1a554099a07baa9e4765824005f47bef94) (std::string name)const | Get an int parameter. +std::pair< [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df), int32_t > | [get_param_int](#classmavsdk_1_1_param_1a23e4fe22bcef677fe9bb291a8f7d56c5) (std::string name)const | Get an int parameter. [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) | [set_param_int](#classmavsdk_1_1_param_1af8124bae8b4649605a51fe2943ae8414) (std::string name, int32_t value)const | Set an int parameter. -std::pair< [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df), float > | [get_param_float](#classmavsdk_1_1_param_1ac8efd0381aa1cc2e4461dfb256797619) (std::string name)const | Get a float parameter. +std::pair< [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df), float > | [get_param_float](#classmavsdk_1_1_param_1a3258e5ceec1bfaa2b0228786f197f4d3) (std::string name)const | Get a float parameter. [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) | [set_param_float](#classmavsdk_1_1_param_1a58a2f14fbcda2bf73815dbc2a31528bf) (std::string name, float value)const | Set a float parameter. -std::pair< [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df), std::string > | [get_param_custom](#classmavsdk_1_1_param_1a7914d3856a9e6d9b91d7f5483a260f4d) (std::string name)const | Get a custom parameter. +std::pair< [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df), std::string > | [get_param_custom](#classmavsdk_1_1_param_1a0fdcf7aee3324843ddd1638aa409a962) (std::string name)const | Get a custom parameter. [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) | [set_param_custom](#classmavsdk_1_1_param_1abb9cc4e4e14d33a93b23295f836de39e) (std::string name, std::string value)const | Set a custom parameter. [Param::AllParams](structmavsdk_1_1_param_1_1_all_params.md) | [get_all_params](#classmavsdk_1_1_param_1ab9259e1f91809aa574404131aa540fd8) () const | Get all parameters. [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) | [select_component](#classmavsdk_1_1_param_1a2ef2e607225d54c6fedd21a9b483937f) (int32_t component_id, [ProtocolVersion](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1a37807968ecb40a732b4fec83792bd5c8) protocol_version)const | Select component ID of parameter component to talk to and param protocol version. -const [Param](classmavsdk_1_1_param.md) & | [operator=](#classmavsdk_1_1_param_1a4d75b066cb985d3a38cc8221e18aa608) (const [Param](classmavsdk_1_1_param.md) &)=delete | Equality operator (object is not copyable). +const [Param](classmavsdk_1_1_param.md) & | [operator=](#classmavsdk_1_1_param_1ac66cb2c623da03454e0cee033c3a1514) (const [Param](classmavsdk_1_1_param.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -156,9 +156,9 @@ Value | Description ## Member Function Documentation -### get_param_int() {#classmavsdk_1_1_param_1a554099a07baa9e4765824005f47bef94} +### get_param_int() {#classmavsdk_1_1_param_1a23e4fe22bcef677fe9bb291a8f7d56c5} ```cpp -std::pair mavsdk::Param::get_param_int(std::string name) const +std::pair< Result, int32_t > mavsdk::Param::get_param_int(std::string name) const ``` @@ -199,9 +199,9 @@ This function is blocking.  [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) - Result of request. -### get_param_float() {#classmavsdk_1_1_param_1ac8efd0381aa1cc2e4461dfb256797619} +### get_param_float() {#classmavsdk_1_1_param_1a3258e5ceec1bfaa2b0228786f197f4d3} ```cpp -std::pair mavsdk::Param::get_param_float(std::string name) const +std::pair< Result, float > mavsdk::Param::get_param_float(std::string name) const ``` @@ -242,9 +242,9 @@ This function is blocking.  [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) - Result of request. -### get_param_custom() {#classmavsdk_1_1_param_1a7914d3856a9e6d9b91d7f5483a260f4d} +### get_param_custom() {#classmavsdk_1_1_param_1a0fdcf7aee3324843ddd1638aa409a962} ```cpp -std::pair mavsdk::Param::get_param_custom(std::string name) const +std::pair< Result, std::string > mavsdk::Param::get_param_custom(std::string name) const ``` @@ -321,9 +321,9 @@ This function is blocking.  [Result](classmavsdk_1_1_param.md#classmavsdk_1_1_param_1afde69c8b60c41e2f21db148d211881df) - Result of request. -### operator=() {#classmavsdk_1_1_param_1a4d75b066cb985d3a38cc8221e18aa608} +### operator=() {#classmavsdk_1_1_param_1ac66cb2c623da03454e0cee033c3a1514} ```cpp -const Param& mavsdk::Param::operator=(const Param &)=delete +const Param & mavsdk::Param::operator=(const Param &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_param_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_param_server.md index 0418fd6983..abd0b22d3b 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_param_server.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_param_server.md @@ -40,11 +40,12 @@ Type | Name | Description   | [ParamServer](#classmavsdk_1_1_param_server_1ae86996ca7c1cf57ae1d011ca5279d231) (std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > server_component) | Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance.   | [~ParamServer](#classmavsdk_1_1_param_server_1a0b221c28148f0278f063232059d372b5) () override | Destructor (internal use only).   | [ParamServer](#classmavsdk_1_1_param_server_1a4cffcb488093838f72414c94e6c40fd0) (const [ParamServer](classmavsdk_1_1_param_server.md) & other) | Copy constructor. -std::pair< [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469), int32_t > | [retrieve_param_int](#classmavsdk_1_1_param_server_1a95c445dbdd2b764248c811da0230b0b4) (std::string name)const | Retrieve an int parameter. +[Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) | [set_protocol](#classmavsdk_1_1_param_server_1a04dd88d5e06f4d7f184c4d8da296ba00) (bool extended_protocol)const | Set param protocol. +std::pair< [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469), int32_t > | [retrieve_param_int](#classmavsdk_1_1_param_server_1aba490929e68a2a280dd4637152ab45c1) (std::string name)const | Retrieve an int parameter. [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) | [provide_param_int](#classmavsdk_1_1_param_server_1a9de5dade4020eda7fb1cc07c6868dad1) (std::string name, int32_t value)const | Provide an int parameter. -std::pair< [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469), float > | [retrieve_param_float](#classmavsdk_1_1_param_server_1a2845916c07a7e47e7444a49f88b23320) (std::string name)const | Retrieve a float parameter. +std::pair< [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469), float > | [retrieve_param_float](#classmavsdk_1_1_param_server_1a4ad8adbaafa16f597e0141716dc440bd) (std::string name)const | Retrieve a float parameter. [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) | [provide_param_float](#classmavsdk_1_1_param_server_1a7893e4b00609eb0826835b3d8930db1f) (std::string name, float value)const | Provide a float parameter. -std::pair< [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469), std::string > | [retrieve_param_custom](#classmavsdk_1_1_param_server_1aa6564b8138bc66519f425a350265b50d) (std::string name)const | Retrieve a custom parameter. +std::pair< [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469), std::string > | [retrieve_param_custom](#classmavsdk_1_1_param_server_1a60ab665d721dce7ab910b8f0abbf7946) (std::string name)const | Retrieve a custom parameter. [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) | [provide_param_custom](#classmavsdk_1_1_param_server_1a60487de3470b9b1c39b403d4c9053d73) (std::string name, std::string value)const | Provide a custom parameter. [ParamServer::AllParams](structmavsdk_1_1_param_server_1_1_all_params.md) | [retrieve_all_params](#classmavsdk_1_1_param_server_1aaf6b3862213d415ff26730afad95565f) () const | Retrieve all parameters. [ChangedParamIntHandle](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a923f3ae88ca5614690f3b1b6e4eb259a) | [subscribe_changed_param_int](#classmavsdk_1_1_param_server_1ad022db97fe1c040d255ce8eeb98dcbf9) (const [ChangedParamIntCallback](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a7674183da6d76416b34df9ce51c59358) & callback) | Subscribe to changed int param. @@ -53,7 +54,7 @@ void | [unsubscribe_changed_param_int](#classmavsdk_1_1_param_server_1adea6bfaca void | [unsubscribe_changed_param_float](#classmavsdk_1_1_param_server_1a33796a9ecc396b905b51ad4d2ce7989b) ([ChangedParamFloatHandle](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a86b8aa9c92d3d6d7dd47fc9b8f0bf881) handle) | Unsubscribe from subscribe_changed_param_float. [ChangedParamCustomHandle](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a27cf0998ffff4bbdb3f00743b30c903f) | [subscribe_changed_param_custom](#classmavsdk_1_1_param_server_1a91d4aa280e7e0c43621ea87088781ccb) (const [ChangedParamCustomCallback](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1ada550af744c9125178f7ad74d3c1041a) & callback) | Subscribe to changed custom param. void | [unsubscribe_changed_param_custom](#classmavsdk_1_1_param_server_1aa78c8df43a9d4c2dbdb6516a04d5f2de) ([ChangedParamCustomHandle](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a27cf0998ffff4bbdb3f00743b30c903f) handle) | Unsubscribe from subscribe_changed_param_custom. -const [ParamServer](classmavsdk_1_1_param_server.md) & | [operator=](#classmavsdk_1_1_param_server_1a29ce1d2c4a2b80fbe4a0b7e7470e14af) (const [ParamServer](classmavsdk_1_1_param_server.md) &)=delete | Equality operator (object is not copyable). +const [ParamServer](classmavsdk_1_1_param_server.md) & | [operator=](#classmavsdk_1_1_param_server_1af919ccd34f6ada4ded2b9c84c448fffe) (const [ParamServer](classmavsdk_1_1_param_server.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -194,9 +195,33 @@ Value | Description ## Member Function Documentation -### retrieve_param_int() {#classmavsdk_1_1_param_server_1a95c445dbdd2b764248c811da0230b0b4} +### set_protocol() {#classmavsdk_1_1_param_server_1a04dd88d5e06f4d7f184c4d8da296ba00} ```cpp -std::pair mavsdk::ParamServer::retrieve_param_int(std::string name) const +Result mavsdk::ParamServer::set_protocol(bool extended_protocol) const +``` + + +Set param protocol. + +The extended param protocol is used by default. This allows to use the previous/normal one. + + +Note that camera definition files are meant to implement/use the extended protocol. + + +This function is blocking. + +**Parameters** + +* bool **extended_protocol** - + +**Returns** + + [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) - Result of request. + +### retrieve_param_int() {#classmavsdk_1_1_param_server_1aba490929e68a2a280dd4637152ab45c1} +```cpp +std::pair< Result, int32_t > mavsdk::ParamServer::retrieve_param_int(std::string name) const ``` @@ -237,9 +262,9 @@ This function is blocking.  [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) - Result of request. -### retrieve_param_float() {#classmavsdk_1_1_param_server_1a2845916c07a7e47e7444a49f88b23320} +### retrieve_param_float() {#classmavsdk_1_1_param_server_1a4ad8adbaafa16f597e0141716dc440bd} ```cpp -std::pair mavsdk::ParamServer::retrieve_param_float(std::string name) const +std::pair< Result, float > mavsdk::ParamServer::retrieve_param_float(std::string name) const ``` @@ -280,9 +305,9 @@ This function is blocking.  [Result](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a6f7fcc017f43dcf68837dbc35ee4f469) - Result of request. -### retrieve_param_custom() {#classmavsdk_1_1_param_server_1aa6564b8138bc66519f425a350265b50d} +### retrieve_param_custom() {#classmavsdk_1_1_param_server_1a60ab665d721dce7ab910b8f0abbf7946} ```cpp -std::pair mavsdk::ParamServer::retrieve_param_custom(std::string name) const +std::pair< Result, std::string > mavsdk::ParamServer::retrieve_param_custom(std::string name) const ``` @@ -427,9 +452,9 @@ Unsubscribe from subscribe_changed_param_custom. * [ChangedParamCustomHandle](classmavsdk_1_1_param_server.md#classmavsdk_1_1_param_server_1a27cf0998ffff4bbdb3f00743b30c903f) **handle** - -### operator=() {#classmavsdk_1_1_param_server_1a29ce1d2c4a2b80fbe4a0b7e7470e14af} +### operator=() {#classmavsdk_1_1_param_server_1af919ccd34f6ada4ded2b9c84c448fffe} ```cpp -const ParamServer& mavsdk::ParamServer::operator=(const ParamServer &)=delete +const ParamServer & mavsdk::ParamServer::operator=(const ParamServer &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_plugin_base.md b/docs/en/cpp/api_reference/classmavsdk_1_1_plugin_base.md index b1a18f4d78..c5d985a9b3 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_plugin_base.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_plugin_base.md @@ -15,7 +15,7 @@ Type | Name | Description   | [PluginBase](#classmavsdk_1_1_plugin_base_1afbb5a017df6856e58fb576d65a9fe207) ()=default | Default Constructor.   | [~PluginBase](#classmavsdk_1_1_plugin_base_1a038befc8f15d34e0be17ec7df8e9d092) ()=default | Default Destructor.   | [PluginBase](#classmavsdk_1_1_plugin_base_1a717e8eda4a615730256f4a707f00aa72) (const [PluginBase](classmavsdk_1_1_plugin_base.md) &)=delete | Copy constructor (object is not copyable). -const [PluginBase](classmavsdk_1_1_plugin_base.md) & | [operator=](#classmavsdk_1_1_plugin_base_1a7336d48f2784ef2ffe284ee2aaea3063) (const [PluginBase](classmavsdk_1_1_plugin_base.md) &)=delete | Assign operator (object is not copyable). +const [PluginBase](classmavsdk_1_1_plugin_base.md) & | [operator=](#classmavsdk_1_1_plugin_base_1a4f60b8eb315861e418e265ceba9a7a9e) (const [PluginBase](classmavsdk_1_1_plugin_base.md) &)=delete | Assign operator (object is not copyable). ## Constructor & Destructor Documentation @@ -55,9 +55,9 @@ Copy constructor (object is not copyable). ## Member Function Documentation -### operator=() {#classmavsdk_1_1_plugin_base_1a7336d48f2784ef2ffe284ee2aaea3063} +### operator=() {#classmavsdk_1_1_plugin_base_1a4f60b8eb315861e418e265ceba9a7a9e} ```cpp -const PluginBase& mavsdk::PluginBase::operator=(const PluginBase &)=delete +const PluginBase & mavsdk::PluginBase::operator=(const PluginBase &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_rtk.md b/docs/en/cpp/api_reference/classmavsdk_1_1_rtk.md index b0dc970fd3..3f4078aeeb 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_rtk.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_rtk.md @@ -30,7 +30,7 @@ Type | Name | Description   | [~Rtk](#classmavsdk_1_1_rtk_1a008724fb2e96cb9a96024f38130c6213) () override | Destructor (internal use only).   | [Rtk](#classmavsdk_1_1_rtk_1af9118d75e7ef85846bcf7a637d8df73c) (const [Rtk](classmavsdk_1_1_rtk.md) & other) | Copy constructor. [Result](classmavsdk_1_1_rtk.md#classmavsdk_1_1_rtk_1a7e310a6ab3cfc82efb46e238bc918a94) | [send_rtcm_data](#classmavsdk_1_1_rtk_1ab0f183ba8e57944e6f9d383f51490d09) ([RtcmData](structmavsdk_1_1_rtk_1_1_rtcm_data.md) rtcm_data)const | Send RTCM data. -const [Rtk](classmavsdk_1_1_rtk.md) & | [operator=](#classmavsdk_1_1_rtk_1a8d4c39419257c0df20b55aa7b838ecb2) (const [Rtk](classmavsdk_1_1_rtk.md) &)=delete | Equality operator (object is not copyable). +const [Rtk](classmavsdk_1_1_rtk.md) & | [operator=](#classmavsdk_1_1_rtk_1aeb2a7981da98ddffe9ce095ff3846ac8) (const [Rtk](classmavsdk_1_1_rtk.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -145,9 +145,9 @@ This function is blocking.  [Result](classmavsdk_1_1_rtk.md#classmavsdk_1_1_rtk_1a7e310a6ab3cfc82efb46e238bc918a94) - Result of request. -### operator=() {#classmavsdk_1_1_rtk_1a8d4c39419257c0df20b55aa7b838ecb2} +### operator=() {#classmavsdk_1_1_rtk_1aeb2a7981da98ddffe9ce095ff3846ac8} ```cpp -const Rtk& mavsdk::Rtk::operator=(const Rtk &)=delete +const Rtk & mavsdk::Rtk::operator=(const Rtk &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_server_component.md b/docs/en/cpp/api_reference/classmavsdk_1_1_server_component.md index 8252e62076..aa014a7386 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_server_component.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_server_component.md @@ -14,6 +14,7 @@ Type | Name | Description ---: | --- | ---   | [~ServerComponent](#classmavsdk_1_1_server_component_1aa93dd133c0c5476bfd9269365e4afcec) ()=default | Destructor. uint8_t | [component_id](#classmavsdk_1_1_server_component_1af05efb79ba6c1ed9992e13671d3268ba) () const | MAVLink component ID of this component. +void | [set_system_status](#classmavsdk_1_1_server_component_1a61a231624bbeacc4b7f5f98eb052b7e6) (uint8_t system_status) | Set system status of this MAVLink entity. ## Constructor & Destructor Documentation @@ -42,4 +43,18 @@ MAVLink component ID of this component. **Returns** - uint8_t - \ No newline at end of file + uint8_t - + +### set_system_status() {#classmavsdk_1_1_server_component_1a61a231624bbeacc4b7f5f98eb052b7e6} +```cpp +void mavsdk::ServerComponent::set_system_status(uint8_t system_status) +``` + + +Set system status of this MAVLink entity. + +The default system status is MAV_STATE_UNINIT. + +**Parameters** + +* uint8_t **system_status** - system status. \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_server_plugin_base.md b/docs/en/cpp/api_reference/classmavsdk_1_1_server_plugin_base.md index 7e71da7dd3..6fabbffb67 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_server_plugin_base.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_server_plugin_base.md @@ -15,7 +15,7 @@ Type | Name | Description   | [ServerPluginBase](#classmavsdk_1_1_server_plugin_base_1a77b7c74e4e2a10cf55071e95b53eedae) ()=default | Default Constructor.   | [~ServerPluginBase](#classmavsdk_1_1_server_plugin_base_1a97e1d14c2b72253d53f9284621b1d248) ()=default | Default Destructor.   | [ServerPluginBase](#classmavsdk_1_1_server_plugin_base_1a86ef071b10d0afc7d287069ac8d11575) (const [ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) &)=delete | Copy constructor (object is not copyable). -const [ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) & | [operator=](#classmavsdk_1_1_server_plugin_base_1ab424dcb3a08fcb7159ca326361548301) (const [ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) &)=delete | Assign operator (object is not copyable). +const [ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) & | [operator=](#classmavsdk_1_1_server_plugin_base_1a2b3d42760fa4b0edd07caae73e3e5f46) (const [ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) &)=delete | Assign operator (object is not copyable). ## Constructor & Destructor Documentation @@ -55,9 +55,9 @@ Copy constructor (object is not copyable). ## Member Function Documentation -### operator=() {#classmavsdk_1_1_server_plugin_base_1ab424dcb3a08fcb7159ca326361548301} +### operator=() {#classmavsdk_1_1_server_plugin_base_1a2b3d42760fa4b0edd07caae73e3e5f46} ```cpp -const ServerPluginBase& mavsdk::ServerPluginBase::operator=(const ServerPluginBase &)=delete +const ServerPluginBase & mavsdk::ServerPluginBase::operator=(const ServerPluginBase &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_server_utility.md b/docs/en/cpp/api_reference/classmavsdk_1_1_server_utility.md index 7c3adee2cf..95203ed3b7 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_server_utility.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_server_utility.md @@ -26,7 +26,7 @@ Type | Name | Description   | [~ServerUtility](#classmavsdk_1_1_server_utility_1a3f5fe15b02bcf41520a94feb2fc51fce) () override | Destructor (internal use only).   | [ServerUtility](#classmavsdk_1_1_server_utility_1a9cbd0e7b1b19b21d98ce7e914ea03f95) (const [ServerUtility](classmavsdk_1_1_server_utility.md) & other) | Copy constructor. [Result](classmavsdk_1_1_server_utility.md#classmavsdk_1_1_server_utility_1accdda519179f5fc6fe946a727f75f468) | [send_status_text](#classmavsdk_1_1_server_utility_1a7b7bb0b568e94575615086a86a625ae1) ([StatusTextType](classmavsdk_1_1_server_utility.md#classmavsdk_1_1_server_utility_1a763ddc41251f992acec6af7f19287233) type, std::string text)const | Sends a statustext. -const [ServerUtility](classmavsdk_1_1_server_utility.md) & | [operator=](#classmavsdk_1_1_server_utility_1a11fcb91df55711ecb78d8687b1d47472) (const [ServerUtility](classmavsdk_1_1_server_utility.md) &)=delete | Equality operator (object is not copyable). +const [ServerUtility](classmavsdk_1_1_server_utility.md) & | [operator=](#classmavsdk_1_1_server_utility_1a164070f95b448b4b6e43bffaaa559ba8) (const [ServerUtility](classmavsdk_1_1_server_utility.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -159,9 +159,9 @@ This function is blocking.  [Result](classmavsdk_1_1_server_utility.md#classmavsdk_1_1_server_utility_1accdda519179f5fc6fe946a727f75f468) - Result of request. -### operator=() {#classmavsdk_1_1_server_utility_1a11fcb91df55711ecb78d8687b1d47472} +### operator=() {#classmavsdk_1_1_server_utility_1a164070f95b448b4b6e43bffaaa559ba8} ```cpp -const ServerUtility& mavsdk::ServerUtility::operator=(const ServerUtility &)=delete +const ServerUtility & mavsdk::ServerUtility::operator=(const ServerUtility &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_shell.md b/docs/en/cpp/api_reference/classmavsdk_1_1_shell.md index fbc49b6295..fd23db43ba 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_shell.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_shell.md @@ -4,10 +4,7 @@ ---- -
    -
  • Allow to communicate with the vehicle's system shell.

    -
  • -
+Allow to communicate with the vehicle's system shell. ## Public Types @@ -32,7 +29,7 @@ Type | Name | Description [Result](classmavsdk_1_1_shell.md#classmavsdk_1_1_shell_1a768bfa296ba3309f936f887fb86c9ba8) | [send](#classmavsdk_1_1_shell_1a7b39022ce3be914eec82b53a76d19bc7) (std::string command)const | Send a command line. [ReceiveHandle](classmavsdk_1_1_shell.md#classmavsdk_1_1_shell_1aea7ab47a9a86aa3f91e71306cc9b430b) | [subscribe_receive](#classmavsdk_1_1_shell_1a2794ac389f4df4f1aaa344612bc8c470) (const [ReceiveCallback](classmavsdk_1_1_shell.md#classmavsdk_1_1_shell_1adfa64ede96967ae1ab5a5ecd83032dbb) & callback) | Receive feedback from a sent command line. void | [unsubscribe_receive](#classmavsdk_1_1_shell_1a5b696e1651459dbc3ceef2a393af433d) ([ReceiveHandle](classmavsdk_1_1_shell.md#classmavsdk_1_1_shell_1aea7ab47a9a86aa3f91e71306cc9b430b) handle) | Unsubscribe from subscribe_receive. -const [Shell](classmavsdk_1_1_shell.md) & | [operator=](#classmavsdk_1_1_shell_1a492f8b2e36ef2468522bfd0f51f4b9b8) (const [Shell](classmavsdk_1_1_shell.md) &)=delete | Equality operator (object is not copyable). +const [Shell](classmavsdk_1_1_shell.md) & | [operator=](#classmavsdk_1_1_shell_1abd920b11e6535152ad85cb4187b0c620) (const [Shell](classmavsdk_1_1_shell.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -199,9 +196,9 @@ Unsubscribe from subscribe_receive. * [ReceiveHandle](classmavsdk_1_1_shell.md#classmavsdk_1_1_shell_1aea7ab47a9a86aa3f91e71306cc9b430b) **handle** - -### operator=() {#classmavsdk_1_1_shell_1a492f8b2e36ef2468522bfd0f51f4b9b8} +### operator=() {#classmavsdk_1_1_shell_1abd920b11e6535152ad85cb4187b0c620} ```cpp -const Shell& mavsdk::Shell::operator=(const Shell &)=delete +const Shell & mavsdk::Shell::operator=(const Shell &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_system.md b/docs/en/cpp/api_reference/classmavsdk_1_1_system.md index 61529b55d1..fbb909a69f 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_system.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_system.md @@ -15,13 +15,12 @@ This class represents a system, made up of one or more components (e.g. autopilo Type | Description --- | --- -enum [ComponentType](#classmavsdk_1_1_system_1af2a91929d9771ae0e59c98557027b1dc) | Component Types. std::function< void(bool)> [IsConnectedCallback](#classmavsdk_1_1_system_1a0e56bb48498100fde0872a3ec376f282) | type for is connected callback. [Handle](classmavsdk_1_1_handle.md)< bool > [IsConnectedHandle](#classmavsdk_1_1_system_1adedf1d76e922076dfd3ca3c726443efd) | handle type to unsubscribe from subscribe_is_connected. -std::function< void([ComponentType](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1af2a91929d9771ae0e59c98557027b1dc))> [ComponentDiscoveredCallback](#classmavsdk_1_1_system_1a064172b17193bb9be448e2053c83627b) | type for component discovery callback -[Handle](classmavsdk_1_1_handle.md)< [ComponentType](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1af2a91929d9771ae0e59c98557027b1dc) > [ComponentDiscoveredHandle](#classmavsdk_1_1_system_1adfb374a9eaaa765cf0813cfa6b40df39) | type for component discovery callback handle -std::function< void([ComponentType](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1af2a91929d9771ae0e59c98557027b1dc), uint8_t)> [ComponentDiscoveredIdCallback](#classmavsdk_1_1_system_1a914c50b413b5bd61d334631096e614ca) | type for component discovery callback with component ID -[Handle](classmavsdk_1_1_handle.md)< [ComponentType](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1af2a91929d9771ae0e59c98557027b1dc), uint8_t > [ComponentDiscoveredIdHandle](#classmavsdk_1_1_system_1abd573ae09348f33e7cd3a006fc26a708) | type for component discovery callback handle with component ID +std::function< void([ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12))> [ComponentDiscoveredCallback](#classmavsdk_1_1_system_1a064172b17193bb9be448e2053c83627b) | type for component discovery callback +[Handle](classmavsdk_1_1_handle.md)< [ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) > [ComponentDiscoveredHandle](#classmavsdk_1_1_system_1adfb374a9eaaa765cf0813cfa6b40df39) | type for component discovery callback handle +std::function< void([ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12), uint8_t)> [ComponentDiscoveredIdCallback](#classmavsdk_1_1_system_1a914c50b413b5bd61d334631096e614ca) | type for component discovery callback with component ID +[Handle](classmavsdk_1_1_handle.md)< [ComponentType](namespacemavsdk.md#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12), uint8_t > [ComponentDiscoveredIdHandle](#classmavsdk_1_1_system_1abd573ae09348f33e7cd3a006fc26a708) | type for component discovery callback handle with component ID ## Public Member Functions @@ -37,7 +36,7 @@ bool | [has_camera](#classmavsdk_1_1_system_1a440fd601ed2120e1e41d9eab536a7da8) bool | [has_gimbal](#classmavsdk_1_1_system_1ad66c3ecc096970d40c34610e49dba929) () const | Checks whether the system has a gimbal. bool | [is_connected](#classmavsdk_1_1_system_1ad07991ae044bc367e27f544db40d065b) () const | Checks if the system is connected. uint8_t | [get_system_id](#classmavsdk_1_1_system_1a091d793db29719f4996040886ad951a6) () const | MAVLink [System](classmavsdk_1_1_system.md) ID of connected system. -std::vector< uint8_t > | [component_ids](#classmavsdk_1_1_system_1aa33f748f81cc512601451c80bd077888) () const | MAVLink component IDs of connected system. +std::vector< uint8_t > | [component_ids](#classmavsdk_1_1_system_1a8ef8d3f5c4b59aa71b6b0e92587185d4) () const | MAVLink component IDs of connected system. [IsConnectedHandle](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1adedf1d76e922076dfd3ca3c726443efd) | [subscribe_is_connected](#classmavsdk_1_1_system_1aae68747c23976fa7eb63ec0762493263) (const [IsConnectedCallback](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1a0e56bb48498100fde0872a3ec376f282) & callback) | Subscribe to callback to be called when system connection state changes. void | [unsubscribe_is_connected](#classmavsdk_1_1_system_1a2f1927d56c14a7ad44995bd56afb706f) ([IsConnectedHandle](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1adedf1d76e922076dfd3ca3c726443efd) handle) | Unsubscribe from subscribe_is_connected. [ComponentDiscoveredHandle](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1adfb374a9eaaa765cf0813cfa6b40df39) | [subscribe_component_discovered](#classmavsdk_1_1_system_1a25ede402b74a9412334ff1cab521e7d3) (const [ComponentDiscoveredCallback](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1a064172b17193bb9be448e2053c83627b) & callback) | Subscribe to be called when a component is discovered. @@ -45,7 +44,8 @@ void | [unsubscribe_component_discovered](#classmavsdk_1_1_system_1a5d62d308534b [ComponentDiscoveredIdHandle](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1abd573ae09348f33e7cd3a006fc26a708) | [subscribe_component_discovered_id](#classmavsdk_1_1_system_1a1905176f3a6633a8a9fe655f2dcd2d23) (const [ComponentDiscoveredIdCallback](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1a914c50b413b5bd61d334631096e614ca) & callback) | Subscribe to be called when a component is discovered. void | [unsubscribe_component_discovered_id](#classmavsdk_1_1_system_1a37bca637341bba8b07e8f95c97d122db) ([ComponentDiscoveredIdHandle](classmavsdk_1_1_system.md#classmavsdk_1_1_system_1abd573ae09348f33e7cd3a006fc26a708) handle) | Unsubscribe from subscribe_component_discovered_id. void | [enable_timesync](#classmavsdk_1_1_system_1a7c7177fb0789aefbfb375f4bb12ce824) () | Enable time synchronization using the TIMESYNC messages. -const [System](classmavsdk_1_1_system.md) & | [operator=](#classmavsdk_1_1_system_1a21284c27829fda2391ee27f5732f916d) (const [System](classmavsdk_1_1_system.md) &)=delete | Equality operator (object is not copyable). +[Autopilot](namespacemavsdk.md#namespacemavsdk_1aba05635d1785223a4d7b457ae0407297) | [autopilot_type](#classmavsdk_1_1_system_1af3ded5464f6025f5d31955e100e15894) () const | Get autopilot type. +const [System](classmavsdk_1_1_system.md) & | [operator=](#classmavsdk_1_1_system_1ace4603ebad199e8619876993a2ad5237) (const [System](classmavsdk_1_1_system.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -136,22 +136,6 @@ using mavsdk::System::ComponentDiscoveredIdHandle = Handle `UNKNOWN` | - `AUTOPILOT` | - `CAMERA` | - `GIMBAL` | - ## Member Function Documentation @@ -249,21 +233,25 @@ uint8_t mavsdk::System::get_system_id() const MAVLink [System](classmavsdk_1_1_system.md) ID of connected system. -> **Note** : this is 0 if nothing is connected yet. +::: info +: this is 0 if nothing is connected yet. +::: **Returns**  uint8_t - the system ID. -### component_ids() {#classmavsdk_1_1_system_1aa33f748f81cc512601451c80bd077888} +### component_ids() {#classmavsdk_1_1_system_1a8ef8d3f5c4b59aa71b6b0e92587185d4} ```cpp -std::vector mavsdk::System::component_ids() const +std::vector< uint8_t > mavsdk::System::component_ids() const ``` MAVLink component IDs of connected system. -> **Note** : all components that have been seen at least once will be listed. +::: info +: all components that have been seen at least once will be listed. +::: **Returns** @@ -368,9 +356,22 @@ void mavsdk::System::enable_timesync() Enable time synchronization using the TIMESYNC messages. -### operator=() {#classmavsdk_1_1_system_1a21284c27829fda2391ee27f5732f916d} +### autopilot_type() {#classmavsdk_1_1_system_1af3ded5464f6025f5d31955e100e15894} +```cpp +Autopilot mavsdk::System::autopilot_type() const +``` + + +Get autopilot type. + + +**Returns** + + [Autopilot](namespacemavsdk.md#namespacemavsdk_1aba05635d1785223a4d7b457ae0407297) - autopilot type discovered. + +### operator=() {#classmavsdk_1_1_system_1ace4603ebad199e8619876993a2ad5237} ```cpp -const System& mavsdk::System::operator=(const System &)=delete +const System & mavsdk::System::operator=(const System &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry.md b/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry.md index d976527c77..a5b4c6763b 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry.md @@ -100,10 +100,6 @@ std::function< void([EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md)) [Handle](classmavsdk_1_1_handle.md)< [EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md) > [AttitudeEulerHandle](#classmavsdk_1_1_telemetry_1ae73f3d3ac224438a6cd07344fda9543b) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_attitude_euler. std::function< void([AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md))> [AttitudeAngularVelocityBodyCallback](#classmavsdk_1_1_telemetry_1a35ff8def3048faeab7f732153d51085f) | Callback type for subscribe_attitude_angular_velocity_body. [Handle](classmavsdk_1_1_handle.md)< [AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md) > [AttitudeAngularVelocityBodyHandle](#classmavsdk_1_1_telemetry_1a2328e39c1a96ce9a090cb19283d3ffc1) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_attitude_angular_velocity_body. -std::function< void([Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md))> [CameraAttitudeQuaternionCallback](#classmavsdk_1_1_telemetry_1aa83dafa14e9b5179573a574f6fbdd973) | Callback type for subscribe_camera_attitude_quaternion. -[Handle](classmavsdk_1_1_handle.md)< [Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md) > [CameraAttitudeQuaternionHandle](#classmavsdk_1_1_telemetry_1aeb2a99828961bf2a4d5c24753e020358) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_camera_attitude_quaternion. -std::function< void([EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md))> [CameraAttitudeEulerCallback](#classmavsdk_1_1_telemetry_1aa29f9bb0767ba8c384bfe1df69f2fdd9) | Callback type for subscribe_camera_attitude_euler. -[Handle](classmavsdk_1_1_handle.md)< [EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md) > [CameraAttitudeEulerHandle](#classmavsdk_1_1_telemetry_1a76471c91115d6e03e6165a3e1315808b) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_camera_attitude_euler. std::function< void([VelocityNed](structmavsdk_1_1_telemetry_1_1_velocity_ned.md))> [VelocityNedCallback](#classmavsdk_1_1_telemetry_1ab5859d2f6a9c9bd81282166b3de92342) | Callback type for subscribe_velocity_ned. [Handle](classmavsdk_1_1_handle.md)< [VelocityNed](structmavsdk_1_1_telemetry_1_1_velocity_ned.md) > [VelocityNedHandle](#classmavsdk_1_1_telemetry_1a2c3898f33bfa1bffe86681aaca33343e) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_velocity_ned. std::function< void([GpsInfo](structmavsdk_1_1_telemetry_1_1_gps_info.md))> [GpsInfoCallback](#classmavsdk_1_1_telemetry_1ad8fa90886b2283eace09b4b46708048b) | Callback type for subscribe_gps_info. @@ -188,12 +184,6 @@ void | [unsubscribe_attitude_euler](#classmavsdk_1_1_telemetry_1aa770088117b0374 [AttitudeAngularVelocityBodyHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a2328e39c1a96ce9a090cb19283d3ffc1) | [subscribe_attitude_angular_velocity_body](#classmavsdk_1_1_telemetry_1a3bbefcdb4e9cd9af9692626984504cb7) (const [AttitudeAngularVelocityBodyCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a35ff8def3048faeab7f732153d51085f) & callback) | Subscribe to 'attitude' updates (angular velocity) void | [unsubscribe_attitude_angular_velocity_body](#classmavsdk_1_1_telemetry_1a2319d78b4e214e5b2f3ef55a1c32e2c5) ([AttitudeAngularVelocityBodyHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a2328e39c1a96ce9a090cb19283d3ffc1) handle) | Unsubscribe from subscribe_attitude_angular_velocity_body. [AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md) | [attitude_angular_velocity_body](#classmavsdk_1_1_telemetry_1a8d9e2489b79c2cdbabaef8b6bb8e2952) () const | Poll for '[AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md)' (blocking). -[CameraAttitudeQuaternionHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aeb2a99828961bf2a4d5c24753e020358) | [subscribe_camera_attitude_quaternion](#classmavsdk_1_1_telemetry_1a9b7517e15c841765fbb8b1230e73bf82) (const [CameraAttitudeQuaternionCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aa83dafa14e9b5179573a574f6fbdd973) & callback) | Subscribe to 'camera attitude' updates (quaternion). -void | [unsubscribe_camera_attitude_quaternion](#classmavsdk_1_1_telemetry_1aa92270b8a30b22271f65d92e9a7ed9a1) ([CameraAttitudeQuaternionHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aeb2a99828961bf2a4d5c24753e020358) handle) | Unsubscribe from subscribe_camera_attitude_quaternion. -[Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md) | [camera_attitude_quaternion](#classmavsdk_1_1_telemetry_1a3c07447351d3b6195d5e2526e7b128b3) () const | Poll for '[Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md)' (blocking). -[CameraAttitudeEulerHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a76471c91115d6e03e6165a3e1315808b) | [subscribe_camera_attitude_euler](#classmavsdk_1_1_telemetry_1aa50015ba9b1decb825d45e459191c342) (const [CameraAttitudeEulerCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aa29f9bb0767ba8c384bfe1df69f2fdd9) & callback) | Subscribe to 'camera attitude' updates (Euler). -void | [unsubscribe_camera_attitude_euler](#classmavsdk_1_1_telemetry_1a90b8dfe6b83afc908e4c236bbbc32930) ([CameraAttitudeEulerHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a76471c91115d6e03e6165a3e1315808b) handle) | Unsubscribe from subscribe_camera_attitude_euler. -[EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md) | [camera_attitude_euler](#classmavsdk_1_1_telemetry_1a635643d955f0cd9a805914501f819796) () const | Poll for '[EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md)' (blocking). [VelocityNedHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a2c3898f33bfa1bffe86681aaca33343e) | [subscribe_velocity_ned](#classmavsdk_1_1_telemetry_1a9b5e6bd8fb05324fd7a99d0260933c9d) (const [VelocityNedCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1ab5859d2f6a9c9bd81282166b3de92342) & callback) | Subscribe to 'ground speed' updates (NED). void | [unsubscribe_velocity_ned](#classmavsdk_1_1_telemetry_1ae14a663f3b4820e891a4d83c2f8aa2c3) ([VelocityNedHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a2c3898f33bfa1bffe86681aaca33343e) handle) | Unsubscribe from subscribe_velocity_ned. [VelocityNed](structmavsdk_1_1_telemetry_1_1_velocity_ned.md) | [velocity_ned](#classmavsdk_1_1_telemetry_1a40a86062c0322d6be7c86d8e15a52f28) () const | Poll for '[VelocityNed](structmavsdk_1_1_telemetry_1_1_velocity_ned.md)' (blocking). @@ -277,10 +267,8 @@ void | [set_rate_attitude_quaternion_async](#classmavsdk_1_1_telemetry_1a1eb6bc9 [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_attitude_quaternion](#classmavsdk_1_1_telemetry_1adfc8e1a3bfa0f459350640630283716d) (double rate_hz)const | Set rate to 'attitude euler angle' updates. void | [set_rate_attitude_euler_async](#classmavsdk_1_1_telemetry_1aabf20f904d9c65582cdf167f7b0275a9) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate to 'attitude quaternion' updates. [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_attitude_euler](#classmavsdk_1_1_telemetry_1adc7a43d7143261df5f97fdc8a882fdf3) (double rate_hz)const | Set rate to 'attitude quaternion' updates. -void | [set_rate_camera_attitude_async](#classmavsdk_1_1_telemetry_1a520f15e42f5f1b3987ca2a9cd94a3d9a) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate of camera attitude updates. -[Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_camera_attitude](#classmavsdk_1_1_telemetry_1a427da223d16ce07a61b07d4e5af1ab04) (double rate_hz)const | Set rate of camera attitude updates. -void | [set_rate_velocity_ned_async](#classmavsdk_1_1_telemetry_1a9429ffa784fa56adee69c5017abedee4) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate to 'ground speed' updates (NED). -[Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_velocity_ned](#classmavsdk_1_1_telemetry_1ab5cb79fd53f27f245808a6bb9ed3225d) (double rate_hz)const | Set rate to 'ground speed' updates (NED). +void | [set_rate_velocity_ned_async](#classmavsdk_1_1_telemetry_1a9429ffa784fa56adee69c5017abedee4) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate of camera attitude updates. Set rate to 'ground speed' updates (NED). +[Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_velocity_ned](#classmavsdk_1_1_telemetry_1ab5cb79fd53f27f245808a6bb9ed3225d) (double rate_hz)const | Set rate of camera attitude updates. Set rate to 'ground speed' updates (NED). void | [set_rate_gps_info_async](#classmavsdk_1_1_telemetry_1ae6ada3cd6d4e9835dd4d1d712f1195e4) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate to 'GPS info' updates. [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_gps_info](#classmavsdk_1_1_telemetry_1a14510bcb6fe3c31d91653d32d354613f) (double rate_hz)const | Set rate to 'GPS info' updates. void | [set_rate_battery_async](#classmavsdk_1_1_telemetry_1a5615e21f616997dfca1318c96a7e550e) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate to 'battery' updates. @@ -312,8 +300,8 @@ void | [set_rate_distance_sensor_async](#classmavsdk_1_1_telemetry_1a0371c470866 void | [set_rate_altitude_async](#classmavsdk_1_1_telemetry_1a15461dd3f64aef2b921c9f06ee144bc1) (double rate_hz, const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) callback) | Set rate to '[Altitude](structmavsdk_1_1_telemetry_1_1_altitude.md)' updates. [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) | [set_rate_altitude](#classmavsdk_1_1_telemetry_1a100fc786b86637385c6188ea53121b98) (double rate_hz)const | Set rate to '[Altitude](structmavsdk_1_1_telemetry_1_1_altitude.md)' updates. void | [get_gps_global_origin_async](#classmavsdk_1_1_telemetry_1a60cca43e2f87e3fd3a9e170ff2b64e0a) (const [GetGpsGlobalOriginCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a350ee89a7e30a691e130e29ace8917ef) callback) | Get the GPS location of where the estimator has been initialized. -std::pair< [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75), [Telemetry::GpsGlobalOrigin](structmavsdk_1_1_telemetry_1_1_gps_global_origin.md) > | [get_gps_global_origin](#classmavsdk_1_1_telemetry_1a77747e7cea5a4d644bd6bec9441c7bfb) () const | Get the GPS location of where the estimator has been initialized. -const [Telemetry](classmavsdk_1_1_telemetry.md) & | [operator=](#classmavsdk_1_1_telemetry_1a703ac978c925be8806921925cf16aca9) (const [Telemetry](classmavsdk_1_1_telemetry.md) &)=delete | Equality operator (object is not copyable). +std::pair< [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75), [Telemetry::GpsGlobalOrigin](structmavsdk_1_1_telemetry_1_1_gps_global_origin.md) > | [get_gps_global_origin](#classmavsdk_1_1_telemetry_1a341b90234b30a27bb25670a31303e0cd) () const | Get the GPS location of where the estimator has been initialized. +const [Telemetry](classmavsdk_1_1_telemetry.md) & | [operator=](#classmavsdk_1_1_telemetry_1ae606a3e3814c773a12035c2674a00c5c) (const [Telemetry](classmavsdk_1_1_telemetry.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -570,46 +558,6 @@ using mavsdk::Telemetry::AttitudeAngularVelocityBodyHandle = Handle -``` - - -Callback type for subscribe_camera_attitude_quaternion. - - -### typedef CameraAttitudeQuaternionHandle {#classmavsdk_1_1_telemetry_1aeb2a99828961bf2a4d5c24753e020358} - -```cpp -using mavsdk::Telemetry::CameraAttitudeQuaternionHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_camera_attitude_quaternion. - - -### typedef CameraAttitudeEulerCallback {#classmavsdk_1_1_telemetry_1aa29f9bb0767ba8c384bfe1df69f2fdd9} - -```cpp -using mavsdk::Telemetry::CameraAttitudeEulerCallback = std::function -``` - - -Callback type for subscribe_camera_attitude_euler. - - -### typedef CameraAttitudeEulerHandle {#classmavsdk_1_1_telemetry_1a76471c91115d6e03e6165a3e1315808b} - -```cpp -using mavsdk::Telemetry::CameraAttitudeEulerHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_camera_attitude_euler. - - ### typedef VelocityNedCallback {#classmavsdk_1_1_telemetry_1ab5859d2f6a9c9bd81282166b3de92342} ```cpp @@ -1576,92 +1524,6 @@ Poll for '[AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_  [AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md) - One [AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md) update. -### subscribe_camera_attitude_quaternion() {#classmavsdk_1_1_telemetry_1a9b7517e15c841765fbb8b1230e73bf82} -```cpp -CameraAttitudeQuaternionHandle mavsdk::Telemetry::subscribe_camera_attitude_quaternion(const CameraAttitudeQuaternionCallback &callback) -``` - - -Subscribe to 'camera attitude' updates (quaternion). - - -**Parameters** - -* const [CameraAttitudeQuaternionCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aa83dafa14e9b5179573a574f6fbdd973)& **callback** - - -**Returns** - - [CameraAttitudeQuaternionHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aeb2a99828961bf2a4d5c24753e020358) - - -### unsubscribe_camera_attitude_quaternion() {#classmavsdk_1_1_telemetry_1aa92270b8a30b22271f65d92e9a7ed9a1} -```cpp -void mavsdk::Telemetry::unsubscribe_camera_attitude_quaternion(CameraAttitudeQuaternionHandle handle) -``` - - -Unsubscribe from subscribe_camera_attitude_quaternion. - - -**Parameters** - -* [CameraAttitudeQuaternionHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aeb2a99828961bf2a4d5c24753e020358) **handle** - - -### camera_attitude_quaternion() {#classmavsdk_1_1_telemetry_1a3c07447351d3b6195d5e2526e7b128b3} -```cpp -Quaternion mavsdk::Telemetry::camera_attitude_quaternion() const -``` - - -Poll for '[Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md)' (blocking). - - -**Returns** - - [Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md) - One [Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md) update. - -### subscribe_camera_attitude_euler() {#classmavsdk_1_1_telemetry_1aa50015ba9b1decb825d45e459191c342} -```cpp -CameraAttitudeEulerHandle mavsdk::Telemetry::subscribe_camera_attitude_euler(const CameraAttitudeEulerCallback &callback) -``` - - -Subscribe to 'camera attitude' updates (Euler). - - -**Parameters** - -* const [CameraAttitudeEulerCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1aa29f9bb0767ba8c384bfe1df69f2fdd9)& **callback** - - -**Returns** - - [CameraAttitudeEulerHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a76471c91115d6e03e6165a3e1315808b) - - -### unsubscribe_camera_attitude_euler() {#classmavsdk_1_1_telemetry_1a90b8dfe6b83afc908e4c236bbbc32930} -```cpp -void mavsdk::Telemetry::unsubscribe_camera_attitude_euler(CameraAttitudeEulerHandle handle) -``` - - -Unsubscribe from subscribe_camera_attitude_euler. - - -**Parameters** - -* [CameraAttitudeEulerHandle](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a76471c91115d6e03e6165a3e1315808b) **handle** - - -### camera_attitude_euler() {#classmavsdk_1_1_telemetry_1a635643d955f0cd9a805914501f819796} -```cpp -EulerAngle mavsdk::Telemetry::camera_attitude_euler() const -``` - - -Poll for '[EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md)' (blocking). - - -**Returns** - - [EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md) - One [EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md) update. - ### subscribe_velocity_ned() {#classmavsdk_1_1_telemetry_1a9b5e6bd8fb05324fd7a99d0260933c9d} ```cpp VelocityNedHandle mavsdk::Telemetry::subscribe_velocity_ned(const VelocityNedCallback &callback) @@ -2882,46 +2744,13 @@ This function is blocking. See 'set_rate_attitude_euler_async' for the non-block  [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) - Result of request. -### set_rate_camera_attitude_async() {#classmavsdk_1_1_telemetry_1a520f15e42f5f1b3987ca2a9cd94a3d9a} -```cpp -void mavsdk::Telemetry::set_rate_camera_attitude_async(double rate_hz, const ResultCallback callback) -``` - - -Set rate of camera attitude updates. - -This function is non-blocking. See 'set_rate_camera_attitude' for the blocking counterpart. - -**Parameters** - -* double **rate_hz** - -* const [ResultCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a166e81c6573532978e5940eafdfcec0b) **callback** - - -### set_rate_camera_attitude() {#classmavsdk_1_1_telemetry_1a427da223d16ce07a61b07d4e5af1ab04} -```cpp -Result mavsdk::Telemetry::set_rate_camera_attitude(double rate_hz) const -``` - - -Set rate of camera attitude updates. - -This function is blocking. See 'set_rate_camera_attitude_async' for the non-blocking counterpart. - -**Parameters** - -* double **rate_hz** - - -**Returns** - - [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75) - Result of request. - ### set_rate_velocity_ned_async() {#classmavsdk_1_1_telemetry_1a9429ffa784fa56adee69c5017abedee4} ```cpp void mavsdk::Telemetry::set_rate_velocity_ned_async(double rate_hz, const ResultCallback callback) ``` -Set rate to 'ground speed' updates (NED). +Set rate of camera attitude updates. Set rate to 'ground speed' updates (NED). This function is non-blocking. See 'set_rate_velocity_ned' for the blocking counterpart. @@ -2936,7 +2765,7 @@ Result mavsdk::Telemetry::set_rate_velocity_ned(double rate_hz) const ``` -Set rate to 'ground speed' updates (NED). +Set rate of camera attitude updates. Set rate to 'ground speed' updates (NED). This function is blocking. See 'set_rate_velocity_ned_async' for the non-blocking counterpart. @@ -3457,9 +3286,9 @@ This function is non-blocking. See 'get_gps_global_origin' for the blocking coun * const [GetGpsGlobalOriginCallback](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a350ee89a7e30a691e130e29ace8917ef) **callback** - -### get_gps_global_origin() {#classmavsdk_1_1_telemetry_1a77747e7cea5a4d644bd6bec9441c7bfb} +### get_gps_global_origin() {#classmavsdk_1_1_telemetry_1a341b90234b30a27bb25670a31303e0cd} ```cpp -std::pair mavsdk::Telemetry::get_gps_global_origin() const +std::pair< Result, Telemetry::GpsGlobalOrigin > mavsdk::Telemetry::get_gps_global_origin() const ``` @@ -3471,9 +3300,9 @@ This function is blocking. See 'get_gps_global_origin_async' for the non-blockin  std::pair< [Result](classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a241427df9a06234df2d3020fb524db75), [Telemetry::GpsGlobalOrigin](structmavsdk_1_1_telemetry_1_1_gps_global_origin.md) > - Result of request. -### operator=() {#classmavsdk_1_1_telemetry_1a703ac978c925be8806921925cf16aca9} +### operator=() {#classmavsdk_1_1_telemetry_1ae606a3e3814c773a12035c2674a00c5c} ```cpp -const Telemetry& mavsdk::Telemetry::operator=(const Telemetry &)=delete +const Telemetry & mavsdk::Telemetry::operator=(const Telemetry &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry_server.md index dd7cb09558..d3f87363a2 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry_server.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_telemetry_server.md @@ -99,7 +99,9 @@ Type | Name | Description [Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) | [publish_raw_imu](#classmavsdk_1_1_telemetry_server_1a92f3fcb090ffc96c70ce35d433a1a2a5) ([Imu](structmavsdk_1_1_telemetry_server_1_1_imu.md) imu)const | Publish to 'Raw IMU' updates. [Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) | [publish_unix_epoch_time](#classmavsdk_1_1_telemetry_server_1a27b1b901cd8baf91380029c2b95b2dac) (uint64_t time_us)const | Publish to 'unix epoch time' updates. [Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) | [publish_distance_sensor](#classmavsdk_1_1_telemetry_server_1a7532d068284fb7f55c00804a4a996a6d) ([DistanceSensor](structmavsdk_1_1_telemetry_server_1_1_distance_sensor.md) distance_sensor)const | Publish to "distance sensor" updates. -const [TelemetryServer](classmavsdk_1_1_telemetry_server.md) & | [operator=](#classmavsdk_1_1_telemetry_server_1a479502f1ce3bdc2c5be486911a20ca25) (const [TelemetryServer](classmavsdk_1_1_telemetry_server.md) &)=delete | Equality operator (object is not copyable). +[Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) | [publish_attitude](#classmavsdk_1_1_telemetry_server_1ab8bd2bfebc1f392c8817bd4a62479799) ([EulerAngle](structmavsdk_1_1_telemetry_server_1_1_euler_angle.md) angle, [AngularVelocityBody](structmavsdk_1_1_telemetry_server_1_1_angular_velocity_body.md) angular_velocity)const | Publish to "attitude" updates. +[Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) | [publish_visual_flight_rules_hud](#classmavsdk_1_1_telemetry_server_1ade51cbbfaec3a680da1e194c014850bd) ([FixedwingMetrics](structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md) fixed_wing_metrics)const | Publish to "Visual Flight Rules HUD" updates. +const [TelemetryServer](classmavsdk_1_1_telemetry_server.md) & | [operator=](#classmavsdk_1_1_telemetry_server_1ae56dd6efaacf4bcbcc9fd65699ff6ec4) (const [TelemetryServer](classmavsdk_1_1_telemetry_server.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -521,9 +523,46 @@ This function is blocking.  [Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) - Result of request. -### operator=() {#classmavsdk_1_1_telemetry_server_1a479502f1ce3bdc2c5be486911a20ca25} +### publish_attitude() {#classmavsdk_1_1_telemetry_server_1ab8bd2bfebc1f392c8817bd4a62479799} ```cpp -const TelemetryServer& mavsdk::TelemetryServer::operator=(const TelemetryServer &)=delete +Result mavsdk::TelemetryServer::publish_attitude(EulerAngle angle, AngularVelocityBody angular_velocity) const +``` + + +Publish to "attitude" updates. + +This function is blocking. + +**Parameters** + +* [EulerAngle](structmavsdk_1_1_telemetry_server_1_1_euler_angle.md) **angle** - +* [AngularVelocityBody](structmavsdk_1_1_telemetry_server_1_1_angular_velocity_body.md) **angular_velocity** - + +**Returns** + + [Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) - Result of request. + +### publish_visual_flight_rules_hud() {#classmavsdk_1_1_telemetry_server_1ade51cbbfaec3a680da1e194c014850bd} +```cpp +Result mavsdk::TelemetryServer::publish_visual_flight_rules_hud(FixedwingMetrics fixed_wing_metrics) const +``` + + +Publish to "Visual Flight Rules HUD" updates. + +This function is blocking. + +**Parameters** + +* [FixedwingMetrics](structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md) **fixed_wing_metrics** - + +**Returns** + + [Result](classmavsdk_1_1_telemetry_server.md#classmavsdk_1_1_telemetry_server_1a39d62e69bdc289d55b73b0e4c3a3ac8a) - Result of request. + +### operator=() {#classmavsdk_1_1_telemetry_server_1ae56dd6efaacf4bcbcc9fd65699ff6ec4} +```cpp +const TelemetryServer & mavsdk::TelemetryServer::operator=(const TelemetryServer &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_tracking_server.md b/docs/en/cpp/api_reference/classmavsdk_1_1_tracking_server.md deleted file mode 100644 index 48864c9ee6..0000000000 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_tracking_server.md +++ /dev/null @@ -1,401 +0,0 @@ -# mavsdk::TrackingServer Class Reference -`#include: tracking_server.h` - ----- - - -API for an onboard image tracking software. - - -## Data Structures - - -struct [TrackPoint](structmavsdk_1_1_tracking_server_1_1_track_point.md) - -struct [TrackRectangle](structmavsdk_1_1_tracking_server_1_1_track_rectangle.md) - -## Public Types - - -Type | Description ---- | --- -enum [CommandAnswer](#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) | Answer to respond to an incoming command. -enum [Result](#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) | Possible results returned for tracking_server requests. -std::function< void([Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2))> [ResultCallback](#classmavsdk_1_1_tracking_server_1a5f726eec45daac754660d557f43e8b99) | Callback type for asynchronous [TrackingServer](classmavsdk_1_1_tracking_server.md) calls. -std::function< void([TrackPoint](structmavsdk_1_1_tracking_server_1_1_track_point.md))> [TrackingPointCommandCallback](#classmavsdk_1_1_tracking_server_1afc190d231e0cd23d22055d5f5319f00d) | Callback type for subscribe_tracking_point_command. -[Handle](classmavsdk_1_1_handle.md)< [TrackPoint](structmavsdk_1_1_tracking_server_1_1_track_point.md) > [TrackingPointCommandHandle](#classmavsdk_1_1_tracking_server_1abd57fbc319036028db3f1b3802bfa184) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_point_command. -std::function< void([TrackRectangle](structmavsdk_1_1_tracking_server_1_1_track_rectangle.md))> [TrackingRectangleCommandCallback](#classmavsdk_1_1_tracking_server_1ad9a54dd2042c28046a03c8b1c5ba5b41) | Callback type for subscribe_tracking_rectangle_command. -[Handle](classmavsdk_1_1_handle.md)< [TrackRectangle](structmavsdk_1_1_tracking_server_1_1_track_rectangle.md) > [TrackingRectangleCommandHandle](#classmavsdk_1_1_tracking_server_1a0bc52069d6d7fe1f5ae2760568c1ed5d) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_rectangle_command. -std::function< void(int32_t)> [TrackingOffCommandCallback](#classmavsdk_1_1_tracking_server_1a585e63bb331d1a5c3e0108b505c6e2e7) | Callback type for subscribe_tracking_off_command. -[Handle](classmavsdk_1_1_handle.md)< int32_t > [TrackingOffCommandHandle](#classmavsdk_1_1_tracking_server_1a7fd355b3ec3e7f0f4a08da194d9ae625) | [Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_off_command. - -## Public Member Functions - - -Type | Name | Description ----: | --- | --- -  | [TrackingServer](#classmavsdk_1_1_tracking_server_1a8e3a87d4bf33fd4ca94dc7c1bf8f50a9) (std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > server_component) | Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. -  | [~TrackingServer](#classmavsdk_1_1_tracking_server_1af459f9f101561ab3a837e3783e56457a) () override | Destructor (internal use only). -  | [TrackingServer](#classmavsdk_1_1_tracking_server_1ade3caff75ba75c18637b30944d7fbb25) (const [TrackingServer](classmavsdk_1_1_tracking_server.md) & other) | Copy constructor. -void | [set_tracking_point_status](#classmavsdk_1_1_tracking_server_1a76404bc162c15dbfb50b7afbb2d3de4e) ([TrackPoint](structmavsdk_1_1_tracking_server_1_1_track_point.md) tracked_point)const | Set/update the current point tracking status. -void | [set_tracking_rectangle_status](#classmavsdk_1_1_tracking_server_1ae3f0696613834aecdd5dbd99a346b9a0) ([TrackRectangle](structmavsdk_1_1_tracking_server_1_1_track_rectangle.md) tracked_rectangle)const | Set/update the current rectangle tracking status. -void | [set_tracking_off_status](#classmavsdk_1_1_tracking_server_1a2d77454965d854f68704e29da645bf94) () const | Set the current tracking status to off. -[TrackingPointCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abd57fbc319036028db3f1b3802bfa184) | [subscribe_tracking_point_command](#classmavsdk_1_1_tracking_server_1a7fc9f06c0d13ce0a73b8a36c3b39591c) (const [TrackingPointCommandCallback](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1afc190d231e0cd23d22055d5f5319f00d) & callback) | Subscribe to incoming tracking point command. -void | [unsubscribe_tracking_point_command](#classmavsdk_1_1_tracking_server_1aaf00344b10e8bbb0c6cd7b5bfd43806b) ([TrackingPointCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abd57fbc319036028db3f1b3802bfa184) handle) | Unsubscribe from subscribe_tracking_point_command. -[TrackingRectangleCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a0bc52069d6d7fe1f5ae2760568c1ed5d) | [subscribe_tracking_rectangle_command](#classmavsdk_1_1_tracking_server_1a5a36aa7b26085834ed56ea1aa80f42b8) (const [TrackingRectangleCommandCallback](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1ad9a54dd2042c28046a03c8b1c5ba5b41) & callback) | Subscribe to incoming tracking rectangle command. -void | [unsubscribe_tracking_rectangle_command](#classmavsdk_1_1_tracking_server_1a35d2617d48c378c176e36f1c8db9594d) ([TrackingRectangleCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a0bc52069d6d7fe1f5ae2760568c1ed5d) handle) | Unsubscribe from subscribe_tracking_rectangle_command. -[TrackingOffCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a7fd355b3ec3e7f0f4a08da194d9ae625) | [subscribe_tracking_off_command](#classmavsdk_1_1_tracking_server_1ad8c9ea7f6b62e56e862d59532b7edf0d) (const [TrackingOffCommandCallback](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a585e63bb331d1a5c3e0108b505c6e2e7) & callback) | Subscribe to incoming tracking off command. -void | [unsubscribe_tracking_off_command](#classmavsdk_1_1_tracking_server_1a9ac5db837aa263dcc8c98fcf0aafa170) ([TrackingOffCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a7fd355b3ec3e7f0f4a08da194d9ae625) handle) | Unsubscribe from subscribe_tracking_off_command. -[Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) | [respond_tracking_point_command](#classmavsdk_1_1_tracking_server_1a75ec8813d5c5dac5dc3fcd3590a62e2a) ([CommandAnswer](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) command_answer)const | Respond to an incoming tracking point command. -[Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) | [respond_tracking_rectangle_command](#classmavsdk_1_1_tracking_server_1a6388d3a7bafeb0fbb58343a09495fc7c) ([CommandAnswer](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) command_answer)const | Respond to an incoming tracking rectangle command. -[Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) | [respond_tracking_off_command](#classmavsdk_1_1_tracking_server_1a113b2d4adf5b62a5f167b81c39474da4) ([CommandAnswer](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) command_answer)const | Respond to an incoming tracking off command. -const [TrackingServer](classmavsdk_1_1_tracking_server.md) & | [operator=](#classmavsdk_1_1_tracking_server_1a9ea0947f9038e3affbd4129f5d6f671d) (const [TrackingServer](classmavsdk_1_1_tracking_server.md) &)=delete | Equality operator (object is not copyable). - - -## Constructor & Destructor Documentation - - -### TrackingServer() {#classmavsdk_1_1_tracking_server_1a8e3a87d4bf33fd4ca94dc7c1bf8f50a9} -```cpp -mavsdk::TrackingServer::TrackingServer(std::shared_ptr< ServerComponent > server_component) -``` - - -Constructor. Creates the plugin for a [ServerComponent](classmavsdk_1_1_server_component.md) instance. - -The plugin is typically created as shown below: - -```cpp -auto tracking_server = TrackingServer(server_component); -``` - -**Parameters** - -* std::shared_ptr< [ServerComponent](classmavsdk_1_1_server_component.md) > **server_component** - The [ServerComponent](classmavsdk_1_1_server_component.md) instance associated with this server plugin. - -### ~TrackingServer() {#classmavsdk_1_1_tracking_server_1af459f9f101561ab3a837e3783e56457a} -```cpp -mavsdk::TrackingServer::~TrackingServer() override -``` - - -Destructor (internal use only). - - -### TrackingServer() {#classmavsdk_1_1_tracking_server_1ade3caff75ba75c18637b30944d7fbb25} -```cpp -mavsdk::TrackingServer::TrackingServer(const TrackingServer &other) -``` - - -Copy constructor. - - -**Parameters** - -* const [TrackingServer](classmavsdk_1_1_tracking_server.md)& **other** - - -## Member Typdef Documentation - - -### typedef ResultCallback {#classmavsdk_1_1_tracking_server_1a5f726eec45daac754660d557f43e8b99} - -```cpp -using mavsdk::TrackingServer::ResultCallback = std::function -``` - - -Callback type for asynchronous [TrackingServer](classmavsdk_1_1_tracking_server.md) calls. - - -### typedef TrackingPointCommandCallback {#classmavsdk_1_1_tracking_server_1afc190d231e0cd23d22055d5f5319f00d} - -```cpp -using mavsdk::TrackingServer::TrackingPointCommandCallback = std::function -``` - - -Callback type for subscribe_tracking_point_command. - - -### typedef TrackingPointCommandHandle {#classmavsdk_1_1_tracking_server_1abd57fbc319036028db3f1b3802bfa184} - -```cpp -using mavsdk::TrackingServer::TrackingPointCommandHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_point_command. - - -### typedef TrackingRectangleCommandCallback {#classmavsdk_1_1_tracking_server_1ad9a54dd2042c28046a03c8b1c5ba5b41} - -```cpp -using mavsdk::TrackingServer::TrackingRectangleCommandCallback = std::function -``` - - -Callback type for subscribe_tracking_rectangle_command. - - -### typedef TrackingRectangleCommandHandle {#classmavsdk_1_1_tracking_server_1a0bc52069d6d7fe1f5ae2760568c1ed5d} - -```cpp -using mavsdk::TrackingServer::TrackingRectangleCommandHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_rectangle_command. - - -### typedef TrackingOffCommandCallback {#classmavsdk_1_1_tracking_server_1a585e63bb331d1a5c3e0108b505c6e2e7} - -```cpp -using mavsdk::TrackingServer::TrackingOffCommandCallback = std::function -``` - - -Callback type for subscribe_tracking_off_command. - - -### typedef TrackingOffCommandHandle {#classmavsdk_1_1_tracking_server_1a7fd355b3ec3e7f0f4a08da194d9ae625} - -```cpp -using mavsdk::TrackingServer::TrackingOffCommandHandle = Handle -``` - - -[Handle](classmavsdk_1_1_handle.md) type for subscribe_tracking_off_command. - - -## Member Enumeration Documentation - - -### enum CommandAnswer {#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61} - - -Answer to respond to an incoming command. - - -Value | Description ---- | --- - `Accepted` | Command accepted. - `TemporarilyRejected` | Command temporarily rejected. - `Denied` | Command denied. - `Unsupported` | Command unsupported. - `Failed` | Command failed. - -### enum Result {#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2} - - -Possible results returned for tracking_server requests. - - -Value | Description ---- | --- - `Unknown` | Unknown result. - `Success` | Request succeeded. - `NoSystem` | No system is connected. - `ConnectionError` | Connection error. - -## Member Function Documentation - - -### set_tracking_point_status() {#classmavsdk_1_1_tracking_server_1a76404bc162c15dbfb50b7afbb2d3de4e} -```cpp -void mavsdk::TrackingServer::set_tracking_point_status(TrackPoint tracked_point) const -``` - - -Set/update the current point tracking status. - -This function is blocking. - -**Parameters** - -* [TrackPoint](structmavsdk_1_1_tracking_server_1_1_track_point.md) **tracked_point** - - -### set_tracking_rectangle_status() {#classmavsdk_1_1_tracking_server_1ae3f0696613834aecdd5dbd99a346b9a0} -```cpp -void mavsdk::TrackingServer::set_tracking_rectangle_status(TrackRectangle tracked_rectangle) const -``` - - -Set/update the current rectangle tracking status. - -This function is blocking. - -**Parameters** - -* [TrackRectangle](structmavsdk_1_1_tracking_server_1_1_track_rectangle.md) **tracked_rectangle** - - -### set_tracking_off_status() {#classmavsdk_1_1_tracking_server_1a2d77454965d854f68704e29da645bf94} -```cpp -void mavsdk::TrackingServer::set_tracking_off_status() const -``` - - -Set the current tracking status to off. - -This function is blocking. - -### subscribe_tracking_point_command() {#classmavsdk_1_1_tracking_server_1a7fc9f06c0d13ce0a73b8a36c3b39591c} -```cpp -TrackingPointCommandHandle mavsdk::TrackingServer::subscribe_tracking_point_command(const TrackingPointCommandCallback &callback) -``` - - -Subscribe to incoming tracking point command. - - -**Parameters** - -* const [TrackingPointCommandCallback](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1afc190d231e0cd23d22055d5f5319f00d)& **callback** - - -**Returns** - - [TrackingPointCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abd57fbc319036028db3f1b3802bfa184) - - -### unsubscribe_tracking_point_command() {#classmavsdk_1_1_tracking_server_1aaf00344b10e8bbb0c6cd7b5bfd43806b} -```cpp -void mavsdk::TrackingServer::unsubscribe_tracking_point_command(TrackingPointCommandHandle handle) -``` - - -Unsubscribe from subscribe_tracking_point_command. - - -**Parameters** - -* [TrackingPointCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abd57fbc319036028db3f1b3802bfa184) **handle** - - -### subscribe_tracking_rectangle_command() {#classmavsdk_1_1_tracking_server_1a5a36aa7b26085834ed56ea1aa80f42b8} -```cpp -TrackingRectangleCommandHandle mavsdk::TrackingServer::subscribe_tracking_rectangle_command(const TrackingRectangleCommandCallback &callback) -``` - - -Subscribe to incoming tracking rectangle command. - - -**Parameters** - -* const [TrackingRectangleCommandCallback](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1ad9a54dd2042c28046a03c8b1c5ba5b41)& **callback** - - -**Returns** - - [TrackingRectangleCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a0bc52069d6d7fe1f5ae2760568c1ed5d) - - -### unsubscribe_tracking_rectangle_command() {#classmavsdk_1_1_tracking_server_1a35d2617d48c378c176e36f1c8db9594d} -```cpp -void mavsdk::TrackingServer::unsubscribe_tracking_rectangle_command(TrackingRectangleCommandHandle handle) -``` - - -Unsubscribe from subscribe_tracking_rectangle_command. - - -**Parameters** - -* [TrackingRectangleCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a0bc52069d6d7fe1f5ae2760568c1ed5d) **handle** - - -### subscribe_tracking_off_command() {#classmavsdk_1_1_tracking_server_1ad8c9ea7f6b62e56e862d59532b7edf0d} -```cpp -TrackingOffCommandHandle mavsdk::TrackingServer::subscribe_tracking_off_command(const TrackingOffCommandCallback &callback) -``` - - -Subscribe to incoming tracking off command. - - -**Parameters** - -* const [TrackingOffCommandCallback](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a585e63bb331d1a5c3e0108b505c6e2e7)& **callback** - - -**Returns** - - [TrackingOffCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a7fd355b3ec3e7f0f4a08da194d9ae625) - - -### unsubscribe_tracking_off_command() {#classmavsdk_1_1_tracking_server_1a9ac5db837aa263dcc8c98fcf0aafa170} -```cpp -void mavsdk::TrackingServer::unsubscribe_tracking_off_command(TrackingOffCommandHandle handle) -``` - - -Unsubscribe from subscribe_tracking_off_command. - - -**Parameters** - -* [TrackingOffCommandHandle](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a7fd355b3ec3e7f0f4a08da194d9ae625) **handle** - - -### respond_tracking_point_command() {#classmavsdk_1_1_tracking_server_1a75ec8813d5c5dac5dc3fcd3590a62e2a} -```cpp -Result mavsdk::TrackingServer::respond_tracking_point_command(CommandAnswer command_answer) const -``` - - -Respond to an incoming tracking point command. - -This function is blocking. - -**Parameters** - -* [CommandAnswer](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) **command_answer** - - -**Returns** - - [Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) - Result of request. - -### respond_tracking_rectangle_command() {#classmavsdk_1_1_tracking_server_1a6388d3a7bafeb0fbb58343a09495fc7c} -```cpp -Result mavsdk::TrackingServer::respond_tracking_rectangle_command(CommandAnswer command_answer) const -``` - - -Respond to an incoming tracking rectangle command. - -This function is blocking. - -**Parameters** - -* [CommandAnswer](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) **command_answer** - - -**Returns** - - [Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) - Result of request. - -### respond_tracking_off_command() {#classmavsdk_1_1_tracking_server_1a113b2d4adf5b62a5f167b81c39474da4} -```cpp -Result mavsdk::TrackingServer::respond_tracking_off_command(CommandAnswer command_answer) const -``` - - -Respond to an incoming tracking off command. - -This function is blocking. - -**Parameters** - -* [CommandAnswer](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1abe88efaef492f9b549a57b5b05666d61) **command_answer** - - -**Returns** - - [Result](classmavsdk_1_1_tracking_server.md#classmavsdk_1_1_tracking_server_1a1a288ecd74fd52a6f0ffbf24e8da2cc2) - Result of request. - -### operator=() {#classmavsdk_1_1_tracking_server_1a9ea0947f9038e3affbd4129f5d6f671d} -```cpp -const TrackingServer& mavsdk::TrackingServer::operator=(const TrackingServer &)=delete -``` - - -Equality operator (object is not copyable). - - -**Parameters** - -* const [TrackingServer](classmavsdk_1_1_tracking_server.md)& - - -**Returns** - - const [TrackingServer](classmavsdk_1_1_tracking_server.md) & - \ No newline at end of file diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_transponder.md b/docs/en/cpp/api_reference/classmavsdk_1_1_transponder.md index 9afd92c33b..5b4b226f5a 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_transponder.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_transponder.md @@ -38,7 +38,7 @@ void | [unsubscribe_transponder](#classmavsdk_1_1_transponder_1a28735123acd67953 [AdsbVehicle](structmavsdk_1_1_transponder_1_1_adsb_vehicle.md) | [transponder](#classmavsdk_1_1_transponder_1a1674c21928af3368e2be84bd182251d9) () const | Poll for '[AdsbVehicle](structmavsdk_1_1_transponder_1_1_adsb_vehicle.md)' (blocking). void | [set_rate_transponder_async](#classmavsdk_1_1_transponder_1a098f5692a3f2b76a201ce0b22a56f0ec) (double rate_hz, const [ResultCallback](classmavsdk_1_1_transponder.md#classmavsdk_1_1_transponder_1a57166e61c37ad92ecd5420bc1b7972a5) callback) | Set rate to 'transponder' updates. [Result](classmavsdk_1_1_transponder.md#classmavsdk_1_1_transponder_1a683477ab9a02d00b2524bc2dcea3ecc8) | [set_rate_transponder](#classmavsdk_1_1_transponder_1a9d9f4b4899ef61b6d13d9e25f44dbecd) (double rate_hz)const | Set rate to 'transponder' updates. -const [Transponder](classmavsdk_1_1_transponder.md) & | [operator=](#classmavsdk_1_1_transponder_1aaee71763de213002fadeb9dec3ec9fb6) (const [Transponder](classmavsdk_1_1_transponder.md) &)=delete | Equality operator (object is not copyable). +const [Transponder](classmavsdk_1_1_transponder.md) & | [operator=](#classmavsdk_1_1_transponder_1a26e549ff3c1a202aa24b3e1a0c5fe87f) (const [Transponder](classmavsdk_1_1_transponder.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -273,9 +273,9 @@ This function is blocking. See 'set_rate_transponder_async' for the non-blocking  [Result](classmavsdk_1_1_transponder.md#classmavsdk_1_1_transponder_1a683477ab9a02d00b2524bc2dcea3ecc8) - Result of request. -### operator=() {#classmavsdk_1_1_transponder_1aaee71763de213002fadeb9dec3ec9fb6} +### operator=() {#classmavsdk_1_1_transponder_1a26e549ff3c1a202aa24b3e1a0c5fe87f} ```cpp -const Transponder& mavsdk::Transponder::operator=(const Transponder &)=delete +const Transponder & mavsdk::Transponder::operator=(const Transponder &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_tune.md b/docs/en/cpp/api_reference/classmavsdk_1_1_tune.md index 100b1943ba..14410abb65 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_tune.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_tune.md @@ -32,7 +32,7 @@ Type | Name | Description   | [Tune](#classmavsdk_1_1_tune_1ae3fb9d4ec2116f1c9543c0e09371b2e0) (const [Tune](classmavsdk_1_1_tune.md) & other) | Copy constructor. void | [play_tune_async](#classmavsdk_1_1_tune_1a6a88b2cfe944a4c1e4ab6945b06620d5) ([TuneDescription](structmavsdk_1_1_tune_1_1_tune_description.md) tune_description, const [ResultCallback](classmavsdk_1_1_tune.md#classmavsdk_1_1_tune_1aa283f6824bee43d341fec56d7ff70985) callback) | Send a tune to be played by the system. [Result](classmavsdk_1_1_tune.md#classmavsdk_1_1_tune_1aed2b008974298098cedd69b7e95e909d) | [play_tune](#classmavsdk_1_1_tune_1a94df5e7c5d8f5ca49fd9844557060695) ([TuneDescription](structmavsdk_1_1_tune_1_1_tune_description.md) tune_description)const | Send a tune to be played by the system. -const [Tune](classmavsdk_1_1_tune.md) & | [operator=](#classmavsdk_1_1_tune_1ae4a076da0417c6858df6fb59fa5110b5) (const [Tune](classmavsdk_1_1_tune.md) &)=delete | Equality operator (object is not copyable). +const [Tune](classmavsdk_1_1_tune.md) & | [operator=](#classmavsdk_1_1_tune_1a0f3ee8fe02178e0944f183a8e7f24cdd) (const [Tune](classmavsdk_1_1_tune.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -193,9 +193,9 @@ This function is blocking. See 'play_tune_async' for the non-blocking counterpar  [Result](classmavsdk_1_1_tune.md#classmavsdk_1_1_tune_1aed2b008974298098cedd69b7e95e909d) - Result of request. -### operator=() {#classmavsdk_1_1_tune_1ae4a076da0417c6858df6fb59fa5110b5} +### operator=() {#classmavsdk_1_1_tune_1a0f3ee8fe02178e0944f183a8e7f24cdd} ```cpp -const Tune& mavsdk::Tune::operator=(const Tune &)=delete +const Tune & mavsdk::Tune::operator=(const Tune &)=delete ``` diff --git a/docs/en/cpp/api_reference/classmavsdk_1_1_winch.md b/docs/en/cpp/api_reference/classmavsdk_1_1_winch.md index 1e5799eea5..fc02dad512 100644 --- a/docs/en/cpp/api_reference/classmavsdk_1_1_winch.md +++ b/docs/en/cpp/api_reference/classmavsdk_1_1_winch.md @@ -57,7 +57,7 @@ void | [abandon_line_async](#classmavsdk_1_1_winch_1a3970c74e067d3734ba8dd3382c5 [Result](classmavsdk_1_1_winch.md#classmavsdk_1_1_winch_1a48edb6e5176dc8d5e95bd30eacd7a091) | [abandon_line](#classmavsdk_1_1_winch_1a625f6d58d5447afbe0c40e3d896071b0) (uint32_t instance)const | Spool out the entire length of the line. void | [load_payload_async](#classmavsdk_1_1_winch_1af715b6c01dc75c44868c2936af04d40a) (uint32_t instance, const [ResultCallback](classmavsdk_1_1_winch.md#classmavsdk_1_1_winch_1a683fc7d385d461efb059df917622a6b7) callback) | Spools out just enough to present the hook to the user to load the payload. [Result](classmavsdk_1_1_winch.md#classmavsdk_1_1_winch_1a48edb6e5176dc8d5e95bd30eacd7a091) | [load_payload](#classmavsdk_1_1_winch_1a01fec2758f7f09d8aef5de23f4566d47) (uint32_t instance)const | Spools out just enough to present the hook to the user to load the payload. -const [Winch](classmavsdk_1_1_winch.md) & | [operator=](#classmavsdk_1_1_winch_1a5216eb2d1533b1e737ad30f31b7eff7a) (const [Winch](classmavsdk_1_1_winch.md) &)=delete | Equality operator (object is not copyable). +const [Winch](classmavsdk_1_1_winch.md) & | [operator=](#classmavsdk_1_1_winch_1a95e5998fc48ba20b61001d344a7274ff) (const [Winch](classmavsdk_1_1_winch.md) &)=delete | Equality operator (object is not copyable). ## Constructor & Destructor Documentation @@ -580,9 +580,9 @@ This function is blocking. See 'load_payload_async' for the non-blocking counter  [Result](classmavsdk_1_1_winch.md#classmavsdk_1_1_winch_1a48edb6e5176dc8d5e95bd30eacd7a091) - Result of request. -### operator=() {#classmavsdk_1_1_winch_1a5216eb2d1533b1e737ad30f31b7eff7a} +### operator=() {#classmavsdk_1_1_winch_1a95e5998fc48ba20b61001d344a7274ff} ```cpp -const Winch& mavsdk::Winch::operator=(const Winch &)=delete +const Winch & mavsdk::Winch::operator=(const Winch &)=delete ``` diff --git a/docs/en/cpp/api_reference/index.md b/docs/en/cpp/api_reference/index.md index a3ad23887f..f5b83eb9a8 100644 --- a/docs/en/cpp/api_reference/index.md +++ b/docs/en/cpp/api_reference/index.md @@ -1,194 +1,3 @@ # C++ API Reference -* [class Mavsdk](classmavsdk_1_1_mavsdk.md) - * [class Mavsdk::Configuration](classmavsdk_1_1_mavsdk_1_1_configuration.md) - * [struct MavlinkAddress](struct_mavlink_address.md) -* [class Action](classmavsdk_1_1_action.md) -* [class ActionServer](classmavsdk_1_1_action_server.md) - * [struct AllowableFlightModes](structmavsdk_1_1_action_server_1_1_allowable_flight_modes.md) - * [struct ArmDisarm](structmavsdk_1_1_action_server_1_1_arm_disarm.md) -* [class Calibration](classmavsdk_1_1_calibration.md) - * [struct ProgressData](structmavsdk_1_1_calibration_1_1_progress_data.md) -* [class Camera](classmavsdk_1_1_camera.md) - * [struct Information](structmavsdk_1_1_camera_1_1_information.md) - * [struct CaptureInfo](structmavsdk_1_1_camera_1_1_capture_info.md) - * [struct Position](structmavsdk_1_1_camera_1_1_position.md) - * [struct Quaternion](structmavsdk_1_1_camera_1_1_quaternion.md) - * [struct EulerAngle](structmavsdk_1_1_camera_1_1_euler_angle.md) - * [struct Status](structmavsdk_1_1_camera_1_1_status.md) - * [struct VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) - * [struct VideoStreamSettings](structmavsdk_1_1_camera_1_1_video_stream_settings.md) - * [struct Option](structmavsdk_1_1_camera_1_1_option.md) - * [struct Setting](structmavsdk_1_1_camera_1_1_setting.md) - * [struct SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) -* [class CameraServer](classmavsdk_1_1_camera_server.md) - * [struct CaptureInfo](structmavsdk_1_1_camera_server_1_1_capture_info.md) - * [struct CaptureStatus](structmavsdk_1_1_camera_server_1_1_capture_status.md) - * [struct Information](structmavsdk_1_1_camera_server_1_1_information.md) - * [struct Position](structmavsdk_1_1_camera_server_1_1_position.md) - * [struct Quaternion](structmavsdk_1_1_camera_server_1_1_quaternion.md) - * [struct StorageStatus](structmavsdk_1_1_camera_server_1_1_capture_status.md) - * [struct VideoStreaming](structmavsdk_1_1_camera_server_1_1_video_streaming.md) -* [class ComponentInformation](classmavsdk_1_1_component_information.md) - * [struct FloatParam](structmavsdk_1_1_component_information_1_1_float_param.md) - * [struct FloatParamUpdate](structmavsdk_1_1_component_information_1_1_float_param_update.md) -* [class ComponentInformationServer](classmavsdk_1_1_component_information_server.md) - * [struct FloatParam](structmavsdk_1_1_component_information_server_1_1_float_param.md) - * [struct FloatParamUpdate](structmavsdk_1_1_component_information_server_1_1_float_param_update.md) -* [class Failure](classmavsdk_1_1_failure.md) -* [class FollowMe](classmavsdk_1_1_follow_me.md) - * [struct Config](structmavsdk_1_1_follow_me_1_1_config.md) - * [struct TargetLocation](structmavsdk_1_1_follow_me_1_1_target_location.md) -* [class Ftp](classmavsdk_1_1_ftp.md) -* [class FtpServer](classmavsdk_1_1_ftp_server.md) -* [class Geofence](classmavsdk_1_1_geofence.md) - * [struct Circle](structmavsdk_1_1_geofence_1_1_circle.md) - * [struct GeofenceData](structmavsdk_1_1_geofence_1_1_geofence_data.md) - * [struct Polygon](structmavsdk_1_1_geofence_1_1_polygon.md) - * [struct Point](structmavsdk_1_1_geofence_1_1_point.md) - * [struct ProgressData](structmavsdk_1_1_ftp_1_1_progress_data.md) -* [class geometry::CoordinateTransformation](classmavsdk_1_1geometry_1_1_coordinate_transformation.md) - * [struct GlobalCoordinate](structmavsdk_1_1geometry_1_1_coordinate_transformation_1_1_global_coordinate.md) - * [struct LocalCoordinate](structmavsdk_1_1geometry_1_1_coordinate_transformation_1_1_local_coordinate.md) -* [class Gimbal](classmavsdk_1_1_gimbal.md) - * [struct ControlStatus](structmavsdk_1_1_gimbal_1_1_control_status.md) -* [class Gripper](classmavsdk_1_1_gripper.md) -* [class Info](classmavsdk_1_1_info.md) - * [struct FlightInfo](structmavsdk_1_1_info_1_1_flight_info.md) - * [struct Identification](structmavsdk_1_1_info_1_1_identification.md) - * [struct Product](structmavsdk_1_1_info_1_1_product.md) - * [struct Version](structmavsdk_1_1_info_1_1_version.md) -* [class LogFiles](classmavsdk_1_1_log_files.md) - * [struct Entry](structmavsdk_1_1_log_files_1_1_entry.md) - * [struct ProgressData](structmavsdk_1_1_log_files_1_1_progress_data.md) -* [class ManualControl](classmavsdk_1_1_manual_control.md) -* [class MavlinkPassthrough](classmavsdk_1_1_mavlink_passthrough.md) - * [struct CommandInt](structmavsdk_1_1_mavlink_passthrough_1_1_command_int.md) - * [struct CommandLong](structmavsdk_1_1_mavlink_passthrough_1_1_command_long.md) -* [class Mission](classmavsdk_1_1_mission.md) - * [struct MissionItem](structmavsdk_1_1_mission_1_1_mission_item.md) - * [struct MissionPlan](structmavsdk_1_1_mission_1_1_mission_plan.md) - * [struct MissionProgress](structmavsdk_1_1_mission_1_1_mission_progress.md) - * [struct ProgressData](structmavsdk_1_1_mission_1_1_progress_data.md) - * [struct ProgressDataOrMission](structmavsdk_1_1_mission_1_1_progress_data_or_mission.md) -* [class MissionRaw](classmavsdk_1_1_mission_raw.md) - * [struct MissionItem](structmavsdk_1_1_mission_raw_1_1_mission_item.md) - * [struct MissionProgress](structmavsdk_1_1_mission_raw_1_1_mission_progress.md) -* [class MissionRawServer](classmavsdk_1_1_mission_raw_server.md) - * [struct MissionItem](structmavsdk_1_1_mission_raw_server_1_1_mission_item.md) - * [struct MissionPlan](structmavsdk_1_1_mission_raw_server_1_1_mission_plan.md) - * [struct MissionProgress](structmavsdk_1_1_mission_raw_server_1_1_mission_progress.md) -* [class Mocap](classmavsdk_1_1_mocap.md) - * [struct AngleBody](structmavsdk_1_1_mocap_1_1_angle_body.md) - * [struct AngularVelocityBody](structmavsdk_1_1_mocap_1_1_angular_velocity_body.md) - * [struct AttitudePositionMocap](structmavsdk_1_1_mocap_1_1_attitude_position_mocap.md) - * [struct Covariance](structmavsdk_1_1_mocap_1_1_covariance.md) - * [struct Odometry](structmavsdk_1_1_mocap_1_1_odometry.md) - * [struct PositionBody](structmavsdk_1_1_mocap_1_1_position_body.md) - * [struct Quaternion](structmavsdk_1_1_mocap_1_1_quaternion.md) - * [struct SpeedBody](structmavsdk_1_1_mocap_1_1_speed_body.md) - * [struct VisionPositionEstimate](structmavsdk_1_1_mocap_1_1_vision_position_estimate.md) -* [class Offboard](classmavsdk_1_1_offboard.md) - * [struct ActuatorControl](structmavsdk_1_1_offboard_1_1_actuator_control.md) - * [struct ActuatorControlGroup](structmavsdk_1_1_offboard_1_1_actuator_control_group.md) - * [struct Attitude](structmavsdk_1_1_offboard_1_1_attitude.md) - * [struct AttitudeRate](structmavsdk_1_1_offboard_1_1_attitude_rate.md) - * [struct VelocityBodyYawspeed](structmavsdk_1_1_offboard_1_1_velocity_body_yawspeed.md) - * [struct VelocityNedYaw](structmavsdk_1_1_offboard_1_1_velocity_ned_yaw.md) - * [struct PositionNedYaw](structmavsdk_1_1_offboard_1_1_position_ned_yaw.md) - * [struct PositionGlobalYaw](structmavsdk_1_1_offboard_1_1_position_global_yaw.md) -* [class Param](classmavsdk_1_1_param.md) - * [struct AllParams](structmavsdk_1_1_param_1_1_all_params.md) - * [struct CustomParam](structmavsdk_1_1_param_1_1_custom_param.md) - * [struct FloatParam](structmavsdk_1_1_param_1_1_float_param.md) - * [struct IntParam](structmavsdk_1_1_param_1_1_int_param.md) -* [class ParamServer](classmavsdk_1_1_param_server.md) - * [struct AllParams](structmavsdk_1_1_param_server_1_1_all_params.md) - * [struct CustomParam](structmavsdk_1_1_param_server_1_1_custom_param.md) - * [struct FloatParam](structmavsdk_1_1_param_server_1_1_float_param.md) - * [struct IntParam](structmavsdk_1_1_param_server_1_1_int_param.md) -* [class Rtk](classmavsdk_1_1_rtk.md) - * [struct RtcmData](structmavsdk_1_1_rtk_1_1_rtcm_data.md) -* [class ServerUtility](classmavsdk_1_1_server_utility.md) -* [class Shell](classmavsdk_1_1_shell.md) -* [class System](classmavsdk_1_1_system.md) - * [struct AutopilotVersion](structmavsdk_1_1_system_1_1_autopilot_version.md) -* [class Telemetry](classmavsdk_1_1_telemetry.md) - * [struct AccelerationFrd](structmavsdk_1_1_telemetry_1_1_acceleration_frd.md) - * [struct ActuatorControlTarget](structmavsdk_1_1_telemetry_1_1_actuator_control_target.md) - * [struct ActuatorOutputStatus](structmavsdk_1_1_telemetry_1_1_actuator_output_status.md) - * [struct Altitude](structmavsdk_1_1_telemetry_1_1_altitude.md) - * [struct AngularVelocityBody](structmavsdk_1_1_telemetry_1_1_angular_velocity_body.md) - * [struct AngularVelocityNed](structmavsdk_1_1_telemetry_1_1_angular_velocity_frd.md) - * [struct Battery](structmavsdk_1_1_telemetry_1_1_battery.md) - * [struct Covariance](structmavsdk_1_1_telemetry_1_1_covariance.md) - * [struct DistanceSensor](structmavsdk_1_1_telemetry_1_1_distance_sensor.md) - * [struct EulerAngle](structmavsdk_1_1_telemetry_1_1_euler_angle.md) - * [struct FixedwingMetrics](structmavsdk_1_1_telemetry_1_1_fixedwing_metrics.md) - * [struct GpsInfo](structmavsdk_1_1_telemetry_1_1_gps_info.md) - * [struct GpsGlobalOrigin](structmavsdk_1_1_telemetry_1_1_gps_global_origin.md) - * [struct GroundTruth](structmavsdk_1_1_telemetry_1_1_ground_truth.md) - * [struct Heading](structmavsdk_1_1_telemetry_1_1_heading.md) - * [struct Health](structmavsdk_1_1_telemetry_1_1_health.md) - * [struct Imu](structmavsdk_1_1_telemetry_1_1_imu.md) - * [struct MagneticFieldFrd](structmavsdk_1_1_telemetry_1_1_magnetic_field_frd.md) - * [struct Odometry](structmavsdk_1_1_telemetry_1_1_odometry.md) - * [struct Position](structmavsdk_1_1_telemetry_1_1_position.md) - * [struct PositionBody](structmavsdk_1_1_telemetry_1_1_position_body.md) - * [struct PositionNed](structmavsdk_1_1_telemetry_1_1_position_ned.md) - * [struct VelocityNed](structmavsdk_1_1_telemetry_1_1_velocity_ned.md) - * [struct VelocityBody](structmavsdk_1_1_telemetry_1_1_velocity_body.md) - * [struct PositionVelocityNed](structmavsdk_1_1_telemetry_1_1_position_velocity_ned.md) - * [struct Quaternion](structmavsdk_1_1_telemetry_1_1_quaternion.md) - * [struct RawGps](structmavsdk_1_1_telemetry_1_1_raw_gps.md) - * [struct RcStatus](structmavsdk_1_1_telemetry_1_1_rc_status.md) - * [struct ScaledPressure](structmavsdk_1_1_telemetry_1_1_scaled_pressure.md) - * [struct StatusText](structmavsdk_1_1_telemetry_1_1_status_text.md) -* [class TelemetryServer](classmavsdk_1_1_telemetry_server.md) - * [struct AccelerationFrd](structmavsdk_1_1_telemetry_server_1_1_acceleration_frd.md) - * [struct ActuatorControlTarget](structmavsdk_1_1_telemetry_server_1_1_actuator_control_target.md) - * [struct ActuatorOutputStatus](structmavsdk_1_1_telemetry_server_1_1_actuator_output_status.md) - * [struct AngularVelocityBody](structmavsdk_1_1_telemetry_server_1_1_angular_velocity_body.md) - * [struct AngularVelocityFrd](structmavsdk_1_1_telemetry_server_1_1_angular_velocity_frd.md) - * [struct Battery](structmavsdk_1_1_telemetry_server_1_1_battery.md) - * [struct Covariance](structmavsdk_1_1_telemetry_server_1_1_covariance.md) - * [struct DistanceSensor](structmavsdk_1_1_telemetry_server_1_1_distance_sensor.md) - * [struct EulerAngle](structmavsdk_1_1_telemetry_server_1_1_euler_angle.md) - * [struct FixedwingMetrics](structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md) - * [struct GpsInfo](structmavsdk_1_1_telemetry_server_1_1_gps_info.md) - * [struct GroundTruth](structmavsdk_1_1_telemetry_server_1_1_ground_truth.md) - * [struct Heading](structmavsdk_1_1_telemetry_server_1_1_heading.md) - * [struct Imu](structmavsdk_1_1_telemetry_server_1_1_imu.md) - * [struct MagneticFieldFrd](structmavsdk_1_1_telemetry_server_1_1_magnetic_field_frd.md) - * [struct Odometry](structmavsdk_1_1_telemetry_server_1_1_odometry.md) - * [struct Position](structmavsdk_1_1_telemetry_server_1_1_position.md) - * [struct PositionBody](structmavsdk_1_1_telemetry_server_1_1_position_body.md) - * [struct PositionNed](structmavsdk_1_1_telemetry_server_1_1_position_ned.md) - * [struct PositionVelocityNed](structmavsdk_1_1_telemetry_server_1_1_position_velocity_ned.md) - * [struct Quaternion](structmavsdk_1_1_telemetry_server_1_1_quaternion.md) - * [struct RawGps](structmavsdk_1_1_telemetry_server_1_1_raw_gps.md) - * [struct RcStatus](structmavsdk_1_1_telemetry_server_1_1_rc_status.md) - * [struct ScaledPressure](structmavsdk_1_1_telemetry_server_1_1_scaled_pressure.md) - * [struct StatusText](structmavsdk_1_1_telemetry_server_1_1_status_text.md) - * [struct VelocityBody](structmavsdk_1_1_telemetry_server_1_1_velocity_body.md) - * [struct VelocityNed](structmavsdk_1_1_telemetry_server_1_1_velocity_ned.md) -* [class TrackingServer](classmavsdk_1_1_tracking_server.md) - * [struct TrackPoint](structmavsdk_1_1_tracking_server_1_1_track_point.md) - * [struct TrackRectangle](structmavsdk_1_1_tracking_server_1_1_track_rectangle.md) -* [class Transponder](classmavsdk_1_1_transponder.md) - * [struct AdsbVehicle](structmavsdk_1_1_transponder_1_1_adsb_vehicle.md) -* [class Tune](classmavsdk_1_1_tune.md) - * [struct TuneDescription](structmavsdk_1_1_tune_1_1_tune_description.md) -* [class Winch](classmavsdk_1_1_winch.md) - * [struct Status](en/cpp/api_reference/structmavsdk_1_1_winch_1_1_status.md) - * [struct StatusFlags](en/cpp/api_reference/structmavsdk_1_1_winch_1_1_status_flags.md) -* [class PluginBase](classmavsdk_1_1_plugin_base.md) -* [class Overloaded](structmavsdk_1_1overloaded.md) -* [class CallbackList](classmavsdk_1_1_callback_list.md) -* [class CallbackListImpl](classmavsdk_1_1_callback_list_impl.md) -* [class Handle](classmavsdk_1_1_handle.md) -* [class FakeHandle](classmavsdk_1_1_fake_handle.md) -* [class ServerComponent](classmavsdk_1_1_server_component.md) -* [class ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) -* [namespace mavsdk (globals)](namespacemavsdk.md) - +The API reference for MAVSDK C++ is generated from docstrings using doxygen in CI. diff --git a/docs/en/cpp/api_reference/namespacemavsdk.md b/docs/en/cpp/api_reference/namespacemavsdk.md index 5014f40ba0..6c6cebf8f2 100644 --- a/docs/en/cpp/api_reference/namespacemavsdk.md +++ b/docs/en/cpp/api_reference/namespacemavsdk.md @@ -7,55 +7,58 @@ Namespace for all mavsdk types. ## Data Structures -* [mavsdk::CallbackListImpl](classmavsdk_1_1_callback_list_impl.md) -* [mavsdk::CallbackList](classmavsdk_1_1_callback_list.md) -* [mavsdk::FakeHandle](classmavsdk_1_1_fake_handle.md) -* [mavsdk::Handle](classmavsdk_1_1_handle.md) -* [mavsdk::Mavsdk](classmavsdk_1_1_mavsdk.md) -* [mavsdk::overloaded](structmavsdk_1_1overloaded.md) -* [mavsdk::PluginBase](classmavsdk_1_1_plugin_base.md) * [mavsdk::Action](classmavsdk_1_1_action.md) * [mavsdk::ActionServer](classmavsdk_1_1_action_server.md) +* [mavsdk::ArmAuthorizerServer](classmavsdk_1_1_arm_authorizer_server.md) * [mavsdk::Calibration](classmavsdk_1_1_calibration.md) * [mavsdk::Camera](classmavsdk_1_1_camera.md) * [mavsdk::CameraServer](classmavsdk_1_1_camera_server.md) -* [mavsdk::ComponentInformation](classmavsdk_1_1_component_information.md) -* [mavsdk::ComponentInformationServer](classmavsdk_1_1_component_information_server.md) +* [mavsdk::ComponentMetadata](classmavsdk_1_1_component_metadata.md) +* [mavsdk::ComponentMetadataServer](classmavsdk_1_1_component_metadata_server.md) +* [mavsdk::Events](classmavsdk_1_1_events.md) * [mavsdk::Failure](classmavsdk_1_1_failure.md) +* [mavsdk::FakeHandle](classmavsdk_1_1_fake_handle.md) * [mavsdk::FollowMe](classmavsdk_1_1_follow_me.md) * [mavsdk::Ftp](classmavsdk_1_1_ftp.md) * [mavsdk::FtpServer](classmavsdk_1_1_ftp_server.md) * [mavsdk::Geofence](classmavsdk_1_1_geofence.md) * [mavsdk::Gimbal](classmavsdk_1_1_gimbal.md) * [mavsdk::Gripper](classmavsdk_1_1_gripper.md) +* [mavsdk::Handle](classmavsdk_1_1_handle.md) +* [mavsdk::HandleFactory](classmavsdk_1_1_handle_factory.md) * [mavsdk::Info](classmavsdk_1_1_info.md) * [mavsdk::LogFiles](classmavsdk_1_1_log_files.md) +* [mavsdk::LogStreaming](classmavsdk_1_1_log_streaming.md) * [mavsdk::ManualControl](classmavsdk_1_1_manual_control.md) * [mavsdk::MavlinkPassthrough](classmavsdk_1_1_mavlink_passthrough.md) +* [mavsdk::Mavsdk](classmavsdk_1_1_mavsdk.md) * [mavsdk::Mission](classmavsdk_1_1_mission.md) * [mavsdk::MissionRaw](classmavsdk_1_1_mission_raw.md) * [mavsdk::MissionRawServer](classmavsdk_1_1_mission_raw_server.md) * [mavsdk::Mocap](classmavsdk_1_1_mocap.md) * [mavsdk::Offboard](classmavsdk_1_1_offboard.md) +* [mavsdk::overloaded](structmavsdk_1_1overloaded.md) * [mavsdk::Param](classmavsdk_1_1_param.md) * [mavsdk::ParamServer](classmavsdk_1_1_param_server.md) +* [mavsdk::PluginBase](classmavsdk_1_1_plugin_base.md) * [mavsdk::Rtk](classmavsdk_1_1_rtk.md) +* [mavsdk::ServerComponent](classmavsdk_1_1_server_component.md) +* [mavsdk::ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) * [mavsdk::ServerUtility](classmavsdk_1_1_server_utility.md) * [mavsdk::Shell](classmavsdk_1_1_shell.md) +* [mavsdk::System](classmavsdk_1_1_system.md) * [mavsdk::Telemetry](classmavsdk_1_1_telemetry.md) * [mavsdk::TelemetryServer](classmavsdk_1_1_telemetry_server.md) -* [mavsdk::TrackingServer](classmavsdk_1_1_tracking_server.md) * [mavsdk::Transponder](classmavsdk_1_1_transponder.md) * [mavsdk::Tune](classmavsdk_1_1_tune.md) * [mavsdk::Winch](classmavsdk_1_1_winch.md) -* [mavsdk::ServerComponent](classmavsdk_1_1_server_component.md) -* [mavsdk::ServerPluginBase](classmavsdk_1_1_server_plugin_base.md) -* [mavsdk::System](classmavsdk_1_1_system.md) ## Enumerations Type | Description --- | --- +enum [Autopilot](#namespacemavsdk_1aba05635d1785223a4d7b457ae0407297) | Autopilot type. +enum [ComponentType](#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12) | ComponentType of configurations, used for automatic ID setting. enum [ConnectionResult](#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) | Result type returned when adding a connection. enum [ForwardingOption](#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) | ForwardingOption for Connection, used to set message forwarding option. @@ -63,12 +66,53 @@ enum [ForwardingOption](#namespacemavsdk_1a7066729108eae8a605d4dd169e4581b9) | F Type | Name | Description --- | --- | --- -std::ostream & | [operator<<](#namespacemavsdk_1a3307e6cbeb3dba8551dcde4b873691d3) (std::ostream & str, const [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) & result) | Stream operator to print information about a `ConnectionResult`. +std::string | [base64_encode](#namespacemavsdk_1a57a9962be22a61e5c36a66bc17e6a2a7) (std::vector< uint8_t > & raw) | Encode raw bytes to a base64 string. +std::vector< uint8_t > | [base64_decode](#namespacemavsdk_1a34e7609c9e2ddcc72a74bbc79daf9c19) (const std::string & str) | Decode a base64 string into raw bytes. +std::ostream & | [operator<<](#namespacemavsdk_1a2aa91d8b846b07fe7f305b399375ce5f) (std::ostream & str, const [ConnectionResult](namespacemavsdk.md#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992) & result) | Stream operator to print information about a `ConnectionResult`.   | [overloaded](#namespacemavsdk_1a724e321aaff91eb2ba28279e0292e552) (Ts...)-> overloaded< Ts... > | Template deduction helper for `overloaded` ## Enumeration Type Documentation +### enum Autopilot {#namespacemavsdk_1aba05635d1785223a4d7b457ae0407297} + +``` +#include: autopilot.h +``` + + +Autopilot type. + + +Value | Description +--- | --- + `Unknown` | + `Px4` | + `ArduPilot` | + +### enum ComponentType {#namespacemavsdk_1a20fe7f7c8312779a187017111bf33d12} + +``` +#include: component_type.h +``` + + +ComponentType of configurations, used for automatic ID setting. + + +Value | Description +--- | --- + `Autopilot` | SDK is used as an autopilot. + `GroundStation` | SDK is used as a ground station. + `CompanionComputer` | SDK is used as a companion computer on board the MAV. + `Camera` | + `Gimbal` | SDK is used as a camera. < + `RemoteId` | SDK is used as a gimbal. < + `Custom` | SDK is used as a RemoteId system. < + + +the SDK is used in a custom configuration, no automatic ID will be provided + ### enum ConnectionResult {#namespacemavsdk_1a0bad93f6d037051ac3906a0bcc09f992} ``` @@ -78,7 +122,7 @@ std::ostream & | [operator<<](#namespacemavsdk_1a3307e6cbeb3dba8551dcde4b873691d Result type returned when adding a connection. -**Note**: [Mavsdk](classmavsdk_1_1_mavsdk.md) does not throw exceptions. Instead a result of this type will be returned when you add a connection: add_udp_connection(). +**Note**: [Mavsdk](classmavsdk_1_1_mavsdk.md) does not throw exceptions. Instead a result of this type will be returned. Value | Description --- | --- @@ -115,13 +159,55 @@ Value | Description ## Function Documentation -### operator<<() {#namespacemavsdk_1a3307e6cbeb3dba8551dcde4b873691d3} +### base64_encode() {#namespacemavsdk_1a57a9962be22a61e5c36a66bc17e6a2a7} + +``` +#include: base64.h +``` +```cpp +std::string mavsdk::base64_encode(std::vector< uint8_t > &raw) +``` + + +Encode raw bytes to a base64 string. + + +**Parameters** + +* std::vector< uint8_t >& **raw** - Raw bytes + +**Returns** + + std::string - Base64 string + +### base64_decode() {#namespacemavsdk_1a34e7609c9e2ddcc72a74bbc79daf9c19} + +``` +#include: base64.h +``` +```cpp +std::vector< uint8_t > mavsdk::base64_decode(const std::string &str) +``` + + +Decode a base64 string into raw bytes. + + +**Parameters** + +* const std::string& **str** - Base64 string + +**Returns** + + std::vector< uint8_t > - Raw bytes + +### operator<<() {#namespacemavsdk_1a2aa91d8b846b07fe7f305b399375ce5f} ``` #include: connection_result.h ``` ```cpp -std::ostream& mavsdk::operator<<(std::ostream &str, const ConnectionResult &result) +std::ostream & mavsdk::operator<<(std::ostream &str, const ConnectionResult &result) ``` diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_camera_list.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_camera_list.md new file mode 100644 index 0000000000..85ca264718 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_camera_list.md @@ -0,0 +1,27 @@ +# mavsdk::Camera::CameraList Struct Reference +`#include: camera.h` + +---- + + +[Camera](classmavsdk_1_1_camera.md) list. + + +## Data Fields + + +std::vector< [Information](structmavsdk_1_1_camera_1_1_information.md) > [cameras](#structmavsdk_1_1_camera_1_1_camera_list_1a76a0bbf4a52e7601e4e6677a64687dcd) {} - [Camera](classmavsdk_1_1_camera.md) items. + + +## Field Documentation + + +### cameras {#structmavsdk_1_1_camera_1_1_camera_list_1a76a0bbf4a52e7601e4e6677a64687dcd} + +```cpp +std::vector mavsdk::Camera::CameraList::cameras {} +``` + + +[Camera](classmavsdk_1_1_camera.md) items. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_capture_info.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_capture_info.md index f9da429364..4ec6494957 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_capture_info.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_capture_info.md @@ -10,6 +10,8 @@ ## Data Fields +int32_t [component_id](#structmavsdk_1_1_camera_1_1_capture_info_1a4911c3f31733e87c2a189a598889ef85) {} - Component ID. + [Position](structmavsdk_1_1_camera_1_1_position.md) [position](#structmavsdk_1_1_camera_1_1_capture_info_1a570779eaff94d3cf3c1a160938096d0f) {} - Location where the picture was taken. [Quaternion](structmavsdk_1_1_camera_1_1_quaternion.md) [attitude_quaternion](#structmavsdk_1_1_camera_1_1_capture_info_1add20201828d0e0a82a6ee6366022abc4) {} - Attitude of the camera when the picture was taken (quaternion) @@ -28,6 +30,16 @@ std::string [file_url](#structmavsdk_1_1_camera_1_1_capture_info_1a6fa362c6a13fe ## Field Documentation +### component_id {#structmavsdk_1_1_camera_1_1_capture_info_1a4911c3f31733e87c2a189a598889ef85} + +```cpp +int32_t mavsdk::Camera::CaptureInfo::component_id {} +``` + + +Component ID. + + ### position {#structmavsdk_1_1_camera_1_1_capture_info_1a570779eaff94d3cf3c1a160938096d0f} ```cpp diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_current_settings_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_current_settings_update.md new file mode 100644 index 0000000000..2e7f73d383 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_current_settings_update.md @@ -0,0 +1,39 @@ +# mavsdk::Camera::CurrentSettingsUpdate Struct Reference +`#include: camera.h` + +---- + + +An update about a current setting. + + +## Data Fields + + +int32_t [component_id](#structmavsdk_1_1_camera_1_1_current_settings_update_1ac558277e13980dbebac288334741d163) {} - Component ID. + +std::vector< [Setting](structmavsdk_1_1_camera_1_1_setting.md) > [current_settings](#structmavsdk_1_1_camera_1_1_current_settings_update_1a459873efe09aec15c83fd78eab046cc7) {} - List of current settings. + + +## Field Documentation + + +### component_id {#structmavsdk_1_1_camera_1_1_current_settings_update_1ac558277e13980dbebac288334741d163} + +```cpp +int32_t mavsdk::Camera::CurrentSettingsUpdate::component_id {} +``` + + +Component ID. + + +### current_settings {#structmavsdk_1_1_camera_1_1_current_settings_update_1a459873efe09aec15c83fd78eab046cc7} + +```cpp +std::vector mavsdk::Camera::CurrentSettingsUpdate::current_settings {} +``` + + +List of current settings. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_information.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_information.md index 4b130d37e8..82368a86fc 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_information.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_information.md @@ -10,6 +10,8 @@ Type to represent a camera information. ## Data Fields +int32_t [component_id](#structmavsdk_1_1_camera_1_1_information_1a2312a17b4f00a1bb55489a72d70de2e4) {} - Component ID. + std::string [vendor_name](#structmavsdk_1_1_camera_1_1_information_1a54c399e4a570ff8a96b4cd4c01651834) {} - Name of the camera vendor. std::string [model_name](#structmavsdk_1_1_camera_1_1_information_1a500232dfe9359366211cd303cc702eaa) {} - Name of the camera model. @@ -28,6 +30,16 @@ uint32_t [vertical_resolution_px](#structmavsdk_1_1_camera_1_1_information_1a2c1 ## Field Documentation +### component_id {#structmavsdk_1_1_camera_1_1_information_1a2312a17b4f00a1bb55489a72d70de2e4} + +```cpp +int32_t mavsdk::Camera::Information::component_id {} +``` + + +Component ID. + + ### vendor_name {#structmavsdk_1_1_camera_1_1_information_1a54c399e4a570ff8a96b4cd4c01651834} ```cpp diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_mode_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_mode_update.md new file mode 100644 index 0000000000..f3af90786a --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_mode_update.md @@ -0,0 +1,39 @@ +# mavsdk::Camera::ModeUpdate Struct Reference +`#include: camera.h` + +---- + + +An update about the current mode. + + +## Data Fields + + +int32_t [component_id](#structmavsdk_1_1_camera_1_1_mode_update_1acda4b5cbba763ea7d874c8d92cdf9faf) {} - Component ID. + +[Mode](classmavsdk_1_1_camera.md#classmavsdk_1_1_camera_1a02bb5ce37d125ba4c65d43f172cc2d65) [mode](#structmavsdk_1_1_camera_1_1_mode_update_1a3c11b44397c4fb63082fd0c05da302aa) {} - [Camera](classmavsdk_1_1_camera.md) mode. + + +## Field Documentation + + +### component_id {#structmavsdk_1_1_camera_1_1_mode_update_1acda4b5cbba763ea7d874c8d92cdf9faf} + +```cpp +int32_t mavsdk::Camera::ModeUpdate::component_id {} +``` + + +Component ID. + + +### mode {#structmavsdk_1_1_camera_1_1_mode_update_1a3c11b44397c4fb63082fd0c05da302aa} + +```cpp +Mode mavsdk::Camera::ModeUpdate::mode {} +``` + + +[Camera](classmavsdk_1_1_camera.md) mode. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_possible_setting_options_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_possible_setting_options_update.md new file mode 100644 index 0000000000..ba5edc52e7 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_possible_setting_options_update.md @@ -0,0 +1,39 @@ +# mavsdk::Camera::PossibleSettingOptionsUpdate Struct Reference +`#include: camera.h` + +---- + + +An update about possible setting options. + + +## Data Fields + + +int32_t [component_id](#structmavsdk_1_1_camera_1_1_possible_setting_options_update_1a2e9c2092ebd74c24bfbca3640fdd717b) {} - Component ID. + +std::vector< [SettingOptions](structmavsdk_1_1_camera_1_1_setting_options.md) > [setting_options](#structmavsdk_1_1_camera_1_1_possible_setting_options_update_1a215577526139988181681a0d6eb5c2f0) {} - List of settings that can be changed. + + +## Field Documentation + + +### component_id {#structmavsdk_1_1_camera_1_1_possible_setting_options_update_1a2e9c2092ebd74c24bfbca3640fdd717b} + +```cpp +int32_t mavsdk::Camera::PossibleSettingOptionsUpdate::component_id {} +``` + + +Component ID. + + +### setting_options {#structmavsdk_1_1_camera_1_1_possible_setting_options_update_1a215577526139988181681a0d6eb5c2f0} + +```cpp +std::vector mavsdk::Camera::PossibleSettingOptionsUpdate::setting_options {} +``` + + +List of settings that can be changed. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_setting_options.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_setting_options.md index c2f72a90d2..337420a737 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_setting_options.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_setting_options.md @@ -10,6 +10,8 @@ Type to represent a setting with a list of options to choose from. ## Data Fields +int32_t [component_id](#structmavsdk_1_1_camera_1_1_setting_options_1ad497c229df9899af7e76226664ced72d) {} - Component ID. + std::string [setting_id](#structmavsdk_1_1_camera_1_1_setting_options_1aca647af6e140ee78b41d85565d673f14) {} - Name of the setting (machine readable) std::string [setting_description](#structmavsdk_1_1_camera_1_1_setting_options_1a8902e7f9dfc25ee9c8363cf5f4775b92) {} - Description of the setting (human readable) @@ -22,6 +24,16 @@ bool [is_range](#structmavsdk_1_1_camera_1_1_setting_options_1af6459fc1e354ec95f ## Field Documentation +### component_id {#structmavsdk_1_1_camera_1_1_setting_options_1ad497c229df9899af7e76226664ced72d} + +```cpp +int32_t mavsdk::Camera::SettingOptions::component_id {} +``` + + +Component ID. + + ### setting_id {#structmavsdk_1_1_camera_1_1_setting_options_1aca647af6e140ee78b41d85565d673f14} ```cpp diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_status.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_status.md deleted file mode 100644 index 17355af0e0..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_status.md +++ /dev/null @@ -1,174 +0,0 @@ -# mavsdk::Camera::Status Struct Reference -`#include: camera.h` - ----- - - -[Information](structmavsdk_1_1_camera_1_1_information.md) about the camera status. - - -## Public Types - - -Type | Description ---- | --- -enum [StorageStatus](#structmavsdk_1_1_camera_1_1_status_1ae4e4a1e5622e75cce5813ffdf2ffcc52) | Storage status type. -enum [StorageType](#structmavsdk_1_1_camera_1_1_status_1a2e4c017d9eb4449a1695269a401648fb) | Storage type. - -## Data Fields - - -bool [video_on](#structmavsdk_1_1_camera_1_1_status_1a08db484755b36139b96d7a53620480c3) {} - Whether video recording is currently in process. - -bool [photo_interval_on](#structmavsdk_1_1_camera_1_1_status_1aa04f9bf95629beb73edc605ff6d0a244) {} - Whether a photo interval is currently in process. - -float [used_storage_mib](#structmavsdk_1_1_camera_1_1_status_1a235ad5628e6aac6f9e9614c29b3a86d9) {} - Used storage (in MiB) - -float [available_storage_mib](#structmavsdk_1_1_camera_1_1_status_1a41a3988f991a338a46d90df698358dd1) {} - Available storage (in MiB) - -float [total_storage_mib](#structmavsdk_1_1_camera_1_1_status_1a9ddfe7a46bc22616553bec58c6b6ecc1) {} - Total storage (in MiB) - -float [recording_time_s](#structmavsdk_1_1_camera_1_1_status_1a0c721ba431bb2708bc87f96c043a1a5d) {} - Elapsed time since starting the video recording (in seconds) - -std::string [media_folder_name](#structmavsdk_1_1_camera_1_1_status_1a37ed53027e526dececc6b06c2db1cddc) {} - Current folder name where media are saved. - -[StorageStatus](structmavsdk_1_1_camera_1_1_status.md#structmavsdk_1_1_camera_1_1_status_1ae4e4a1e5622e75cce5813ffdf2ffcc52) [storage_status](#structmavsdk_1_1_camera_1_1_status_1a7a8e6d37bce3e2a97c9e71d5b6ea6536) {} - Storage status. - -uint32_t [storage_id](#structmavsdk_1_1_camera_1_1_status_1a2abcc09bd9f5b657698d56cb4bd6ef4c) {} - Storage ID starting at 1. - -[StorageType](structmavsdk_1_1_camera_1_1_status.md#structmavsdk_1_1_camera_1_1_status_1a2e4c017d9eb4449a1695269a401648fb) [storage_type](#structmavsdk_1_1_camera_1_1_status_1a92decb1a85b16d505bd17e71740c221a) {} - Storage type. - - -## Member Enumeration Documentation - - -### enum StorageStatus {#structmavsdk_1_1_camera_1_1_status_1ae4e4a1e5622e75cce5813ffdf2ffcc52} - - -Storage status type. - - -Value | Description ---- | --- - `NotAvailable` | [Status](structmavsdk_1_1_camera_1_1_status.md) not available. - `Unformatted` | Storage is not formatted (i.e. has no recognized file system). - `Formatted` | Storage is formatted (i.e. has recognized a file system). - `NotSupported` | Storage status is not supported. - -### enum StorageType {#structmavsdk_1_1_camera_1_1_status_1a2e4c017d9eb4449a1695269a401648fb} - - -Storage type. - - -Value | Description ---- | --- - `Unknown` | Storage type unknown. - `UsbStick` | Storage type USB stick. - `Sd` | Storage type SD card. - `Microsd` | Storage type MicroSD card. - `Hd` | Storage type HD mass storage. - `Other` | Storage type other, not listed. - -## Field Documentation - - -### video_on {#structmavsdk_1_1_camera_1_1_status_1a08db484755b36139b96d7a53620480c3} - -```cpp -bool mavsdk::Camera::Status::video_on {} -``` - - -Whether video recording is currently in process. - - -### photo_interval_on {#structmavsdk_1_1_camera_1_1_status_1aa04f9bf95629beb73edc605ff6d0a244} - -```cpp -bool mavsdk::Camera::Status::photo_interval_on {} -``` - - -Whether a photo interval is currently in process. - - -### used_storage_mib {#structmavsdk_1_1_camera_1_1_status_1a235ad5628e6aac6f9e9614c29b3a86d9} - -```cpp -float mavsdk::Camera::Status::used_storage_mib {} -``` - - -Used storage (in MiB) - - -### available_storage_mib {#structmavsdk_1_1_camera_1_1_status_1a41a3988f991a338a46d90df698358dd1} - -```cpp -float mavsdk::Camera::Status::available_storage_mib {} -``` - - -Available storage (in MiB) - - -### total_storage_mib {#structmavsdk_1_1_camera_1_1_status_1a9ddfe7a46bc22616553bec58c6b6ecc1} - -```cpp -float mavsdk::Camera::Status::total_storage_mib {} -``` - - -Total storage (in MiB) - - -### recording_time_s {#structmavsdk_1_1_camera_1_1_status_1a0c721ba431bb2708bc87f96c043a1a5d} - -```cpp -float mavsdk::Camera::Status::recording_time_s {} -``` - - -Elapsed time since starting the video recording (in seconds) - - -### media_folder_name {#structmavsdk_1_1_camera_1_1_status_1a37ed53027e526dececc6b06c2db1cddc} - -```cpp -std::string mavsdk::Camera::Status::media_folder_name {} -``` - - -Current folder name where media are saved. - - -### storage_status {#structmavsdk_1_1_camera_1_1_status_1a7a8e6d37bce3e2a97c9e71d5b6ea6536} - -```cpp -StorageStatus mavsdk::Camera::Status::storage_status {} -``` - - -Storage status. - - -### storage_id {#structmavsdk_1_1_camera_1_1_status_1a2abcc09bd9f5b657698d56cb4bd6ef4c} - -```cpp -uint32_t mavsdk::Camera::Status::storage_id {} -``` - - -Storage ID starting at 1. - - -### storage_type {#structmavsdk_1_1_camera_1_1_status_1a92decb1a85b16d505bd17e71740c221a} - -```cpp -StorageType mavsdk::Camera::Status::storage_type {} -``` - - -Storage type. - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_storage.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_storage.md new file mode 100644 index 0000000000..4e85473809 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_storage.md @@ -0,0 +1,186 @@ +# mavsdk::Camera::Storage Struct Reference +`#include: camera.h` + +---- + + +[Information](structmavsdk_1_1_camera_1_1_information.md) about the camera's storage status. + + +## Public Types + + +Type | Description +--- | --- +enum [StorageStatus](#structmavsdk_1_1_camera_1_1_storage_1a57ec40da608871d2a23fc6460a4bc49a) | [Storage](structmavsdk_1_1_camera_1_1_storage.md) status type. +enum [StorageType](#structmavsdk_1_1_camera_1_1_storage_1a404236fdf8dbab2570b3fc9cbeb4e290) | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type. + +## Data Fields + + +int32_t [component_id](#structmavsdk_1_1_camera_1_1_storage_1a3a8040ef921dec7b5b77e9bfb2406036) {} - Component ID. + +bool [video_on](#structmavsdk_1_1_camera_1_1_storage_1aee007d646be2f4c6d32d8c23e1a83dc4) {} - Whether video recording is currently in process. + +bool [photo_interval_on](#structmavsdk_1_1_camera_1_1_storage_1a91d5c2e653642b949889f5236ff7e1ae) {} - Whether a photo interval is currently in process. + +float [used_storage_mib](#structmavsdk_1_1_camera_1_1_storage_1a524b19eb489baf9ac1eea908baf9cdd9) {} - Used storage (in MiB) + +float [available_storage_mib](#structmavsdk_1_1_camera_1_1_storage_1a0f529192063ce6888c7411cce720ecc1) {} - Available storage (in MiB) + +float [total_storage_mib](#structmavsdk_1_1_camera_1_1_storage_1a40b4ca56b8bd923fea7c50b43d1ae891) {} - Total storage (in MiB) + +float [recording_time_s](#structmavsdk_1_1_camera_1_1_storage_1a903999c7001fe1f025369b35a3908a20) {} - Elapsed time since starting the video recording (in seconds) + +std::string [media_folder_name](#structmavsdk_1_1_camera_1_1_storage_1a210b8451c96810b54bcb7359a934a663) {} - Current folder name where media are saved. + +[StorageStatus](structmavsdk_1_1_camera_1_1_storage.md#structmavsdk_1_1_camera_1_1_storage_1a57ec40da608871d2a23fc6460a4bc49a) [storage_status](#structmavsdk_1_1_camera_1_1_storage_1a7547bb3cb47e22f64f21026ebbca890e) {} - [Storage](structmavsdk_1_1_camera_1_1_storage.md) status. + +uint32_t [storage_id](#structmavsdk_1_1_camera_1_1_storage_1aa534f7cec458d9cbb075675e91db4127) {} - [Storage](structmavsdk_1_1_camera_1_1_storage.md) ID starting at 1. + +[StorageType](structmavsdk_1_1_camera_1_1_storage.md#structmavsdk_1_1_camera_1_1_storage_1a404236fdf8dbab2570b3fc9cbeb4e290) [storage_type](#structmavsdk_1_1_camera_1_1_storage_1a193dc7d75ea3278f81e73793d61ba8a5) {} - [Storage](structmavsdk_1_1_camera_1_1_storage.md) type. + + +## Member Enumeration Documentation + + +### enum StorageStatus {#structmavsdk_1_1_camera_1_1_storage_1a57ec40da608871d2a23fc6460a4bc49a} + + +[Storage](structmavsdk_1_1_camera_1_1_storage.md) status type. + + +Value | Description +--- | --- + `NotAvailable` | Status not available. + `Unformatted` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) is not formatted (i.e. has no recognized file system). + `Formatted` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) is formatted (i.e. has recognized a file system). + `NotSupported` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) status is not supported. + +### enum StorageType {#structmavsdk_1_1_camera_1_1_storage_1a404236fdf8dbab2570b3fc9cbeb4e290} + + +[Storage](structmavsdk_1_1_camera_1_1_storage.md) type. + + +Value | Description +--- | --- + `Unknown` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type unknown. + `UsbStick` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type USB stick. + `Sd` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type SD card. + `Microsd` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type MicroSD card. + `Hd` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type HD mass storage. + `Other` | [Storage](structmavsdk_1_1_camera_1_1_storage.md) type other, not listed. + +## Field Documentation + + +### component_id {#structmavsdk_1_1_camera_1_1_storage_1a3a8040ef921dec7b5b77e9bfb2406036} + +```cpp +int32_t mavsdk::Camera::Storage::component_id {} +``` + + +Component ID. + + +### video_on {#structmavsdk_1_1_camera_1_1_storage_1aee007d646be2f4c6d32d8c23e1a83dc4} + +```cpp +bool mavsdk::Camera::Storage::video_on {} +``` + + +Whether video recording is currently in process. + + +### photo_interval_on {#structmavsdk_1_1_camera_1_1_storage_1a91d5c2e653642b949889f5236ff7e1ae} + +```cpp +bool mavsdk::Camera::Storage::photo_interval_on {} +``` + + +Whether a photo interval is currently in process. + + +### used_storage_mib {#structmavsdk_1_1_camera_1_1_storage_1a524b19eb489baf9ac1eea908baf9cdd9} + +```cpp +float mavsdk::Camera::Storage::used_storage_mib {} +``` + + +Used storage (in MiB) + + +### available_storage_mib {#structmavsdk_1_1_camera_1_1_storage_1a0f529192063ce6888c7411cce720ecc1} + +```cpp +float mavsdk::Camera::Storage::available_storage_mib {} +``` + + +Available storage (in MiB) + + +### total_storage_mib {#structmavsdk_1_1_camera_1_1_storage_1a40b4ca56b8bd923fea7c50b43d1ae891} + +```cpp +float mavsdk::Camera::Storage::total_storage_mib {} +``` + + +Total storage (in MiB) + + +### recording_time_s {#structmavsdk_1_1_camera_1_1_storage_1a903999c7001fe1f025369b35a3908a20} + +```cpp +float mavsdk::Camera::Storage::recording_time_s {} +``` + + +Elapsed time since starting the video recording (in seconds) + + +### media_folder_name {#structmavsdk_1_1_camera_1_1_storage_1a210b8451c96810b54bcb7359a934a663} + +```cpp +std::string mavsdk::Camera::Storage::media_folder_name {} +``` + + +Current folder name where media are saved. + + +### storage_status {#structmavsdk_1_1_camera_1_1_storage_1a7547bb3cb47e22f64f21026ebbca890e} + +```cpp +StorageStatus mavsdk::Camera::Storage::storage_status {} +``` + + +[Storage](structmavsdk_1_1_camera_1_1_storage.md) status. + + +### storage_id {#structmavsdk_1_1_camera_1_1_storage_1aa534f7cec458d9cbb075675e91db4127} + +```cpp +uint32_t mavsdk::Camera::Storage::storage_id {} +``` + + +[Storage](structmavsdk_1_1_camera_1_1_storage.md) ID starting at 1. + + +### storage_type {#structmavsdk_1_1_camera_1_1_storage_1a193dc7d75ea3278f81e73793d61ba8a5} + +```cpp +StorageType mavsdk::Camera::Storage::storage_type {} +``` + + +[Storage](structmavsdk_1_1_camera_1_1_storage.md) type. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_storage_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_storage_update.md new file mode 100644 index 0000000000..1571981449 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_storage_update.md @@ -0,0 +1,39 @@ +# mavsdk::Camera::StorageUpdate Struct Reference +`#include: camera.h` + +---- + + +An update about storage. + + +## Data Fields + + +int32_t [component_id](#structmavsdk_1_1_camera_1_1_storage_update_1aed1bead07af742d02ba92ed3bf200705) {} - Component ID. + +[Storage](structmavsdk_1_1_camera_1_1_storage.md) [storage](#structmavsdk_1_1_camera_1_1_storage_update_1afc1aec4724f448b127d0deaab8a4a6e0) {} - [Storage](structmavsdk_1_1_camera_1_1_storage.md). + + +## Field Documentation + + +### component_id {#structmavsdk_1_1_camera_1_1_storage_update_1aed1bead07af742d02ba92ed3bf200705} + +```cpp +int32_t mavsdk::Camera::StorageUpdate::component_id {} +``` + + +Component ID. + + +### storage {#structmavsdk_1_1_camera_1_1_storage_update_1afc1aec4724f448b127d0deaab8a4a6e0} + +```cpp +Storage mavsdk::Camera::StorageUpdate::storage {} +``` + + +[Storage](structmavsdk_1_1_camera_1_1_storage.md). + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_info.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_info.md index fe28e17725..c03370753c 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_info.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_info.md @@ -18,6 +18,8 @@ enum [VideoStreamSpectrum](#structmavsdk_1_1_camera_1_1_video_stream_info_1a51a8 ## Data Fields +int32_t [stream_id](#structmavsdk_1_1_camera_1_1_video_stream_info_1a0b3d94b0885b9f38daa91d4f61315073) {} - Stream ID. + [VideoStreamSettings](structmavsdk_1_1_camera_1_1_video_stream_settings.md) [settings](#structmavsdk_1_1_camera_1_1_video_stream_info_1a11d9b81db8dc7b666ff9cd37d3835ead) {} - Video stream settings. [VideoStreamStatus](structmavsdk_1_1_camera_1_1_video_stream_info.md#structmavsdk_1_1_camera_1_1_video_stream_info_1a1750d70ce75b862be98164b67026d85c) [status](#structmavsdk_1_1_camera_1_1_video_stream_info_1a08c5a2c0f4109d9a61a7e0b7edffde96) {} - Current status of video streaming. @@ -54,6 +56,16 @@ Value | Description ## Field Documentation +### stream_id {#structmavsdk_1_1_camera_1_1_video_stream_info_1a0b3d94b0885b9f38daa91d4f61315073} + +```cpp +int32_t mavsdk::Camera::VideoStreamInfo::stream_id {} +``` + + +Stream ID. + + ### settings {#structmavsdk_1_1_camera_1_1_video_stream_info_1a11d9b81db8dc7b666ff9cd37d3835ead} ```cpp diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_update.md new file mode 100644 index 0000000000..eba361c247 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_1_1_video_stream_update.md @@ -0,0 +1,39 @@ +# mavsdk::Camera::VideoStreamUpdate Struct Reference +`#include: camera.h` + +---- + + +An update about a video stream. + + +## Data Fields + + +int32_t [component_id](#structmavsdk_1_1_camera_1_1_video_stream_update_1a7ea541bdc0355fe7b91f2439c94d4660) {} - Component ID. + +[VideoStreamInfo](structmavsdk_1_1_camera_1_1_video_stream_info.md) [video_stream_info](#structmavsdk_1_1_camera_1_1_video_stream_update_1a8ed2f5bbac8109b35fb6cfe08cba3190) {} - Video stream info. + + +## Field Documentation + + +### component_id {#structmavsdk_1_1_camera_1_1_video_stream_update_1a7ea541bdc0355fe7b91f2439c94d4660} + +```cpp +int32_t mavsdk::Camera::VideoStreamUpdate::component_id {} +``` + + +Component ID. + + +### video_stream_info {#structmavsdk_1_1_camera_1_1_video_stream_update_1a8ed2f5bbac8109b35fb6cfe08cba3190} + +```cpp +VideoStreamInfo mavsdk::Camera::VideoStreamUpdate::video_stream_info {} +``` + + +Video stream info. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_status.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_status.md index 7696752605..d977f8040f 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_status.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_capture_status.md @@ -1,16 +1,19 @@ # mavsdk::CameraServer::CaptureStatus Struct Reference -`#include: UNKNOWN` +`#include: camera_server.h` ---- +Capture status. + + ## Public Types Type | Description --- | --- -enum [ImageStatus](#structmavsdk_1_1_camera_server_1_1_capture_status_1ab9567d4fc7a19f6549f233684f2657cc) | -enum [VideoStatus](#structmavsdk_1_1_camera_server_1_1_capture_status_1aa5805c521b56d734ab6d78be2084397a) | +enum [ImageStatus](#structmavsdk_1_1_camera_server_1_1_capture_status_1ab9567d4fc7a19f6549f233684f2657cc) | The image status. +enum [VideoStatus](#structmavsdk_1_1_camera_server_1_1_capture_status_1aa5805c521b56d734ab6d78be2084397a) | The video status. ## Data Fields @@ -34,6 +37,9 @@ int32_t [image_count](#structmavsdk_1_1_camera_server_1_1_capture_status_1a64feb ### enum ImageStatus {#structmavsdk_1_1_camera_server_1_1_capture_status_1ab9567d4fc7a19f6549f233684f2657cc} +The image status. + + Value | Description --- | --- `Idle` | idle. @@ -44,6 +50,9 @@ Value | Description ### enum VideoStatus {#structmavsdk_1_1_camera_server_1_1_capture_status_1aa5805c521b56d734ab6d78be2084397a} +The video status. + + Value | Description --- | --- `Idle` | idle. diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_information.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_information.md index 608e520cec..2312cc917a 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_information.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_information.md @@ -32,6 +32,10 @@ uint32_t [definition_file_version](#structmavsdk_1_1_camera_server_1_1_informati std::string [definition_file_uri](#structmavsdk_1_1_camera_server_1_1_information_1ac45dbba688c93cafe5750fc352917797) {} - [Camera](classmavsdk_1_1_camera.md) definition URI (http or mavlink ftp) +bool [image_in_video_mode_supported](#structmavsdk_1_1_camera_server_1_1_information_1a9c57eed55bfa60127eed4601becc523f) {} - [Camera](classmavsdk_1_1_camera.md) supports taking images while in video mode. + +bool [video_in_image_mode_supported](#structmavsdk_1_1_camera_server_1_1_information_1a18761cceb1ef3226d87e9752a738145a) {} - [Camera](classmavsdk_1_1_camera.md) supports recording video while in image mode. + ## Field Documentation @@ -145,3 +149,23 @@ std::string mavsdk::CameraServer::Information::definition_file_uri {} [Camera](classmavsdk_1_1_camera.md) definition URI (http or mavlink ftp) + +### image_in_video_mode_supported {#structmavsdk_1_1_camera_server_1_1_information_1a9c57eed55bfa60127eed4601becc523f} + +```cpp +bool mavsdk::CameraServer::Information::image_in_video_mode_supported {} +``` + + +[Camera](classmavsdk_1_1_camera.md) supports taking images while in video mode. + + +### video_in_image_mode_supported {#structmavsdk_1_1_camera_server_1_1_information_1a18761cceb1ef3226d87e9752a738145a} + +```cpp +bool mavsdk::CameraServer::Information::video_in_image_mode_supported {} +``` + + +[Camera](classmavsdk_1_1_camera.md) supports recording video while in image mode. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_point.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_point.md new file mode 100644 index 0000000000..17ee5e2450 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_point.md @@ -0,0 +1,51 @@ +# mavsdk::CameraServer::TrackPoint Struct Reference +`#include: camera_server.h` + +---- + + +Point description type. + + +## Data Fields + + +float [point_x](#structmavsdk_1_1_camera_server_1_1_track_point_1a1f8e102e4298e76baaa6a5cff8d8ad24) {} - Point to track x value (normalized 0..1, 0 is left, 1 is right). + +float [point_y](#structmavsdk_1_1_camera_server_1_1_track_point_1aca0cfb45d93117e650b02885b49bac8f) {} - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + +float [radius](#structmavsdk_1_1_camera_server_1_1_track_point_1a5894beb5581737c917c1e87b83ae52de) {} - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + + +## Field Documentation + + +### point_x {#structmavsdk_1_1_camera_server_1_1_track_point_1a1f8e102e4298e76baaa6a5cff8d8ad24} + +```cpp +float mavsdk::CameraServer::TrackPoint::point_x {} +``` + + +Point to track x value (normalized 0..1, 0 is left, 1 is right). + + +### point_y {#structmavsdk_1_1_camera_server_1_1_track_point_1aca0cfb45d93117e650b02885b49bac8f} + +```cpp +float mavsdk::CameraServer::TrackPoint::point_y {} +``` + + +Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + + +### radius {#structmavsdk_1_1_camera_server_1_1_track_point_1a5894beb5581737c917c1e87b83ae52de} + +```cpp +float mavsdk::CameraServer::TrackPoint::radius {} +``` + + +Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_rectangle.md b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_rectangle.md new file mode 100644 index 0000000000..73afbd7f3b --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_camera_server_1_1_track_rectangle.md @@ -0,0 +1,63 @@ +# mavsdk::CameraServer::TrackRectangle Struct Reference +`#include: camera_server.h` + +---- + + +Rectangle description type. + + +## Data Fields + + +float [top_left_corner_x](#structmavsdk_1_1_camera_server_1_1_track_rectangle_1afadf849f55c56cee294381db00bfddef) {} - Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + +float [top_left_corner_y](#structmavsdk_1_1_camera_server_1_1_track_rectangle_1adbfcfc50606ca093dad01881e81c4522) {} - Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + +float [bottom_right_corner_x](#structmavsdk_1_1_camera_server_1_1_track_rectangle_1a047dea51f7e3e4fbd20aaa15b179e466) {} - Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + +float [bottom_right_corner_y](#structmavsdk_1_1_camera_server_1_1_track_rectangle_1aedfafa197b18e37a4adc074aa7e02659) {} - Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + + +## Field Documentation + + +### top_left_corner_x {#structmavsdk_1_1_camera_server_1_1_track_rectangle_1afadf849f55c56cee294381db00bfddef} + +```cpp +float mavsdk::CameraServer::TrackRectangle::top_left_corner_x {} +``` + + +Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + + +### top_left_corner_y {#structmavsdk_1_1_camera_server_1_1_track_rectangle_1adbfcfc50606ca093dad01881e81c4522} + +```cpp +float mavsdk::CameraServer::TrackRectangle::top_left_corner_y {} +``` + + +Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + + +### bottom_right_corner_x {#structmavsdk_1_1_camera_server_1_1_track_rectangle_1a047dea51f7e3e4fbd20aaa15b179e466} + +```cpp +float mavsdk::CameraServer::TrackRectangle::bottom_right_corner_x {} +``` + + +Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + + +### bottom_right_corner_y {#structmavsdk_1_1_camera_server_1_1_track_rectangle_1aedfafa197b18e37a4adc074aa7e02659} + +```cpp +float mavsdk::CameraServer::TrackRectangle::bottom_right_corner_y {} +``` + + +Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param.md deleted file mode 100644 index 04b5b3b4cb..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param.md +++ /dev/null @@ -1,123 +0,0 @@ -# mavsdk::ComponentInformation::FloatParam Struct Reference -`#include: component_information.h` - ----- - - -Meta information for parameter of type float. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_component_information_1_1_float_param_1a8b8f1dd37502456363a1ff037d32ecd4) {} - Name (max 16 chars) - -std::string [short_description](#structmavsdk_1_1_component_information_1_1_float_param_1a7d2d7a41d1905b324570fa14cbd52a92) {} - Short description. - -std::string [long_description](#structmavsdk_1_1_component_information_1_1_float_param_1a9233602a3d5cb0cba6801ec97d9e4b3a) {} - Long description. - -std::string [unit](#structmavsdk_1_1_component_information_1_1_float_param_1a3bcff75ef0055cfbed0ad033ffc7d1e1) {} - Unit. - -int32_t [decimal_places](#structmavsdk_1_1_component_information_1_1_float_param_1a396958944eb0b431c3322a6e312f6fe0) {} - Decimal places for user to show. - -float [start_value](#structmavsdk_1_1_component_information_1_1_float_param_1aee892485217a4612e997c3003b5ef8b2) {} - Current/starting value. - -float [default_value](#structmavsdk_1_1_component_information_1_1_float_param_1a96119f1c35c17cbb95147acb12711997) {} - Default value. - -float [min_value](#structmavsdk_1_1_component_information_1_1_float_param_1ad5186ad76bd538580ed25259b8b4c236) {} - Minimum value. - -float [max_value](#structmavsdk_1_1_component_information_1_1_float_param_1a302486bbc172fd4aaf67a9bd0c4de259) {} - Maximum value. - - -## Field Documentation - - -### name {#structmavsdk_1_1_component_information_1_1_float_param_1a8b8f1dd37502456363a1ff037d32ecd4} - -```cpp -std::string mavsdk::ComponentInformation::FloatParam::name {} -``` - - -Name (max 16 chars) - - -### short_description {#structmavsdk_1_1_component_information_1_1_float_param_1a7d2d7a41d1905b324570fa14cbd52a92} - -```cpp -std::string mavsdk::ComponentInformation::FloatParam::short_description {} -``` - - -Short description. - - -### long_description {#structmavsdk_1_1_component_information_1_1_float_param_1a9233602a3d5cb0cba6801ec97d9e4b3a} - -```cpp -std::string mavsdk::ComponentInformation::FloatParam::long_description {} -``` - - -Long description. - - -### unit {#structmavsdk_1_1_component_information_1_1_float_param_1a3bcff75ef0055cfbed0ad033ffc7d1e1} - -```cpp -std::string mavsdk::ComponentInformation::FloatParam::unit {} -``` - - -Unit. - - -### decimal_places {#structmavsdk_1_1_component_information_1_1_float_param_1a396958944eb0b431c3322a6e312f6fe0} - -```cpp -int32_t mavsdk::ComponentInformation::FloatParam::decimal_places {} -``` - - -Decimal places for user to show. - - -### start_value {#structmavsdk_1_1_component_information_1_1_float_param_1aee892485217a4612e997c3003b5ef8b2} - -```cpp -float mavsdk::ComponentInformation::FloatParam::start_value {} -``` - - -Current/starting value. - - -### default_value {#structmavsdk_1_1_component_information_1_1_float_param_1a96119f1c35c17cbb95147acb12711997} - -```cpp -float mavsdk::ComponentInformation::FloatParam::default_value {} -``` - - -Default value. - - -### min_value {#structmavsdk_1_1_component_information_1_1_float_param_1ad5186ad76bd538580ed25259b8b4c236} - -```cpp -float mavsdk::ComponentInformation::FloatParam::min_value {} -``` - - -Minimum value. - - -### max_value {#structmavsdk_1_1_component_information_1_1_float_param_1a302486bbc172fd4aaf67a9bd0c4de259} - -```cpp -float mavsdk::ComponentInformation::FloatParam::max_value {} -``` - - -Maximum value. - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param_update.md deleted file mode 100644 index cde15f23dd..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_1_1_float_param_update.md +++ /dev/null @@ -1,39 +0,0 @@ -# mavsdk::ComponentInformation::FloatParamUpdate Struct Reference -`#include: component_information.h` - ----- - - -A float param that has been updated. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_component_information_1_1_float_param_update_1ac4bb31341e4a4edd2072dd169cbd0412) {} - Name of param that changed. - -float [value](#structmavsdk_1_1_component_information_1_1_float_param_update_1aa764f57cf3dafdaf959abdf83b973709) {} - New value of param. - - -## Field Documentation - - -### name {#structmavsdk_1_1_component_information_1_1_float_param_update_1ac4bb31341e4a4edd2072dd169cbd0412} - -```cpp -std::string mavsdk::ComponentInformation::FloatParamUpdate::name {} -``` - - -Name of param that changed. - - -### value {#structmavsdk_1_1_component_information_1_1_float_param_update_1aa764f57cf3dafdaf959abdf83b973709} - -```cpp -float mavsdk::ComponentInformation::FloatParamUpdate::value {} -``` - - -New value of param. - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param.md deleted file mode 100644 index 78f0b1d98b..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param.md +++ /dev/null @@ -1,123 +0,0 @@ -# mavsdk::ComponentInformationServer::FloatParam Struct Reference -`#include: component_information_server.h` - ----- - - -Meta information for parameter of type float. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_component_information_server_1_1_float_param_1a926dc62a3f6e70cb5cd7d766decefb80) {} - Name (max 16 chars) - -std::string [short_description](#structmavsdk_1_1_component_information_server_1_1_float_param_1af16e9d8b079cbe927c6db3197c1ca919) {} - Short description. - -std::string [long_description](#structmavsdk_1_1_component_information_server_1_1_float_param_1a979c36646ee823b0668ff6e0a3aa0d9b) {} - Long description. - -std::string [unit](#structmavsdk_1_1_component_information_server_1_1_float_param_1ae67230a5438cf60eca03fe94b554f12d) {} - Unit. - -int32_t [decimal_places](#structmavsdk_1_1_component_information_server_1_1_float_param_1aaca5f5795fef5737a2b7b5f120647329) {} - Decimal places for user to show. - -float [start_value](#structmavsdk_1_1_component_information_server_1_1_float_param_1ad511a434c255184c245e01249fb389d0) {} - Current/starting value. - -float [default_value](#structmavsdk_1_1_component_information_server_1_1_float_param_1a54937cafca787f7a441d839def64ee65) {} - Default value. - -float [min_value](#structmavsdk_1_1_component_information_server_1_1_float_param_1a78b075ab7e63547c730620ed23226c71) {} - Minimum value. - -float [max_value](#structmavsdk_1_1_component_information_server_1_1_float_param_1af60f9ed1a1b489c695d6604bbe5fee8f) {} - Maximum value. - - -## Field Documentation - - -### name {#structmavsdk_1_1_component_information_server_1_1_float_param_1a926dc62a3f6e70cb5cd7d766decefb80} - -```cpp -std::string mavsdk::ComponentInformationServer::FloatParam::name {} -``` - - -Name (max 16 chars) - - -### short_description {#structmavsdk_1_1_component_information_server_1_1_float_param_1af16e9d8b079cbe927c6db3197c1ca919} - -```cpp -std::string mavsdk::ComponentInformationServer::FloatParam::short_description {} -``` - - -Short description. - - -### long_description {#structmavsdk_1_1_component_information_server_1_1_float_param_1a979c36646ee823b0668ff6e0a3aa0d9b} - -```cpp -std::string mavsdk::ComponentInformationServer::FloatParam::long_description {} -``` - - -Long description. - - -### unit {#structmavsdk_1_1_component_information_server_1_1_float_param_1ae67230a5438cf60eca03fe94b554f12d} - -```cpp -std::string mavsdk::ComponentInformationServer::FloatParam::unit {} -``` - - -Unit. - - -### decimal_places {#structmavsdk_1_1_component_information_server_1_1_float_param_1aaca5f5795fef5737a2b7b5f120647329} - -```cpp -int32_t mavsdk::ComponentInformationServer::FloatParam::decimal_places {} -``` - - -Decimal places for user to show. - - -### start_value {#structmavsdk_1_1_component_information_server_1_1_float_param_1ad511a434c255184c245e01249fb389d0} - -```cpp -float mavsdk::ComponentInformationServer::FloatParam::start_value {} -``` - - -Current/starting value. - - -### default_value {#structmavsdk_1_1_component_information_server_1_1_float_param_1a54937cafca787f7a441d839def64ee65} - -```cpp -float mavsdk::ComponentInformationServer::FloatParam::default_value {} -``` - - -Default value. - - -### min_value {#structmavsdk_1_1_component_information_server_1_1_float_param_1a78b075ab7e63547c730620ed23226c71} - -```cpp -float mavsdk::ComponentInformationServer::FloatParam::min_value {} -``` - - -Minimum value. - - -### max_value {#structmavsdk_1_1_component_information_server_1_1_float_param_1af60f9ed1a1b489c695d6604bbe5fee8f} - -```cpp -float mavsdk::ComponentInformationServer::FloatParam::max_value {} -``` - - -Maximum value. - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param_update.md deleted file mode 100644 index d4fe00044e..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_component_information_server_1_1_float_param_update.md +++ /dev/null @@ -1,39 +0,0 @@ -# mavsdk::ComponentInformationServer::FloatParamUpdate Struct Reference -`#include: component_information_server.h` - ----- - - -A float param that has been updated. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_component_information_server_1_1_float_param_update_1aec3ed754aca50cba04cbdcb5955b9ce3) {} - Name of param that changed. - -float [value](#structmavsdk_1_1_component_information_server_1_1_float_param_update_1ab0d10711fecc6b9868acbc6e1e3f1bd2) {} - New value of param. - - -## Field Documentation - - -### name {#structmavsdk_1_1_component_information_server_1_1_float_param_update_1aec3ed754aca50cba04cbdcb5955b9ce3} - -```cpp -std::string mavsdk::ComponentInformationServer::FloatParamUpdate::name {} -``` - - -Name of param that changed. - - -### value {#structmavsdk_1_1_component_information_server_1_1_float_param_update_1ab0d10711fecc6b9868acbc6e1e3f1bd2} - -```cpp -float mavsdk::ComponentInformationServer::FloatParamUpdate::value {} -``` - - -New value of param. - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_data.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_data.md new file mode 100644 index 0000000000..1684cfe1ac --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_data.md @@ -0,0 +1,27 @@ +# mavsdk::ComponentMetadata::MetadataData Struct Reference +`#include: component_metadata.h` + +---- + + +Metadata response. + + +## Data Fields + + +std::string [json_metadata](#structmavsdk_1_1_component_metadata_1_1_metadata_data_1ad25802446fdbae6ca3d23ba2a8ed4201) {} - The JSON metadata. + + +## Field Documentation + + +### json_metadata {#structmavsdk_1_1_component_metadata_1_1_metadata_data_1ad25802446fdbae6ca3d23ba2a8ed4201} + +```cpp +std::string mavsdk::ComponentMetadata::MetadataData::json_metadata {} +``` + + +The JSON metadata. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_update.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_update.md new file mode 100644 index 0000000000..91fc2b7af2 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_1_1_metadata_update.md @@ -0,0 +1,51 @@ +# mavsdk::ComponentMetadata::MetadataUpdate Struct Reference +`#include: component_metadata.h` + +---- + + +Metadata for a given component and type. + + +## Data Fields + + +uint32_t [compid](#structmavsdk_1_1_component_metadata_1_1_metadata_update_1acf104bcc3e77947687de065436acbbda) {} - The component ID. + +[MetadataType](classmavsdk_1_1_component_metadata.md#classmavsdk_1_1_component_metadata_1a0d85236afbbb3dc6b2dd46351a6b38bc) [type](#structmavsdk_1_1_component_metadata_1_1_metadata_update_1ab38bfcf6247c11c74f12b46e4e630eed) {} - The metadata type. + +std::string [json_metadata](#structmavsdk_1_1_component_metadata_1_1_metadata_update_1a2fad2330a6ed1c2fd1e5e34d5a56b377) {} - The JSON metadata. + + +## Field Documentation + + +### compid {#structmavsdk_1_1_component_metadata_1_1_metadata_update_1acf104bcc3e77947687de065436acbbda} + +```cpp +uint32_t mavsdk::ComponentMetadata::MetadataUpdate::compid {} +``` + + +The component ID. + + +### type {#structmavsdk_1_1_component_metadata_1_1_metadata_update_1ab38bfcf6247c11c74f12b46e4e630eed} + +```cpp +MetadataType mavsdk::ComponentMetadata::MetadataUpdate::type {} +``` + + +The metadata type. + + +### json_metadata {#structmavsdk_1_1_component_metadata_1_1_metadata_update_1a2fad2330a6ed1c2fd1e5e34d5a56b377} + +```cpp +std::string mavsdk::ComponentMetadata::MetadataUpdate::json_metadata {} +``` + + +The JSON metadata. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_server_1_1_metadata.md b/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_server_1_1_metadata.md new file mode 100644 index 0000000000..92141b297d --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_component_metadata_server_1_1_metadata.md @@ -0,0 +1,39 @@ +# mavsdk::ComponentMetadataServer::Metadata Struct Reference +`#include: component_metadata_server.h` + +---- + + +The metadata type and content. + + +## Data Fields + + +[MetadataType](classmavsdk_1_1_component_metadata_server.md#classmavsdk_1_1_component_metadata_server_1abaa555f8d1e2ae73f2275b18271537d6) [type](#structmavsdk_1_1_component_metadata_server_1_1_metadata_1a8abdeb22ca28af4c29943119aa00a101) {} - The metadata type. + +std::string [json_metadata](#structmavsdk_1_1_component_metadata_server_1_1_metadata_1a84a97b8f3ddc3aea0b49fbd24a371e0f) {} - The JSON metadata. + + +## Field Documentation + + +### type {#structmavsdk_1_1_component_metadata_server_1_1_metadata_1a8abdeb22ca28af4c29943119aa00a101} + +```cpp +MetadataType mavsdk::ComponentMetadataServer::Metadata::type {} +``` + + +The metadata type. + + +### json_metadata {#structmavsdk_1_1_component_metadata_server_1_1_metadata_1a84a97b8f3ddc3aea0b49fbd24a371e0f} + +```cpp +std::string mavsdk::ComponentMetadataServer::Metadata::json_metadata {} +``` + + +The JSON metadata. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_event.md b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_event.md new file mode 100644 index 0000000000..70e2b97a87 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_event.md @@ -0,0 +1,87 @@ +# mavsdk::Events::Event Struct Reference +`#include: events.h` + +---- + + +[Event](structmavsdk_1_1_events_1_1_event.md) type. + + +## Data Fields + + +uint32_t [compid](#structmavsdk_1_1_events_1_1_event_1a7ec91e98105fae94d3ff041d42b5ac0a) {} - The source component ID of the event. + +std::string [message](#structmavsdk_1_1_events_1_1_event_1ae18a466fde5623f099c9b20753302852) {} - Short, single-line message. + +std::string [description](#structmavsdk_1_1_events_1_1_event_1aee27a34850edf145d56ebc6b37829fba) {} - Detailed description (optional, might be multiple lines) + +[LogLevel](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a237c8de77f3995138125db44d148cecc) [log_level](#structmavsdk_1_1_events_1_1_event_1ae1a2b68931086b7ec4f31a6b2d4de3fd) {} - Log level of message. + +std::string [event_namespace](#structmavsdk_1_1_events_1_1_event_1afa6ed28311d60fb9a44318d985931050) {} - Namespace, e.g. "px4". + +std::string [event_name](#structmavsdk_1_1_events_1_1_event_1a9e8ad465085e81a6b534c89614767963) {} - [Event](structmavsdk_1_1_events_1_1_event.md) name (unique within the namespace) + + +## Field Documentation + + +### compid {#structmavsdk_1_1_events_1_1_event_1a7ec91e98105fae94d3ff041d42b5ac0a} + +```cpp +uint32_t mavsdk::Events::Event::compid {} +``` + + +The source component ID of the event. + + +### message {#structmavsdk_1_1_events_1_1_event_1ae18a466fde5623f099c9b20753302852} + +```cpp +std::string mavsdk::Events::Event::message {} +``` + + +Short, single-line message. + + +### description {#structmavsdk_1_1_events_1_1_event_1aee27a34850edf145d56ebc6b37829fba} + +```cpp +std::string mavsdk::Events::Event::description {} +``` + + +Detailed description (optional, might be multiple lines) + + +### log_level {#structmavsdk_1_1_events_1_1_event_1ae1a2b68931086b7ec4f31a6b2d4de3fd} + +```cpp +LogLevel mavsdk::Events::Event::log_level {} +``` + + +Log level of message. + + +### event_namespace {#structmavsdk_1_1_events_1_1_event_1afa6ed28311d60fb9a44318d985931050} + +```cpp +std::string mavsdk::Events::Event::event_namespace {} +``` + + +Namespace, e.g. "px4". + + +### event_name {#structmavsdk_1_1_events_1_1_event_1a9e8ad465085e81a6b534c89614767963} + +```cpp +std::string mavsdk::Events::Event::event_name {} +``` + + +[Event](structmavsdk_1_1_events_1_1_event.md) name (unique within the namespace) + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_mode.md b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_mode.md new file mode 100644 index 0000000000..eb2b35b43b --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_mode.md @@ -0,0 +1,51 @@ +# mavsdk::Events::HealthAndArmingCheckMode Struct Reference +`#include: events.h` + +---- + + +Arming checks for a specific mode. + + +## Data Fields + + +std::string [mode_name](#structmavsdk_1_1_events_1_1_health_and_arming_check_mode_1ade334ef65152cc7c6fcee3d14a1e0168) {} - Mode name, e.g. "Position". + +bool [can_arm_or_run](#structmavsdk_1_1_events_1_1_health_and_arming_check_mode_1a0054b9e84b9159715cda9e11b4920d16) {} - If disarmed: indicates if arming is possible. If armed: indicates if the mode can be selected. + +std::vector< [HealthAndArmingCheckProblem](structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md) > [problems](#structmavsdk_1_1_events_1_1_health_and_arming_check_mode_1a1003ed614d692a6db439821e626b1748) {} - List of reported problems for the mode. + + +## Field Documentation + + +### mode_name {#structmavsdk_1_1_events_1_1_health_and_arming_check_mode_1ade334ef65152cc7c6fcee3d14a1e0168} + +```cpp +std::string mavsdk::Events::HealthAndArmingCheckMode::mode_name {} +``` + + +Mode name, e.g. "Position". + + +### can_arm_or_run {#structmavsdk_1_1_events_1_1_health_and_arming_check_mode_1a0054b9e84b9159715cda9e11b4920d16} + +```cpp +bool mavsdk::Events::HealthAndArmingCheckMode::can_arm_or_run {} +``` + + +If disarmed: indicates if arming is possible. If armed: indicates if the mode can be selected. + + +### problems {#structmavsdk_1_1_events_1_1_health_and_arming_check_mode_1a1003ed614d692a6db439821e626b1748} + +```cpp +std::vector mavsdk::Events::HealthAndArmingCheckMode::problems {} +``` + + +List of reported problems for the mode. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md new file mode 100644 index 0000000000..a347083c78 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md @@ -0,0 +1,63 @@ +# mavsdk::Events::HealthAndArmingCheckProblem Struct Reference +`#include: events.h` + +---- + + +Health and arming check problem type. + + +## Data Fields + + +std::string [message](#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1afd72427f3eba7f5592dce7f69731bbd6) {} - Short, single-line message. + +std::string [description](#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1a81dc36ffb30a64e4a47b5512df37a45f) {} - Detailed description (optional, might be multiple lines) + +[LogLevel](classmavsdk_1_1_events.md#classmavsdk_1_1_events_1a237c8de77f3995138125db44d148cecc) [log_level](#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1ac05048809875f80d0c02b643165b0c33) {} - Log level of message. + +std::string [health_component](#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1a37d19a2c8d83f6fe03ac47525487d80d) {} - Associated health component, e.g. "gps". + + +## Field Documentation + + +### message {#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1afd72427f3eba7f5592dce7f69731bbd6} + +```cpp +std::string mavsdk::Events::HealthAndArmingCheckProblem::message {} +``` + + +Short, single-line message. + + +### description {#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1a81dc36ffb30a64e4a47b5512df37a45f} + +```cpp +std::string mavsdk::Events::HealthAndArmingCheckProblem::description {} +``` + + +Detailed description (optional, might be multiple lines) + + +### log_level {#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1ac05048809875f80d0c02b643165b0c33} + +```cpp +LogLevel mavsdk::Events::HealthAndArmingCheckProblem::log_level {} +``` + + +Log level of message. + + +### health_component {#structmavsdk_1_1_events_1_1_health_and_arming_check_problem_1a37d19a2c8d83f6fe03ac47525487d80d} + +```cpp +std::string mavsdk::Events::HealthAndArmingCheckProblem::health_component {} +``` + + +Associated health component, e.g. "gps". + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_report.md b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_report.md new file mode 100644 index 0000000000..1ee51004dc --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_and_arming_check_report.md @@ -0,0 +1,51 @@ +# mavsdk::Events::HealthAndArmingCheckReport Struct Reference +`#include: events.h` + +---- + + +Health and arming check report type. + + +## Data Fields + + +[HealthAndArmingCheckMode](structmavsdk_1_1_events_1_1_health_and_arming_check_mode.md) [current_mode_intention](#structmavsdk_1_1_events_1_1_health_and_arming_check_report_1a00f1d9c7d6beb8d4a9b310aa6a72572f) {} - Report for currently intended mode. + +std::vector< [HealthComponentReport](structmavsdk_1_1_events_1_1_health_component_report.md) > [health_components](#structmavsdk_1_1_events_1_1_health_and_arming_check_report_1af3267879f370b4f7cd84840f3625c0fc) {} - Health components list (e.g. for "gps") + +std::vector< [HealthAndArmingCheckProblem](structmavsdk_1_1_events_1_1_health_and_arming_check_problem.md) > [all_problems](#structmavsdk_1_1_events_1_1_health_and_arming_check_report_1adb355887bc72bee03dceccfda4836e4a) {} - Complete list of problems. + + +## Field Documentation + + +### current_mode_intention {#structmavsdk_1_1_events_1_1_health_and_arming_check_report_1a00f1d9c7d6beb8d4a9b310aa6a72572f} + +```cpp +HealthAndArmingCheckMode mavsdk::Events::HealthAndArmingCheckReport::current_mode_intention {} +``` + + +Report for currently intended mode. + + +### health_components {#structmavsdk_1_1_events_1_1_health_and_arming_check_report_1af3267879f370b4f7cd84840f3625c0fc} + +```cpp +std::vector mavsdk::Events::HealthAndArmingCheckReport::health_components {} +``` + + +Health components list (e.g. for "gps") + + +### all_problems {#structmavsdk_1_1_events_1_1_health_and_arming_check_report_1adb355887bc72bee03dceccfda4836e4a} + +```cpp +std::vector mavsdk::Events::HealthAndArmingCheckReport::all_problems {} +``` + + +Complete list of problems. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_component_report.md b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_component_report.md new file mode 100644 index 0000000000..ab3de1144a --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_events_1_1_health_component_report.md @@ -0,0 +1,75 @@ +# mavsdk::Events::HealthComponentReport Struct Reference +`#include: events.h` + +---- + + +Health component report type. + + +## Data Fields + + +std::string [name](#structmavsdk_1_1_events_1_1_health_component_report_1ae33eb7667f6ee51585fed8d2d7a13cb6) {} - Unique component name, e.g. "gps". + +std::string [label](#structmavsdk_1_1_events_1_1_health_component_report_1a5798959a7d5b8b65d3763e4981c4a1b6) {} - Human readable label of the component, e.g. "GPS" or "Accelerometer". + +bool [is_present](#structmavsdk_1_1_events_1_1_health_component_report_1a5c71a42e740f3c137359f3d53de52cf9) {} - If the component is present. + +bool [has_error](#structmavsdk_1_1_events_1_1_health_component_report_1a79f0e8503febb4c19a07b49668c76ba7) {} - If the component has errors. + +bool [has_warning](#structmavsdk_1_1_events_1_1_health_component_report_1ab37c768a8f671ee40224034e86794af4) {} - If the component has warnings. + + +## Field Documentation + + +### name {#structmavsdk_1_1_events_1_1_health_component_report_1ae33eb7667f6ee51585fed8d2d7a13cb6} + +```cpp +std::string mavsdk::Events::HealthComponentReport::name {} +``` + + +Unique component name, e.g. "gps". + + +### label {#structmavsdk_1_1_events_1_1_health_component_report_1a5798959a7d5b8b65d3763e4981c4a1b6} + +```cpp +std::string mavsdk::Events::HealthComponentReport::label {} +``` + + +Human readable label of the component, e.g. "GPS" or "Accelerometer". + + +### is_present {#structmavsdk_1_1_events_1_1_health_component_report_1a5c71a42e740f3c137359f3d53de52cf9} + +```cpp +bool mavsdk::Events::HealthComponentReport::is_present {} +``` + + +If the component is present. + + +### has_error {#structmavsdk_1_1_events_1_1_health_component_report_1a79f0e8503febb4c19a07b49668c76ba7} + +```cpp +bool mavsdk::Events::HealthComponentReport::has_error {} +``` + + +If the component has errors. + + +### has_warning {#structmavsdk_1_1_events_1_1_health_component_report_1ab37c768a8f671ee40224034e86794af4} + +```cpp +bool mavsdk::Events::HealthComponentReport::has_warning {} +``` + + +If the component has warnings. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_ftp_1_1_list_directory_data.md b/docs/en/cpp/api_reference/structmavsdk_1_1_ftp_1_1_list_directory_data.md new file mode 100644 index 0000000000..ee37d057c8 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_ftp_1_1_list_directory_data.md @@ -0,0 +1,39 @@ +# mavsdk::Ftp::ListDirectoryData Struct Reference +`#include: ftp.h` + +---- + + +The output of a directory list. + + +## Data Fields + + +std::vector< std::string > [dirs](#structmavsdk_1_1_ftp_1_1_list_directory_data_1af4a66423b4ffcda32987579f6fd91013) {} - The found directories. + +std::vector< std::string > [files](#structmavsdk_1_1_ftp_1_1_list_directory_data_1a85078176a4e0e8f8df617bdec794df76) {} - The found files. + + +## Field Documentation + + +### dirs {#structmavsdk_1_1_ftp_1_1_list_directory_data_1af4a66423b4ffcda32987579f6fd91013} + +```cpp +std::vector mavsdk::Ftp::ListDirectoryData::dirs {} +``` + + +The found directories. + + +### files {#structmavsdk_1_1_ftp_1_1_list_directory_data_1a85078176a4e0e8f8df617bdec794df76} + +```cpp +std::vector mavsdk::Ftp::ListDirectoryData::files {} +``` + + +The found files. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_angular_velocity_body.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_angular_velocity_body.md new file mode 100644 index 0000000000..9a26774cbb --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_angular_velocity_body.md @@ -0,0 +1,51 @@ +# mavsdk::Gimbal::AngularVelocityBody Struct Reference +`#include: gimbal.h` + +---- + + +[Gimbal](classmavsdk_1_1_gimbal.md) angular rate type. + + +## Data Fields + + +float [roll_rad_s](#structmavsdk_1_1_gimbal_1_1_angular_velocity_body_1a9506ed55cf2c971dc15bdbf592bb1b2b) {float(NAN)} - Roll angular velocity. + +float [pitch_rad_s](#structmavsdk_1_1_gimbal_1_1_angular_velocity_body_1a2126c47c851ac5f24f2acd4932301241) {float(NAN)} - Pitch angular velocity. + +float [yaw_rad_s](#structmavsdk_1_1_gimbal_1_1_angular_velocity_body_1af5c55f39fd3a04edea8f6f0c47890c16) {float(NAN)} - Yaw angular velocity. + + +## Field Documentation + + +### roll_rad_s {#structmavsdk_1_1_gimbal_1_1_angular_velocity_body_1a9506ed55cf2c971dc15bdbf592bb1b2b} + +```cpp +float mavsdk::Gimbal::AngularVelocityBody::roll_rad_s {float(NAN)} +``` + + +Roll angular velocity. + + +### pitch_rad_s {#structmavsdk_1_1_gimbal_1_1_angular_velocity_body_1a2126c47c851ac5f24f2acd4932301241} + +```cpp +float mavsdk::Gimbal::AngularVelocityBody::pitch_rad_s {float(NAN)} +``` + + +Pitch angular velocity. + + +### yaw_rad_s {#structmavsdk_1_1_gimbal_1_1_angular_velocity_body_1af5c55f39fd3a04edea8f6f0c47890c16} + +```cpp +float mavsdk::Gimbal::AngularVelocityBody::yaw_rad_s {float(NAN)} +``` + + +Yaw angular velocity. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_attitude.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_attitude.md new file mode 100644 index 0000000000..d220f0680c --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_attitude.md @@ -0,0 +1,99 @@ +# mavsdk::Gimbal::Attitude Struct Reference +`#include: gimbal.h` + +---- + + +[Gimbal](classmavsdk_1_1_gimbal.md) attitude type. + + +## Data Fields + + +int32_t [gimbal_id](#structmavsdk_1_1_gimbal_1_1_attitude_1afbcae93e94034d0e43ebb35a358cf098) {} - [Gimbal](classmavsdk_1_1_gimbal.md) ID. + +[EulerAngle](structmavsdk_1_1_gimbal_1_1_euler_angle.md) [euler_angle_forward](#structmavsdk_1_1_gimbal_1_1_attitude_1af84d7adce79d0fb5c72151b00e6aaf4d) {} - Euler angle relative to forward. + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) [quaternion_forward](#structmavsdk_1_1_gimbal_1_1_attitude_1acd153d4d03bf2e780bf5073e49f9a1b3) {} - [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) relative to forward. + +[EulerAngle](structmavsdk_1_1_gimbal_1_1_euler_angle.md) [euler_angle_north](#structmavsdk_1_1_gimbal_1_1_attitude_1ade09fd2a0748b8fa310110f39e937365) {} - Euler angle relative to North. + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) [quaternion_north](#structmavsdk_1_1_gimbal_1_1_attitude_1a40ec2e7395692e824a855e5771c8a728) {} - [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) relative to North. + +[AngularVelocityBody](structmavsdk_1_1_gimbal_1_1_angular_velocity_body.md) [angular_velocity](#structmavsdk_1_1_gimbal_1_1_attitude_1a1746291596ff6b69dd9c28c2f37730f1) {} - The angular rate. + +uint64_t [timestamp_us](#structmavsdk_1_1_gimbal_1_1_attitude_1a5c620e118ca06f8553918df38012677e) {} - Timestamp in microseconds. + + +## Field Documentation + + +### gimbal_id {#structmavsdk_1_1_gimbal_1_1_attitude_1afbcae93e94034d0e43ebb35a358cf098} + +```cpp +int32_t mavsdk::Gimbal::Attitude::gimbal_id {} +``` + + +[Gimbal](classmavsdk_1_1_gimbal.md) ID. + + +### euler_angle_forward {#structmavsdk_1_1_gimbal_1_1_attitude_1af84d7adce79d0fb5c72151b00e6aaf4d} + +```cpp +EulerAngle mavsdk::Gimbal::Attitude::euler_angle_forward {} +``` + + +Euler angle relative to forward. + + +### quaternion_forward {#structmavsdk_1_1_gimbal_1_1_attitude_1acd153d4d03bf2e780bf5073e49f9a1b3} + +```cpp +Quaternion mavsdk::Gimbal::Attitude::quaternion_forward {} +``` + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) relative to forward. + + +### euler_angle_north {#structmavsdk_1_1_gimbal_1_1_attitude_1ade09fd2a0748b8fa310110f39e937365} + +```cpp +EulerAngle mavsdk::Gimbal::Attitude::euler_angle_north {} +``` + + +Euler angle relative to North. + + +### quaternion_north {#structmavsdk_1_1_gimbal_1_1_attitude_1a40ec2e7395692e824a855e5771c8a728} + +```cpp +Quaternion mavsdk::Gimbal::Attitude::quaternion_north {} +``` + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) relative to North. + + +### angular_velocity {#structmavsdk_1_1_gimbal_1_1_attitude_1a1746291596ff6b69dd9c28c2f37730f1} + +```cpp +AngularVelocityBody mavsdk::Gimbal::Attitude::angular_velocity {} +``` + + +The angular rate. + + +### timestamp_us {#structmavsdk_1_1_gimbal_1_1_attitude_1a5c620e118ca06f8553918df38012677e} + +```cpp +uint64_t mavsdk::Gimbal::Attitude::timestamp_us {} +``` + + +Timestamp in microseconds. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_control_status.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_control_status.md index fb28b6470e..51fb9c5687 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_control_status.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_control_status.md @@ -10,6 +10,8 @@ Control status. ## Data Fields +int32_t [gimbal_id](#structmavsdk_1_1_gimbal_1_1_control_status_1a25f59ad4fe9be95dc14f43d37c5d378e) {} - [Gimbal](classmavsdk_1_1_gimbal.md) ID. + [ControlMode](classmavsdk_1_1_gimbal.md#classmavsdk_1_1_gimbal_1a01b721086d7de6089aefdeb0fda4cff3) [control_mode](#structmavsdk_1_1_gimbal_1_1_control_status_1a58ab8c223f8dd71268bbcfdc019fae8a) {} - Control mode (none, primary or secondary) int32_t [sysid_primary_control](#structmavsdk_1_1_gimbal_1_1_control_status_1a99fdfdc94af7663c03bd88ac4bde82c3) {} - Sysid of the component that has primary control over the gimbal (0 if no one is in control) @@ -24,6 +26,16 @@ int32_t [compid_secondary_control](#structmavsdk_1_1_gimbal_1_1_control_status_1 ## Field Documentation +### gimbal_id {#structmavsdk_1_1_gimbal_1_1_control_status_1a25f59ad4fe9be95dc14f43d37c5d378e} + +```cpp +int32_t mavsdk::Gimbal::ControlStatus::gimbal_id {} +``` + + +[Gimbal](classmavsdk_1_1_gimbal.md) ID. + + ### control_mode {#structmavsdk_1_1_gimbal_1_1_control_status_1a58ab8c223f8dd71268bbcfdc019fae8a} ```cpp diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_euler_angle.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_euler_angle.md new file mode 100644 index 0000000000..8b9cd2a24d --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_euler_angle.md @@ -0,0 +1,57 @@ +# mavsdk::Gimbal::EulerAngle Struct Reference +`#include: gimbal.h` + +---- + + +Euler angle type. + + +All rotations and axis systems follow the right-hand rule. The Euler angles are converted using the 3-1-2 sequence instead of standard 3-2-1 in order to avoid the gimbal lock at 90 degrees down. + + +For more info see [https://en.wikipedia.org/wiki/Euler_angles](https://en.wikipedia.org/wiki/Euler_angles) + + +## Data Fields + + +float [roll_deg](#structmavsdk_1_1_gimbal_1_1_euler_angle_1a8597dbca1cc6c0f9595b8299827164c4) { float(NAN)} - Roll angle in degrees, positive is banking to the right. + +float [pitch_deg](#structmavsdk_1_1_gimbal_1_1_euler_angle_1aafe2a84a6a9001962190b115ea6b94e4) { float(NAN)} - Pitch angle in degrees, positive is pitching nose up. + +float [yaw_deg](#structmavsdk_1_1_gimbal_1_1_euler_angle_1ac09ef8ac782fbaa72812f53985ff312e) { float(NAN)} - Yaw angle in degrees, positive is clock-wise seen from above. + + +## Field Documentation + + +### roll_deg {#structmavsdk_1_1_gimbal_1_1_euler_angle_1a8597dbca1cc6c0f9595b8299827164c4} + +```cpp +float mavsdk::Gimbal::EulerAngle::roll_deg { float(NAN)} +``` + + +Roll angle in degrees, positive is banking to the right. + + +### pitch_deg {#structmavsdk_1_1_gimbal_1_1_euler_angle_1aafe2a84a6a9001962190b115ea6b94e4} + +```cpp +float mavsdk::Gimbal::EulerAngle::pitch_deg { float(NAN)} +``` + + +Pitch angle in degrees, positive is pitching nose up. + + +### yaw_deg {#structmavsdk_1_1_gimbal_1_1_euler_angle_1ac09ef8ac782fbaa72812f53985ff312e} + +```cpp +float mavsdk::Gimbal::EulerAngle::yaw_deg { float(NAN)} +``` + + +Yaw angle in degrees, positive is clock-wise seen from above. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_item.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_item.md new file mode 100644 index 0000000000..859dd85adf --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_item.md @@ -0,0 +1,87 @@ +# mavsdk::Gimbal::GimbalItem Struct Reference +`#include: gimbal.h` + +---- + + +[Gimbal](classmavsdk_1_1_gimbal.md) list item. + + +## Data Fields + + +int32_t [gimbal_id](#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a9424d6672c7ce15ba1e76f7dba72c398) {} - ID to address it, starting at 1 (0 means all gimbals) + +std::string [vendor_name](#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a4f242d74e738cf807770c8d45340edcb) {} - Vendor name. + +std::string [model_name](#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a7429465ade39f000358ba6597dd21c07) {} - Model name. + +std::string [custom_name](#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a495511db3d00aa170512dbe3f862a919) {} - Custom name name. + +int32_t [gimbal_manager_component_id](#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a9b378bec4973e834803917c341b6832d) {} - MAVLink component of gimbal manager, for debugging purposes. + +int32_t [gimbal_device_id](#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a6c6ed15759db38636774ca244367dafd) {} - MAVLink component of gimbal device. + + +## Field Documentation + + +### gimbal_id {#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a9424d6672c7ce15ba1e76f7dba72c398} + +```cpp +int32_t mavsdk::Gimbal::GimbalItem::gimbal_id {} +``` + + +ID to address it, starting at 1 (0 means all gimbals) + + +### vendor_name {#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a4f242d74e738cf807770c8d45340edcb} + +```cpp +std::string mavsdk::Gimbal::GimbalItem::vendor_name {} +``` + + +Vendor name. + + +### model_name {#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a7429465ade39f000358ba6597dd21c07} + +```cpp +std::string mavsdk::Gimbal::GimbalItem::model_name {} +``` + + +Model name. + + +### custom_name {#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a495511db3d00aa170512dbe3f862a919} + +```cpp +std::string mavsdk::Gimbal::GimbalItem::custom_name {} +``` + + +Custom name name. + + +### gimbal_manager_component_id {#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a9b378bec4973e834803917c341b6832d} + +```cpp +int32_t mavsdk::Gimbal::GimbalItem::gimbal_manager_component_id {} +``` + + +MAVLink component of gimbal manager, for debugging purposes. + + +### gimbal_device_id {#structmavsdk_1_1_gimbal_1_1_gimbal_item_1a6c6ed15759db38636774ca244367dafd} + +```cpp +int32_t mavsdk::Gimbal::GimbalItem::gimbal_device_id {} +``` + + +MAVLink component of gimbal device. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_list.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_list.md new file mode 100644 index 0000000000..f3cee8cd75 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_gimbal_list.md @@ -0,0 +1,27 @@ +# mavsdk::Gimbal::GimbalList Struct Reference +`#include: gimbal.h` + +---- + + +[Gimbal](classmavsdk_1_1_gimbal.md) list. + + +## Data Fields + + +std::vector< [GimbalItem](structmavsdk_1_1_gimbal_1_1_gimbal_item.md) > [gimbals](#structmavsdk_1_1_gimbal_1_1_gimbal_list_1abee70e34b8e4d99d699551cdde634b83) {} - [Gimbal](classmavsdk_1_1_gimbal.md) items. + + +## Field Documentation + + +### gimbals {#structmavsdk_1_1_gimbal_1_1_gimbal_list_1abee70e34b8e4d99d699551cdde634b83} + +```cpp +std::vector mavsdk::Gimbal::GimbalList::gimbals {} +``` + + +[Gimbal](classmavsdk_1_1_gimbal.md) items. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_quaternion.md b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_quaternion.md new file mode 100644 index 0000000000..68bb16cf20 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_gimbal_1_1_quaternion.md @@ -0,0 +1,69 @@ +# mavsdk::Gimbal::Quaternion Struct Reference +`#include: gimbal.h` + +---- + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) type. + + +All rotations and axis systems follow the right-hand rule. The Hamilton quaternion product definition is used. A zero-rotation quaternion is represented by (1,0,0,0). The quaternion could also be written as w + xi + yj + zk. + + +For more info see: [https://en.wikipedia.org/wiki/Quaternion](https://en.wikipedia.org/wiki/Quaternion) + + +## Data Fields + + +float [w](#structmavsdk_1_1_gimbal_1_1_quaternion_1a9b22296604cb17fc43c2f1e6643c4828) {float(NAN)} - [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 0, also denoted as a. + +float [x](#structmavsdk_1_1_gimbal_1_1_quaternion_1a51708e59333fd24629ccc1cc1a42e01a) {float(NAN)} - [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 1, also denoted as b. + +float [y](#structmavsdk_1_1_gimbal_1_1_quaternion_1ae33e49d12aeeb58bd50469474e8cc3e8) {float(NAN)} - [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 2, also denoted as c. + +float [z](#structmavsdk_1_1_gimbal_1_1_quaternion_1a4a2173406079a5561cbe5fab511eed4a) {float(NAN)} - [Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 3, also denoted as d. + + +## Field Documentation + + +### w {#structmavsdk_1_1_gimbal_1_1_quaternion_1a9b22296604cb17fc43c2f1e6643c4828} + +```cpp +float mavsdk::Gimbal::Quaternion::w {float(NAN)} +``` + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 0, also denoted as a. + + +### x {#structmavsdk_1_1_gimbal_1_1_quaternion_1a51708e59333fd24629ccc1cc1a42e01a} + +```cpp +float mavsdk::Gimbal::Quaternion::x {float(NAN)} +``` + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 1, also denoted as b. + + +### y {#structmavsdk_1_1_gimbal_1_1_quaternion_1ae33e49d12aeeb58bd50469474e8cc3e8} + +```cpp +float mavsdk::Gimbal::Quaternion::y {float(NAN)} +``` + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 2, also denoted as c. + + +### z {#structmavsdk_1_1_gimbal_1_1_quaternion_1a4a2173406079a5561cbe5fab511eed4a} + +```cpp +float mavsdk::Gimbal::Quaternion::z {float(NAN)} +``` + + +[Quaternion](structmavsdk_1_1_gimbal_1_1_quaternion.md) entry 3, also denoted as d. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_flight_info.md b/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_flight_info.md index cc37b6b4d2..3e295fb196 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_flight_info.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_flight_info.md @@ -14,6 +14,10 @@ uint32_t [time_boot_ms](#structmavsdk_1_1_info_1_1_flight_info_1aa38f317ec1c38bc uint64_t [flight_uid](#structmavsdk_1_1_info_1_1_flight_info_1adfae0cbebc461eb3ab144d7173cca9e8) {} - Flight counter. Starts from zero, is incremented at every disarm and is never reset (even after reboot) +uint32_t [duration_since_arming_ms](#structmavsdk_1_1_info_1_1_flight_info_1a29404e4b5d2581f70dc7880ac5add47d) {} - Duration since arming in milliseconds. + +uint32_t [duration_since_takeoff_ms](#structmavsdk_1_1_info_1_1_flight_info_1a2167b2a6df2fdcbc0823a0876d139c79) {} - Duration since takeoff in milliseconds. + ## Field Documentation @@ -37,3 +41,23 @@ uint64_t mavsdk::Info::FlightInfo::flight_uid {} Flight counter. Starts from zero, is incremented at every disarm and is never reset (even after reboot) + +### duration_since_arming_ms {#structmavsdk_1_1_info_1_1_flight_info_1a29404e4b5d2581f70dc7880ac5add47d} + +```cpp +uint32_t mavsdk::Info::FlightInfo::duration_since_arming_ms {} +``` + + +Duration since arming in milliseconds. + + +### duration_since_takeoff_ms {#structmavsdk_1_1_info_1_1_flight_info_1a2167b2a6df2fdcbc0823a0876d139c79} + +```cpp +uint32_t mavsdk::Info::FlightInfo::duration_since_takeoff_ms {} +``` + + +Duration since takeoff in milliseconds. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_identification.md b/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_identification.md index 6a8391fe54..4a21ac53cd 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_identification.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_info_1_1_identification.md @@ -1,39 +1,39 @@ -# mavsdk::Info::Identification Struct Reference -`#include: info.h` - ----- - - -[System](classmavsdk_1_1_system.md) identification. - - -## Data Fields - - -std::string [hardware_uid](#structmavsdk_1_1_info_1_1_identification_1a68be9823aae193b5473191d287b5e385) {} - UID of the hardware. This refers to uid2 of MAVLink. If the system does not support uid2 yet, this is all zeros. - -uint64_t [legacy_uid](#structmavsdk_1_1_info_1_1_identification_1a2429c1ffc3fbda0d55e85fa5a6f79dc1) {} - Legacy UID of the hardware, referred to as uid in MAVLink (formerly exposed during system discovery as UUID). - - -## Field Documentation - - -### hardware_uid {#structmavsdk_1_1_info_1_1_identification_1a68be9823aae193b5473191d287b5e385} - -```cpp -std::string mavsdk::Info::Identification::hardware_uid {} -``` - - -UID of the hardware. This refers to uid2 of MAVLink. If the system does not support uid2 yet, this is all zeros. - - -### legacy_uid {#structmavsdk_1_1_info_1_1_identification_1a2429c1ffc3fbda0d55e85fa5a6f79dc1} - -```cpp -uint64_t mavsdk::Info::Identification::legacy_uid {} -``` - - -Legacy UID of the hardware, referred to as uid in MAVLink (formerly exposed during system discovery as UUID). - +# mavsdk::Info::Identification Struct Reference +`#include: info.h` + +---- + + +[System](classmavsdk_1_1_system.md) identification. + + +## Data Fields + + +std::string [hardware_uid](#structmavsdk_1_1_info_1_1_identification_1a68be9823aae193b5473191d287b5e385) {} - UID of the hardware. This refers to uid2 of MAVLink. If the system does not support uid2 yet, this is all zeros. + +uint64_t [legacy_uid](#structmavsdk_1_1_info_1_1_identification_1a2429c1ffc3fbda0d55e85fa5a6f79dc1) {} - Legacy UID of the hardware, referred to as uid in MAVLink (formerly exposed during system discovery as UUID). + + +## Field Documentation + + +### hardware_uid {#structmavsdk_1_1_info_1_1_identification_1a68be9823aae193b5473191d287b5e385} + +```cpp +std::string mavsdk::Info::Identification::hardware_uid {} +``` + + +UID of the hardware. This refers to uid2 of MAVLink. If the system does not support uid2 yet, this is all zeros. + + +### legacy_uid {#structmavsdk_1_1_info_1_1_identification_1a2429c1ffc3fbda0d55e85fa5a6f79dc1} + +```cpp +uint64_t mavsdk::Info::Identification::legacy_uid {} +``` + + +Legacy UID of the hardware, referred to as uid in MAVLink (formerly exposed during system discovery as UUID). + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md b/docs/en/cpp/api_reference/structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md new file mode 100644 index 0000000000..049dd9f97e --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_log_streaming_1_1_log_streaming_raw.md @@ -0,0 +1,27 @@ +# mavsdk::LogStreaming::LogStreamingRaw Struct Reference +`#include: log_streaming.h` + +---- + + +Raw logging data type. + + +## Data Fields + + +std::string [data_base64](#structmavsdk_1_1_log_streaming_1_1_log_streaming_raw_1aec57f1eae019a51c09bce6f887dafb60) {} - Ulog file stream data encoded as base64. + + +## Field Documentation + + +### data_base64 {#structmavsdk_1_1_log_streaming_1_1_log_streaming_raw_1aec57f1eae019a51c09bce6f887dafb60} + +```cpp +std::string mavsdk::LogStreaming::LogStreamingRaw::data_base64 {} +``` + + +Ulog file stream data encoded as base64. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_mavsdk_1_1_connection_error.md b/docs/en/cpp/api_reference/structmavsdk_1_1_mavsdk_1_1_connection_error.md new file mode 100644 index 0000000000..d7b13dfde3 --- /dev/null +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_mavsdk_1_1_connection_error.md @@ -0,0 +1,39 @@ +# mavsdk::Mavsdk::ConnectionError Struct Reference +`#include: mavsdk.h` + +---- + + +[ConnectionError](structmavsdk_1_1_mavsdk_1_1_connection_error.md) type + + +## Data Fields + + +std::string [error_description](#structmavsdk_1_1_mavsdk_1_1_connection_error_1a3f017cb6e947849d900ebd84799f2ecc) - The error description. + +[ConnectionHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a1b16edeae47af0815b3267c9075f6a8f) [connection_handle](#structmavsdk_1_1_mavsdk_1_1_connection_error_1ad5d30e153d373a8aba910654bb3ae7fb) - The connection handle. + + +## Field Documentation + + +### error_description {#structmavsdk_1_1_mavsdk_1_1_connection_error_1a3f017cb6e947849d900ebd84799f2ecc} + +```cpp +std::string mavsdk::Mavsdk::ConnectionError::error_description +``` + + +The error description. + + +### connection_handle {#structmavsdk_1_1_mavsdk_1_1_connection_error_1ad5d30e153d373a8aba910654bb3ae7fb} + +```cpp +ConnectionHandle mavsdk::Mavsdk::ConnectionError::connection_handle +``` + + +The connection handle. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_param_1_1_float_param.md b/docs/en/cpp/api_reference/structmavsdk_1_1_param_1_1_float_param.md index 7f669839f1..196adc40c4 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_param_1_1_float_param.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_param_1_1_float_param.md @@ -1,39 +1,39 @@ -# mavsdk::Param::FloatParam Struct Reference -`#include: param.h` - ----- - - -Type for float parameters. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_param_1_1_float_param_1a64b1dd40eb04c1fa8f9de7ad2c868a3f) {} - Name of the parameter. - -float [value](#structmavsdk_1_1_param_1_1_float_param_1a65d2f28d30739bfb8b1ceb8785c51f66) {} - Value of the parameter. - - -## Field Documentation - - -### name {#structmavsdk_1_1_param_1_1_float_param_1a64b1dd40eb04c1fa8f9de7ad2c868a3f} - -```cpp -std::string mavsdk::Param::FloatParam::name {} -``` - - -Name of the parameter. - - -### value {#structmavsdk_1_1_param_1_1_float_param_1a65d2f28d30739bfb8b1ceb8785c51f66} - -```cpp -float mavsdk::Param::FloatParam::value {} -``` - - -Value of the parameter. - +# mavsdk::Param::FloatParam Struct Reference +`#include: param.h` + +---- + + +Type for float parameters. + + +## Data Fields + + +std::string [name](#structmavsdk_1_1_param_1_1_float_param_1a64b1dd40eb04c1fa8f9de7ad2c868a3f) {} - Name of the parameter. + +float [value](#structmavsdk_1_1_param_1_1_float_param_1a65d2f28d30739bfb8b1ceb8785c51f66) {} - Value of the parameter. + + +## Field Documentation + + +### name {#structmavsdk_1_1_param_1_1_float_param_1a64b1dd40eb04c1fa8f9de7ad2c868a3f} + +```cpp +std::string mavsdk::Param::FloatParam::name {} +``` + + +Name of the parameter. + + +### value {#structmavsdk_1_1_param_1_1_float_param_1a65d2f28d30739bfb8b1ceb8785c51f66} + +```cpp +float mavsdk::Param::FloatParam::value {} +``` + + +Value of the parameter. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_float_param.md b/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_float_param.md index b927b4c601..c83778a510 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_float_param.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_float_param.md @@ -1,39 +1,39 @@ -# mavsdk::ParamServer::FloatParam Struct Reference -`#include: param_server.h` - ----- - - -Type for float parameters. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_param_server_1_1_float_param_1a3988384276ac7ffad9bede8d60a8b50e) {} - Name of the parameter. - -float [value](#structmavsdk_1_1_param_server_1_1_float_param_1a515a8aef124b471b4763bad39015d536) {} - Value of the parameter. - - -## Field Documentation - - -### name {#structmavsdk_1_1_param_server_1_1_float_param_1a3988384276ac7ffad9bede8d60a8b50e} - -```cpp -std::string mavsdk::ParamServer::FloatParam::name {} -``` - - -Name of the parameter. - - -### value {#structmavsdk_1_1_param_server_1_1_float_param_1a515a8aef124b471b4763bad39015d536} - -```cpp -float mavsdk::ParamServer::FloatParam::value {} -``` - - -Value of the parameter. - +# mavsdk::ParamServer::FloatParam Struct Reference +`#include: param_server.h` + +---- + + +Type for float parameters. + + +## Data Fields + + +std::string [name](#structmavsdk_1_1_param_server_1_1_float_param_1a3988384276ac7ffad9bede8d60a8b50e) {} - Name of the parameter. + +float [value](#structmavsdk_1_1_param_server_1_1_float_param_1a515a8aef124b471b4763bad39015d536) {} - Value of the parameter. + + +## Field Documentation + + +### name {#structmavsdk_1_1_param_server_1_1_float_param_1a3988384276ac7ffad9bede8d60a8b50e} + +```cpp +std::string mavsdk::ParamServer::FloatParam::name {} +``` + + +Name of the parameter. + + +### value {#structmavsdk_1_1_param_server_1_1_float_param_1a515a8aef124b471b4763bad39015d536} + +```cpp +float mavsdk::ParamServer::FloatParam::value {} +``` + + +Value of the parameter. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_int_param.md b/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_int_param.md index 3a865f831d..42d1c98c65 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_int_param.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_param_server_1_1_int_param.md @@ -1,39 +1,39 @@ -# mavsdk::ParamServer::IntParam Struct Reference -`#include: param_server.h` - ----- - - -Type for integer parameters. - - -## Data Fields - - -std::string [name](#structmavsdk_1_1_param_server_1_1_int_param_1aae5236fe2a7753bff87dec3eae56c292) {} - Name of the parameter. - -int32_t [value](#structmavsdk_1_1_param_server_1_1_int_param_1ad826ffbeb58e4d975c60dc355c96ffb2) {} - Value of the parameter. - - -## Field Documentation - - -### name {#structmavsdk_1_1_param_server_1_1_int_param_1aae5236fe2a7753bff87dec3eae56c292} - -```cpp -std::string mavsdk::ParamServer::IntParam::name {} -``` - - -Name of the parameter. - - -### value {#structmavsdk_1_1_param_server_1_1_int_param_1ad826ffbeb58e4d975c60dc355c96ffb2} - -```cpp -int32_t mavsdk::ParamServer::IntParam::value {} -``` - - -Value of the parameter. - +# mavsdk::ParamServer::IntParam Struct Reference +`#include: param_server.h` + +---- + + +Type for integer parameters. + + +## Data Fields + + +std::string [name](#structmavsdk_1_1_param_server_1_1_int_param_1aae5236fe2a7753bff87dec3eae56c292) {} - Name of the parameter. + +int32_t [value](#structmavsdk_1_1_param_server_1_1_int_param_1ad826ffbeb58e4d975c60dc355c96ffb2) {} - Value of the parameter. + + +## Field Documentation + + +### name {#structmavsdk_1_1_param_server_1_1_int_param_1aae5236fe2a7753bff87dec3eae56c292} + +```cpp +std::string mavsdk::ParamServer::IntParam::name {} +``` + + +Name of the parameter. + + +### value {#structmavsdk_1_1_param_server_1_1_int_param_1ad826ffbeb58e4d975c60dc355c96ffb2} + +```cpp +int32_t mavsdk::ParamServer::IntParam::value {} +``` + + +Value of the parameter. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_rtk_1_1_rtcm_data.md b/docs/en/cpp/api_reference/structmavsdk_1_1_rtk_1_1_rtcm_data.md index c18dcca14f..56e0ff1e44 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_rtk_1_1_rtcm_data.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_rtk_1_1_rtcm_data.md @@ -10,18 +10,18 @@ RTCM data type. ## Data Fields -std::string [data](#structmavsdk_1_1_rtk_1_1_rtcm_data_1aeed6ee4ada82ac78707d3dcda34f9da0) {} - The data encoded as a string. +std::string [data_base64](#structmavsdk_1_1_rtk_1_1_rtcm_data_1afdd80ba138b2e4484c92597a34a1a3e8) {} - The data encoded as a base64 string. ## Field Documentation -### data {#structmavsdk_1_1_rtk_1_1_rtcm_data_1aeed6ee4ada82ac78707d3dcda34f9da0} +### data_base64 {#structmavsdk_1_1_rtk_1_1_rtcm_data_1afdd80ba138b2e4484c92597a34a1a3e8} ```cpp -std::string mavsdk::Rtk::RtcmData::data {} +std::string mavsdk::Rtk::RtcmData::data_base64 {} ``` -The data encoded as a string. +The data encoded as a base64 string. diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_system_1_1_autopilot_version.md b/docs/en/cpp/api_reference/structmavsdk_1_1_system_1_1_autopilot_version.md deleted file mode 100644 index 3c4dc92589..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_system_1_1_autopilot_version.md +++ /dev/null @@ -1,114 +0,0 @@ -# mavsdk::System::AutopilotVersion Struct Reference -`#include: system.h` - ----- - - -This struct represents Autopilot version information. This is only used when MAVSDK is configured as an autopilot. - - -Other MAVLink systems can use this to identify and match software and capabilities. - - -## Data Fields - - -uint64_t [capabilities](#structmavsdk_1_1_system_1_1_autopilot_version_1a3c4e4f2fb21b67f9d676adbe0ec32ce6) {} - MAVLink autopilot_version capabilities. - -uint32_t [flight_sw_version](#structmavsdk_1_1_system_1_1_autopilot_version_1a50dccbc4c01e07a65dda21ab7bb49e7f) {0} - MAVLink autopilot_version flight_sw_version. - -uint32_t [middleware_sw_version](#structmavsdk_1_1_system_1_1_autopilot_version_1a737e740ddc844306a086e0c779568951) {0} - MAVLink autopilot_version middleware_sw_version. - -uint32_t [os_sw_version](#structmavsdk_1_1_system_1_1_autopilot_version_1aa120013fe26560952d19f5d2bee1df01) {0} - MAVLink autopilot_version os_sw_version. - -uint32_t [board_version](#structmavsdk_1_1_system_1_1_autopilot_version_1ab5fa9c33f5493e68fbe4b8407f07ba8d) {0} - MAVLink autopilot_version board_version. - -uint16_t [vendor_id](#structmavsdk_1_1_system_1_1_autopilot_version_1a04b6ff2e1add2247a8c510e018efb81a) {0} - MAVLink autopilot_version vendor_id. - -uint16_t [product_id](#structmavsdk_1_1_system_1_1_autopilot_version_1a0c09156f2c75545f3895023fe22f80ec) {0} - MAVLink autopilot_version product_id. - -std::array< uint8_t, 18 > [uid2](#structmavsdk_1_1_system_1_1_autopilot_version_1a7f0bd696e9200a6e3c802fd9b05adca9) {0} - MAVLink autopilot_version uid2. - - -## Field Documentation - - -### capabilities {#structmavsdk_1_1_system_1_1_autopilot_version_1a3c4e4f2fb21b67f9d676adbe0ec32ce6} - -```cpp -uint64_t mavsdk::System::AutopilotVersion::capabilities {} -``` - - -MAVLink autopilot_version capabilities. - - -### flight_sw_version {#structmavsdk_1_1_system_1_1_autopilot_version_1a50dccbc4c01e07a65dda21ab7bb49e7f} - -```cpp -uint32_t mavsdk::System::AutopilotVersion::flight_sw_version {0} -``` - - -MAVLink autopilot_version flight_sw_version. - - -### middleware_sw_version {#structmavsdk_1_1_system_1_1_autopilot_version_1a737e740ddc844306a086e0c779568951} - -```cpp -uint32_t mavsdk::System::AutopilotVersion::middleware_sw_version {0} -``` - - -MAVLink autopilot_version middleware_sw_version. - - -### os_sw_version {#structmavsdk_1_1_system_1_1_autopilot_version_1aa120013fe26560952d19f5d2bee1df01} - -```cpp -uint32_t mavsdk::System::AutopilotVersion::os_sw_version {0} -``` - - -MAVLink autopilot_version os_sw_version. - - -### board_version {#structmavsdk_1_1_system_1_1_autopilot_version_1ab5fa9c33f5493e68fbe4b8407f07ba8d} - -```cpp -uint32_t mavsdk::System::AutopilotVersion::board_version {0} -``` - - -MAVLink autopilot_version board_version. - - -### vendor_id {#structmavsdk_1_1_system_1_1_autopilot_version_1a04b6ff2e1add2247a8c510e018efb81a} - -```cpp -uint16_t mavsdk::System::AutopilotVersion::vendor_id {0} -``` - - -MAVLink autopilot_version vendor_id. - - -### product_id {#structmavsdk_1_1_system_1_1_autopilot_version_1a0c09156f2c75545f3895023fe22f80ec} - -```cpp -uint16_t mavsdk::System::AutopilotVersion::product_id {0} -``` - - -MAVLink autopilot_version product_id. - - -### uid2 {#structmavsdk_1_1_system_1_1_autopilot_version_1a7f0bd696e9200a6e3c802fd9b05adca9} - -```cpp -std::array mavsdk::System::AutopilotVersion::uid2 {0} -``` - - -MAVLink autopilot_version uid2. - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_fixedwing_metrics.md b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_fixedwing_metrics.md index f7a35f9aad..74a77c0c26 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_fixedwing_metrics.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_fixedwing_metrics.md @@ -16,6 +16,12 @@ float [throttle_percentage](#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1a float [climb_rate_m_s](#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1a9bc33e3e1ea00ad6fd4ef385c20b1233) {float(NAN)} - Current climb rate in metres per second. +float [groundspeed_m_s](#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1af0b1ea02e78baea35235a66b3077de82) {float(NAN)} - Current groundspeed metres per second. + +float [heading_deg](#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1a80e3b31e3288fe11bb7eaa97b31409da) { float(NAN)} - Current heading in compass units (0-360, 0=north) + +float [absolute_altitude_m](#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1a197cc902b11b366c8e3c556817da9a7b) {float(NAN)} - Current altitude in metres (MSL) + ## Field Documentation @@ -49,3 +55,33 @@ float mavsdk::Telemetry::FixedwingMetrics::climb_rate_m_s {float(NAN)} Current climb rate in metres per second. + +### groundspeed_m_s {#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1af0b1ea02e78baea35235a66b3077de82} + +```cpp +float mavsdk::Telemetry::FixedwingMetrics::groundspeed_m_s {float(NAN)} +``` + + +Current groundspeed metres per second. + + +### heading_deg {#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1a80e3b31e3288fe11bb7eaa97b31409da} + +```cpp +float mavsdk::Telemetry::FixedwingMetrics::heading_deg { float(NAN)} +``` + + +Current heading in compass units (0-360, 0=north) + + +### absolute_altitude_m {#structmavsdk_1_1_telemetry_1_1_fixedwing_metrics_1a197cc902b11b366c8e3c556817da9a7b} + +```cpp +float mavsdk::Telemetry::FixedwingMetrics::absolute_altitude_m {float(NAN)} +``` + + +Current altitude in metres (MSL) + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_health.md b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_health.md index 26d3809215..269aae16f6 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_health.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_health.md @@ -1,99 +1,99 @@ -# mavsdk::Telemetry::Health Struct Reference -`#include: telemetry.h` - ----- - - -[Health](structmavsdk_1_1_telemetry_1_1_health.md) type. - - -## Data Fields - - -bool [is_gyrometer_calibration_ok](#structmavsdk_1_1_telemetry_1_1_health_1a4ce524d8a5ca42e50cf615ddade4bac4) {false} - True if the gyrometer is calibrated. - -bool [is_accelerometer_calibration_ok](#structmavsdk_1_1_telemetry_1_1_health_1a910417712b6960d371e79acdb5a19e35) { false} - True if the accelerometer is calibrated. - -bool [is_magnetometer_calibration_ok](#structmavsdk_1_1_telemetry_1_1_health_1ac99ff7621f22a5148adfbb03004fccc8) { false} - True if the magnetometer is calibrated. - -bool [is_local_position_ok](#structmavsdk_1_1_telemetry_1_1_health_1a86da005d0191a856b649d679e03b78b4) {false} - True if the local position estimate is good enough to fly in 'position control' mode. - -bool [is_global_position_ok](#structmavsdk_1_1_telemetry_1_1_health_1ae85eb066716de1eef1a1bd3f6b375c6c) {false} - True if the global position estimate is good enough to fly in 'position control' mode. - -bool [is_home_position_ok](#structmavsdk_1_1_telemetry_1_1_health_1ad67d5e7ef46fd34246011d31f95049fa) { false} - True if the home position has been initialized properly. - -bool [is_armable](#structmavsdk_1_1_telemetry_1_1_health_1a7fbe53f1255bce1dcb30d4cd33c3d4f7) {false} - True if system can be armed. - - -## Field Documentation - - -### is_gyrometer_calibration_ok {#structmavsdk_1_1_telemetry_1_1_health_1a4ce524d8a5ca42e50cf615ddade4bac4} - -```cpp -bool mavsdk::Telemetry::Health::is_gyrometer_calibration_ok {false} -``` - - -True if the gyrometer is calibrated. - - -### is_accelerometer_calibration_ok {#structmavsdk_1_1_telemetry_1_1_health_1a910417712b6960d371e79acdb5a19e35} - -```cpp -bool mavsdk::Telemetry::Health::is_accelerometer_calibration_ok { false} -``` - - -True if the accelerometer is calibrated. - - -### is_magnetometer_calibration_ok {#structmavsdk_1_1_telemetry_1_1_health_1ac99ff7621f22a5148adfbb03004fccc8} - -```cpp -bool mavsdk::Telemetry::Health::is_magnetometer_calibration_ok { false} -``` - - -True if the magnetometer is calibrated. - - -### is_local_position_ok {#structmavsdk_1_1_telemetry_1_1_health_1a86da005d0191a856b649d679e03b78b4} - -```cpp -bool mavsdk::Telemetry::Health::is_local_position_ok {false} -``` - - -True if the local position estimate is good enough to fly in 'position control' mode. - - -### is_global_position_ok {#structmavsdk_1_1_telemetry_1_1_health_1ae85eb066716de1eef1a1bd3f6b375c6c} - -```cpp -bool mavsdk::Telemetry::Health::is_global_position_ok {false} -``` - - -True if the global position estimate is good enough to fly in 'position control' mode. - - -### is_home_position_ok {#structmavsdk_1_1_telemetry_1_1_health_1ad67d5e7ef46fd34246011d31f95049fa} - -```cpp -bool mavsdk::Telemetry::Health::is_home_position_ok { false} -``` - - -True if the home position has been initialized properly. - - -### is_armable {#structmavsdk_1_1_telemetry_1_1_health_1a7fbe53f1255bce1dcb30d4cd33c3d4f7} - -```cpp -bool mavsdk::Telemetry::Health::is_armable {false} -``` - - -True if system can be armed. - +# mavsdk::Telemetry::Health Struct Reference +`#include: telemetry.h` + +---- + + +[Health](structmavsdk_1_1_telemetry_1_1_health.md) type. + + +## Data Fields + + +bool [is_gyrometer_calibration_ok](#structmavsdk_1_1_telemetry_1_1_health_1a4ce524d8a5ca42e50cf615ddade4bac4) {false} - True if the gyrometer is calibrated. + +bool [is_accelerometer_calibration_ok](#structmavsdk_1_1_telemetry_1_1_health_1a910417712b6960d371e79acdb5a19e35) { false} - True if the accelerometer is calibrated. + +bool [is_magnetometer_calibration_ok](#structmavsdk_1_1_telemetry_1_1_health_1ac99ff7621f22a5148adfbb03004fccc8) { false} - True if the magnetometer is calibrated. + +bool [is_local_position_ok](#structmavsdk_1_1_telemetry_1_1_health_1a86da005d0191a856b649d679e03b78b4) {false} - True if the local position estimate is good enough to fly in 'position control' mode. + +bool [is_global_position_ok](#structmavsdk_1_1_telemetry_1_1_health_1ae85eb066716de1eef1a1bd3f6b375c6c) {false} - True if the global position estimate is good enough to fly in 'position control' mode. + +bool [is_home_position_ok](#structmavsdk_1_1_telemetry_1_1_health_1ad67d5e7ef46fd34246011d31f95049fa) { false} - True if the home position has been initialized properly. + +bool [is_armable](#structmavsdk_1_1_telemetry_1_1_health_1a7fbe53f1255bce1dcb30d4cd33c3d4f7) {false} - True if system can be armed. + + +## Field Documentation + + +### is_gyrometer_calibration_ok {#structmavsdk_1_1_telemetry_1_1_health_1a4ce524d8a5ca42e50cf615ddade4bac4} + +```cpp +bool mavsdk::Telemetry::Health::is_gyrometer_calibration_ok {false} +``` + + +True if the gyrometer is calibrated. + + +### is_accelerometer_calibration_ok {#structmavsdk_1_1_telemetry_1_1_health_1a910417712b6960d371e79acdb5a19e35} + +```cpp +bool mavsdk::Telemetry::Health::is_accelerometer_calibration_ok { false} +``` + + +True if the accelerometer is calibrated. + + +### is_magnetometer_calibration_ok {#structmavsdk_1_1_telemetry_1_1_health_1ac99ff7621f22a5148adfbb03004fccc8} + +```cpp +bool mavsdk::Telemetry::Health::is_magnetometer_calibration_ok { false} +``` + + +True if the magnetometer is calibrated. + + +### is_local_position_ok {#structmavsdk_1_1_telemetry_1_1_health_1a86da005d0191a856b649d679e03b78b4} + +```cpp +bool mavsdk::Telemetry::Health::is_local_position_ok {false} +``` + + +True if the local position estimate is good enough to fly in 'position control' mode. + + +### is_global_position_ok {#structmavsdk_1_1_telemetry_1_1_health_1ae85eb066716de1eef1a1bd3f6b375c6c} + +```cpp +bool mavsdk::Telemetry::Health::is_global_position_ok {false} +``` + + +True if the global position estimate is good enough to fly in 'position control' mode. + + +### is_home_position_ok {#structmavsdk_1_1_telemetry_1_1_health_1ad67d5e7ef46fd34246011d31f95049fa} + +```cpp +bool mavsdk::Telemetry::Health::is_home_position_ok { false} +``` + + +True if the home position has been initialized properly. + + +### is_armable {#structmavsdk_1_1_telemetry_1_1_health_1a7fbe53f1255bce1dcb30d4cd33c3d4f7} + +```cpp +bool mavsdk::Telemetry::Health::is_armable {false} +``` + + +True if system can be armed. + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_rc_status.md b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_rc_status.md index 55ea867766..f04a6da172 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_rc_status.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_rc_status.md @@ -1,51 +1,51 @@ -# mavsdk::Telemetry::RcStatus Struct Reference -`#include: telemetry.h` - ----- - - -Remote control status type. - - -## Data Fields - - -bool [was_available_once](#structmavsdk_1_1_telemetry_1_1_rc_status_1ab137802b6d9e6d9fde0822d3d42fe900) {false} - True if an RC signal has been available once. - -bool [is_available](#structmavsdk_1_1_telemetry_1_1_rc_status_1a6949a32def1be5468cab9b4ce5c15b07) {false} - True if the RC signal is available now. - -float [signal_strength_percent](#structmavsdk_1_1_telemetry_1_1_rc_status_1a5d637a687d2bcc84abef28ff0f1ab31e) { float(NAN)} - Signal strength (range: 0 to 100, NaN if unknown) - - -## Field Documentation - - -### was_available_once {#structmavsdk_1_1_telemetry_1_1_rc_status_1ab137802b6d9e6d9fde0822d3d42fe900} - -```cpp -bool mavsdk::Telemetry::RcStatus::was_available_once {false} -``` - - -True if an RC signal has been available once. - - -### is_available {#structmavsdk_1_1_telemetry_1_1_rc_status_1a6949a32def1be5468cab9b4ce5c15b07} - -```cpp -bool mavsdk::Telemetry::RcStatus::is_available {false} -``` - - -True if the RC signal is available now. - - -### signal_strength_percent {#structmavsdk_1_1_telemetry_1_1_rc_status_1a5d637a687d2bcc84abef28ff0f1ab31e} - -```cpp -float mavsdk::Telemetry::RcStatus::signal_strength_percent { float(NAN)} -``` - - -Signal strength (range: 0 to 100, NaN if unknown) - +# mavsdk::Telemetry::RcStatus Struct Reference +`#include: telemetry.h` + +---- + + +Remote control status type. + + +## Data Fields + + +bool [was_available_once](#structmavsdk_1_1_telemetry_1_1_rc_status_1ab137802b6d9e6d9fde0822d3d42fe900) {false} - True if an RC signal has been available once. + +bool [is_available](#structmavsdk_1_1_telemetry_1_1_rc_status_1a6949a32def1be5468cab9b4ce5c15b07) {false} - True if the RC signal is available now. + +float [signal_strength_percent](#structmavsdk_1_1_telemetry_1_1_rc_status_1a5d637a687d2bcc84abef28ff0f1ab31e) { float(NAN)} - Signal strength (range: 0 to 100, NaN if unknown) + + +## Field Documentation + + +### was_available_once {#structmavsdk_1_1_telemetry_1_1_rc_status_1ab137802b6d9e6d9fde0822d3d42fe900} + +```cpp +bool mavsdk::Telemetry::RcStatus::was_available_once {false} +``` + + +True if an RC signal has been available once. + + +### is_available {#structmavsdk_1_1_telemetry_1_1_rc_status_1a6949a32def1be5468cab9b4ce5c15b07} + +```cpp +bool mavsdk::Telemetry::RcStatus::is_available {false} +``` + + +True if the RC signal is available now. + + +### signal_strength_percent {#structmavsdk_1_1_telemetry_1_1_rc_status_1a5d637a687d2bcc84abef28ff0f1ab31e} + +```cpp +float mavsdk::Telemetry::RcStatus::signal_strength_percent { float(NAN)} +``` + + +Signal strength (range: 0 to 100, NaN if unknown) + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_scaled_pressure.md b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_scaled_pressure.md index efc719a33f..86911f2378 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_scaled_pressure.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_1_1_scaled_pressure.md @@ -1,75 +1,75 @@ -# mavsdk::Telemetry::ScaledPressure Struct Reference -`#include: telemetry.h` - ----- - - -Scaled Pressure message type. - - -## Data Fields - - -uint64_t [timestamp_us](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1a37d91f3f8470a21ee36ce55bd9977d67) {} - Timestamp (time since system boot) - -float [absolute_pressure_hpa](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1abacfc48910bc70f49b5852a4185898ef) {} - Absolute pressure in hPa. - -float [differential_pressure_hpa](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1ac60181897aae8504209912e0d8818e9b) {} - Differential pressure 1 in hPa. - -float [temperature_deg](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1adadf4a1be58f4d8cb5d856a9ca767ed4) {} - Absolute pressure temperature (in celsius) - -float [differential_pressure_temperature_deg](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1afa6c5d02d87be13bd08d5a2706b694aa) {} - Differential pressure temperature (in celsius, 0 if not available) - - -## Field Documentation - - -### timestamp_us {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1a37d91f3f8470a21ee36ce55bd9977d67} - -```cpp -uint64_t mavsdk::Telemetry::ScaledPressure::timestamp_us {} -``` - - -Timestamp (time since system boot) - - -### absolute_pressure_hpa {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1abacfc48910bc70f49b5852a4185898ef} - -```cpp -float mavsdk::Telemetry::ScaledPressure::absolute_pressure_hpa {} -``` - - -Absolute pressure in hPa. - - -### differential_pressure_hpa {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1ac60181897aae8504209912e0d8818e9b} - -```cpp -float mavsdk::Telemetry::ScaledPressure::differential_pressure_hpa {} -``` - - -Differential pressure 1 in hPa. - - -### temperature_deg {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1adadf4a1be58f4d8cb5d856a9ca767ed4} - -```cpp -float mavsdk::Telemetry::ScaledPressure::temperature_deg {} -``` - - -Absolute pressure temperature (in celsius) - - -### differential_pressure_temperature_deg {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1afa6c5d02d87be13bd08d5a2706b694aa} - -```cpp -float mavsdk::Telemetry::ScaledPressure::differential_pressure_temperature_deg {} -``` - - -Differential pressure temperature (in celsius, 0 if not available) - +# mavsdk::Telemetry::ScaledPressure Struct Reference +`#include: telemetry.h` + +---- + + +Scaled Pressure message type. + + +## Data Fields + + +uint64_t [timestamp_us](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1a37d91f3f8470a21ee36ce55bd9977d67) {} - Timestamp (time since system boot) + +float [absolute_pressure_hpa](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1abacfc48910bc70f49b5852a4185898ef) {} - Absolute pressure in hPa. + +float [differential_pressure_hpa](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1ac60181897aae8504209912e0d8818e9b) {} - Differential pressure 1 in hPa. + +float [temperature_deg](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1adadf4a1be58f4d8cb5d856a9ca767ed4) {} - Absolute pressure temperature (in celsius) + +float [differential_pressure_temperature_deg](#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1afa6c5d02d87be13bd08d5a2706b694aa) {} - Differential pressure temperature (in celsius, 0 if not available) + + +## Field Documentation + + +### timestamp_us {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1a37d91f3f8470a21ee36ce55bd9977d67} + +```cpp +uint64_t mavsdk::Telemetry::ScaledPressure::timestamp_us {} +``` + + +Timestamp (time since system boot) + + +### absolute_pressure_hpa {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1abacfc48910bc70f49b5852a4185898ef} + +```cpp +float mavsdk::Telemetry::ScaledPressure::absolute_pressure_hpa {} +``` + + +Absolute pressure in hPa. + + +### differential_pressure_hpa {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1ac60181897aae8504209912e0d8818e9b} + +```cpp +float mavsdk::Telemetry::ScaledPressure::differential_pressure_hpa {} +``` + + +Differential pressure 1 in hPa. + + +### temperature_deg {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1adadf4a1be58f4d8cb5d856a9ca767ed4} + +```cpp +float mavsdk::Telemetry::ScaledPressure::temperature_deg {} +``` + + +Absolute pressure temperature (in celsius) + + +### differential_pressure_temperature_deg {#structmavsdk_1_1_telemetry_1_1_scaled_pressure_1afa6c5d02d87be13bd08d5a2706b694aa} + +```cpp +float mavsdk::Telemetry::ScaledPressure::differential_pressure_temperature_deg {} +``` + + +Differential pressure temperature (in celsius, 0 if not available) + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md index a79ae8c32f..7e98de69e0 100644 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md +++ b/docs/en/cpp/api_reference/structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics.md @@ -16,6 +16,12 @@ float [throttle_percentage](#structmavsdk_1_1_telemetry_server_1_1_fixedwing_met float [climb_rate_m_s](#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1a8486ccc7e96add636a228399a74b1019) {float(NAN)} - Current climb rate in metres per second. +float [groundspeed_m_s](#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1ac3d6a9651edb283a1217ef2dcee91fce) {float(NAN)} - Current groundspeed metres per second. + +float [heading_deg](#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1ab5cad9e76b47fec7f40282b0de8b75f3) { float(NAN)} - Current heading in compass units (0-360, 0=north) + +float [absolute_altitude_m](#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1adb56c63202cdcd9abcab1464ee138dbd) {float(NAN)} - Current altitude in metres (MSL) + ## Field Documentation @@ -49,3 +55,33 @@ float mavsdk::TelemetryServer::FixedwingMetrics::climb_rate_m_s {float(NAN)} Current climb rate in metres per second. + +### groundspeed_m_s {#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1ac3d6a9651edb283a1217ef2dcee91fce} + +```cpp +float mavsdk::TelemetryServer::FixedwingMetrics::groundspeed_m_s {float(NAN)} +``` + + +Current groundspeed metres per second. + + +### heading_deg {#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1ab5cad9e76b47fec7f40282b0de8b75f3} + +```cpp +float mavsdk::TelemetryServer::FixedwingMetrics::heading_deg { float(NAN)} +``` + + +Current heading in compass units (0-360, 0=north) + + +### absolute_altitude_m {#structmavsdk_1_1_telemetry_server_1_1_fixedwing_metrics_1adb56c63202cdcd9abcab1464ee138dbd} + +```cpp +float mavsdk::TelemetryServer::FixedwingMetrics::absolute_altitude_m {float(NAN)} +``` + + +Current altitude in metres (MSL) + diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_point.md b/docs/en/cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_point.md deleted file mode 100644 index 9d8579af81..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_point.md +++ /dev/null @@ -1,51 +0,0 @@ -# mavsdk::TrackingServer::TrackPoint Struct Reference -`#include: tracking_server.h` - ----- - - -Point description type. - - -## Data Fields - - -float [point_x](#structmavsdk_1_1_tracking_server_1_1_track_point_1a853c938e0ae6c618d4fe2e08cf763511) {} - Point to track x value (normalized 0..1, 0 is left, 1 is right). - -float [point_y](#structmavsdk_1_1_tracking_server_1_1_track_point_1af8d89f46a6b0ebd85a027832fe64aded) {} - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - -float [radius](#structmavsdk_1_1_tracking_server_1_1_track_point_1ac34f7779009f26b33dd4c86fcb010f85) {} - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - - -## Field Documentation - - -### point_x {#structmavsdk_1_1_tracking_server_1_1_track_point_1a853c938e0ae6c618d4fe2e08cf763511} - -```cpp -float mavsdk::TrackingServer::TrackPoint::point_x {} -``` - - -Point to track x value (normalized 0..1, 0 is left, 1 is right). - - -### point_y {#structmavsdk_1_1_tracking_server_1_1_track_point_1af8d89f46a6b0ebd85a027832fe64aded} - -```cpp -float mavsdk::TrackingServer::TrackPoint::point_y {} -``` - - -Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - - -### radius {#structmavsdk_1_1_tracking_server_1_1_track_point_1ac34f7779009f26b33dd4c86fcb010f85} - -```cpp -float mavsdk::TrackingServer::TrackPoint::radius {} -``` - - -Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - diff --git a/docs/en/cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_rectangle.md b/docs/en/cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_rectangle.md deleted file mode 100644 index b6861c9b95..0000000000 --- a/docs/en/cpp/api_reference/structmavsdk_1_1_tracking_server_1_1_track_rectangle.md +++ /dev/null @@ -1,63 +0,0 @@ -# mavsdk::TrackingServer::TrackRectangle Struct Reference -`#include: tracking_server.h` - ----- - - -Rectangle description type. - - -## Data Fields - - -float [top_left_corner_x](#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1aa4ddff2dd970ee04e17b7744249cc8a4) {} - Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - -float [top_left_corner_y](#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1a277494afe3b3f9fde3bca320989ca5d7) {} - Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - -float [bottom_right_corner_x](#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1a71c6140a7c6332fed079359723b3f86b) {} - Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - -float [bottom_right_corner_y](#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1aab56c0de04020104b4c5cbf6fe2e69a5) {} - Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - - -## Field Documentation - - -### top_left_corner_x {#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1aa4ddff2dd970ee04e17b7744249cc8a4} - -```cpp -float mavsdk::TrackingServer::TrackRectangle::top_left_corner_x {} -``` - - -Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - - -### top_left_corner_y {#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1a277494afe3b3f9fde3bca320989ca5d7} - -```cpp -float mavsdk::TrackingServer::TrackRectangle::top_left_corner_y {} -``` - - -Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - - -### bottom_right_corner_x {#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1a71c6140a7c6332fed079359723b3f86b} - -```cpp -float mavsdk::TrackingServer::TrackRectangle::bottom_right_corner_x {} -``` - - -Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - - -### bottom_right_corner_y {#structmavsdk_1_1_tracking_server_1_1_track_rectangle_1aab56c0de04020104b4c5cbf6fe2e69a5} - -```cpp -float mavsdk::TrackingServer::TrackRectangle::bottom_right_corner_y {} -``` - - -Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - diff --git a/docs/en/cpp/contributing/autogen.md b/docs/en/cpp/contributing/autogen.md index eba7e1e56d..2053dd46b8 100644 --- a/docs/en/cpp/contributing/autogen.md +++ b/docs/en/cpp/contributing/autogen.md @@ -1,64 +1,64 @@ -# Autogeneration - -MAVSDK is available in a number of different languages. -These all share the same "core" MAVLink implementation (written in C++), but almost all of the API-specific code for other languages is *autogenerated* from API definition files (and language-specific templates). - -This approach means that we don't have to maintain a separate MAVLink implementation or API for each language. -New features are implemented (just once) in C++, and are then automatically available in Python, Java, etc. - -This page provides an overview of the architecture and explains how to add a feature using the autogeneration. - -## Overview - -The common MAVLink implementation is written in C++ (it is part of MAVSDK-C++). -The `mavsdk_server` exposes the MAVSDK-C++ API over [gRPC](https://grpc.io/) to the language bindings. -The API for all languages is autogenerated from a single common definition. - -![MAVSDK structure/architecture](../../../assets/autogen/mavsdk_overview.png) - -The following parts are autogenerated: - -* MAVSDK-C++ API (i.e. header files) -* Most of `mavsdk_server` -* Most of the language bindings - -Those parts are maintained manually: - -* MAVSDK-C++ implementation (i.e. the MAVLink business logic) -* New plugins need to be added to `mavsdk_server` (this may be automated in future) -* The `System` wrapper in language bindings usually needs to be updated whenever a new plugin is added (this may be automated in future) - -The heart of the autogeneration system is the [MAVSDK-Proto](https://github.com/mavlink/mavsdk-proto) repository which is described [below](#mechanisms). - -## Autogeneration Mechanisms {#mechanisms} - -The autogeneration pipeline is shown below: - -![Autogeneration pipeline](../../../assets/autogen/autogen_overview.png) - -The main parts are: - -* [`protoc-gen-mavsdk`](https://github.com/mavlink/MAVSDK-Proto/tree/main/pb_plugins), which is a `protoc` custom plugin generating MAVSDK's code. -* [The API definition](https://github.com/mavlink/MAVSDK-Proto/tree/main/protos), in the form of proto files. -* Template files (per language, see e.g. the [Python templates](https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py) or the [C++ templates](https://github.com/mavlink/MAVSDK/tree/main/templates)). - - -`protoc` takes the custom plugin (`protoc-gen-mavsdk`) and the template files as inputs, and generate source code out of it. -The way it currently works is that it generates one source file out of each `*.proto` file. For instance, `action.proto` becomes `Action.java` in MAVSDK-Java. - -In some languages (typically C++), we need to generate multiple source files out of one proto definition file, and this is the reason why the C++ generation script runs protoc [in](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L72-L74) [multiple](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L76-L77) [passes](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L79-L81), once [for each template](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L61) (e.g. "templates/plugin_h" defines the templates to generate `action.h`, `telemetry.h`, ..., and "templates/plugin_cpp" is responsible for `action.cpp`, `telemetry.cpp`, ...). - -All the MAVSDK repositories contain some kind of `generate_from_proto.sh` file, and a `templates/` directory: - -* MAVSDK-C++: [script](https://github.com/mavlink/MAVSDK/blob/main/tools/generate_from_protos.sh), [templates](https://github.com/mavlink/MAVSDK/tree/main/templates) -* MAVSDK-Python: [script](https://github.com/mavlink/MAVSDK-Python/blob/main/other/tools/run_protoc.sh), [templates](https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py) -* MAVSDK-Swift: [script](https://github.com/mavlink/MAVSDK-Swift/blob/main/Sources/Mavsdk/tools/generate_from_protos.bash), [templates](https://github.com/mavlink/MAVSDK-Swift/tree/main/Sources/Mavsdk/templates) -* MAVSDK-Java: [script](https://github.com/mavlink/MAVSDK-Java/blob/983b361aa42b9088abbf17037d762ac174b44308/sdk/build.gradle#L54-L73), [templates](https://github.com/mavlink/MAVSDK-Java/tree/main/sdk/templates) -* MAVSDK-C#: [script](https://github.com/mavlink/MAVSDK-CSharp/blob/f989aae79a0d62d6b92bac9120a89fc85ba80006/MAVSDK-CSharp/MAVSDK/MAVSDK.csproj#L18-L31), [templates](https://github.com/mavlink/MAVSDK-CSharp/tree/main/MAVSDK-CSharp/MAVSDK/templates) -* MAVSDK-Go: [script](https://github.com/mavlink/MAVSDK-Go/blob/main/tools/generate_from_protos.bash), [templates](https://github.com/mavlink/MAVSDK-Go/tree/main/templates) - -## Adding a New Feature - -When adding a new feature to MAVSDK it is important to think first about the API that is required, and later about the implementation needed to enable the feature. This is not only because MAVSDK strives to have a simple and safe API but also comes from the fact that a new feature needs to be defined in the API first and can then be implemented (using the autogenerated files) in a later step. - -To add a new feature, follow the steps on [how to write plugins](plugins.md#add-api-to-proto). +# Autogeneration + +MAVSDK is available in a number of different languages. +These all share the same "core" MAVLink implementation written in C++. Most of the API-specific code for other languages is *autogenerated* from API definition files (and language-specific templates). + +This approach means that we don't have to maintain a separate MAVLink implementation or API for each language. +New features are implemented once in C++, and can then be automatically be rolled out in Python, Java, etc. + +This page provides an overview of the architecture and explains how to add a feature using the autogeneration. + +## Overview + +The common MAVLink implementation is written in C++ (it is part of MAVSDK-C++). +The `mavsdk_server` exposes the MAVSDK-C++ API over [gRPC](https://grpc.io/) to the language bindings. +The API for all languages is autogenerated from a common definition. + +![MAVSDK structure/architecture](../../../assets/autogen/mavsdk_overview.png) + +The following parts are autogenerated: + +* MAVSDK-C++ API (i.e. header files) +* Most of `mavsdk_server` +* Most of the language bindings + +Those parts are maintained manually: + +* MAVSDK-C++ implementation (i.e. the MAVLink business logic) +* New plugins need to be added to `mavsdk_server` (this may be automated in future) +* The `System` wrapper in language bindings usually needs to be updated whenever a new plugin is added (this may be automated in future) + +The heart of the autogeneration system is the [MAVSDK-Proto](https://github.com/mavlink/mavsdk-proto) repository which is described [below](#mechanisms). + +## Autogeneration Mechanisms {#mechanisms} + +The autogeneration pipeline is shown below: + +![Autogeneration pipeline](../../../assets/autogen/autogen_overview.png) + +The main parts are: + +* [`protoc-gen-mavsdk`](https://github.com/mavlink/MAVSDK-Proto/tree/main/pb_plugins), which is a `protoc` custom plugin generating MAVSDK's code. +* [The API definition](https://github.com/mavlink/MAVSDK-Proto/tree/main/protos), in the form of proto files. +* Template files (per language, see e.g. the [Python templates](https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py) or the [C++ templates](https://github.com/mavlink/MAVSDK/tree/main/templates)). + + +`protoc` takes the custom plugin (`protoc-gen-mavsdk`) and the template files as inputs, and generate source code out of it. +The way it currently works is that it generates one source file out of each `*.proto` file. For instance, `action.proto` becomes `Action.java` in MAVSDK-Java. + +In some languages (typically C++), we need to generate multiple source files out of one proto definition file, and this is the reason why the C++ generation script runs protoc [in](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L72-L74) [multiple](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L76-L77) [passes](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L79-L81), once [for each template](https://github.com/mavlink/MAVSDK/blob/6434e0c6a7c25a3203d4652da13ea1944279beb1/tools/generate_from_protos.sh#L61) (e.g. "templates/plugin_h" defines the templates to generate `action.h`, `telemetry.h`, ..., and "templates/plugin_cpp" is responsible for `action.cpp`, `telemetry.cpp`, ...). + +All the MAVSDK repositories contain some kind of `generate_from_proto.sh` file, and a `templates/` directory: + +* MAVSDK-C++: [script](https://github.com/mavlink/MAVSDK/blob/main/tools/generate_from_protos.sh), [templates](https://github.com/mavlink/MAVSDK/tree/main/templates) +* MAVSDK-Python: [script](https://github.com/mavlink/MAVSDK-Python/blob/main/other/tools/run_protoc.sh), [templates](https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py) +* MAVSDK-Swift: [script](https://github.com/mavlink/MAVSDK-Swift/blob/main/Sources/Mavsdk/tools/generate_from_protos.bash), [templates](https://github.com/mavlink/MAVSDK-Swift/tree/main/Sources/Mavsdk/templates) +* MAVSDK-Java: [script](https://github.com/mavlink/MAVSDK-Java/blob/983b361aa42b9088abbf17037d762ac174b44308/sdk/build.gradle#L54-L73), [templates](https://github.com/mavlink/MAVSDK-Java/tree/main/sdk/templates) +* MAVSDK-C#: [script](https://github.com/mavlink/MAVSDK-CSharp/blob/f989aae79a0d62d6b92bac9120a89fc85ba80006/MAVSDK-CSharp/MAVSDK/MAVSDK.csproj#L18-L31), [templates](https://github.com/mavlink/MAVSDK-CSharp/tree/main/MAVSDK-CSharp/MAVSDK/templates) +* MAVSDK-Go: [script](https://github.com/mavlink/MAVSDK-Go/blob/main/tools/generate_from_protos.bash), [templates](https://github.com/mavlink/MAVSDK-Go/tree/main/templates) + +## Adding a New Feature + +When adding a new feature to MAVSDK it is important to think first about the API that is required, and later about the implementation needed to enable the feature. This is not only because MAVSDK strives to have a simple and safe API but also comes from the fact that a new feature needs to be defined in the API first and can then be implemented (using the autogenerated files) in a later step. + +To add a new feature, follow the steps on [how to write plugins](plugins.md#add-api-to-proto). diff --git a/docs/en/cpp/contributing/documentation.md b/docs/en/cpp/contributing/documentation.md index 52bc5ec2bd..9e5877f51a 100644 --- a/docs/en/cpp/contributing/documentation.md +++ b/docs/en/cpp/contributing/documentation.md @@ -1,18 +1,15 @@ # Contributing to Documentation Making quick fixes to existing text or raising issues is very easy. -More complicated changes will require you to set up the [Gitbook toolchain](https://github.com/GitbookIO/gitbook/blob/master/docs/setup.md). If you want to help, [get in touch](../../index.md#getting-help). -::: tip +::: tip You will need a [Github](https://github.com/) login to make and submit changes to this guide. -::: +::: ## Overview This guide is written in [markdown](https://github.com/GitbookIO/gitbook/blob/master/docs/syntax/markdown.md) wiki syntax and stored in the Github [mavlink/MAVSDK-docs](https://github.com/mavlink/MAVSDK-docs) repo. -The book is hosted on [Gitbook.com](https://www.gitbook.com/) and is automatically rebuilt whenever the master branch of the repo is updated. -You can also rebuild it locally using the [Gitbook toolchain](https://github.com/GitbookIO/gitbook/blob/master/docs/setup.md). The [API Reference](../api_reference/index.md) section is compiled from source code into markdown using a [separate toolchain](#api-reference) and then copied into Github. Updates to the reference should be made in the [source code repository](https://github.com/mavlink/MAVSDK) (see [API Reference](#api-reference) below for more information). @@ -48,6 +45,8 @@ To raise an issue against the documentation: This will open a bug in Github, seeded with the URL/name for the current page. 1. Enter enough information for someone to understand the problem, and ideally to fix it. +TODO: still valid? + ## Making a Big Change @@ -58,7 +57,7 @@ For setup information see: [Gitbook toolchain](https://github.com/GitbookIO/gitb ## API Reference -The C++ source code is annotated using comments using [Doxygen](http://doxygen.nl/manual/index.html) syntax. +The C++ public header files are annotated using docstrings using [Doxygen](http://doxygen.nl/manual/index.html) syntax. You can extract the documentation to markdown files (one per class) on macOS or Linux using the instructions in [Build API Reference Documentation](../guide/build_docs.md). In order to include new API reference in the *SDK Documentation* it must be manually added to the [Github repository](https://github.com/mavlink/MAVSDK-docs): diff --git a/docs/en/cpp/contributing/plugins.md b/docs/en/cpp/contributing/plugins.md index ea09fb0ad8..3b55a9fe96 100644 --- a/docs/en/cpp/contributing/plugins.md +++ b/docs/en/cpp/contributing/plugins.md @@ -18,7 +18,7 @@ A simplified view of the folder structure is shown below: ``` ├── MAVSDK │ └── src -│ ├── integration_tests +│ ├── system_tests │ ├── mavsdk_server │ └── mavsdk │ ├── core @@ -122,12 +122,12 @@ message SetReturnToLaunchAltitudeResponse { } ``` -::: info +::: info Requests can defined SYNC, ASYNC, or BOTH using `option (mavsdk.options.async_type) = ...;`. The choice depends on the functionality that is being implemented and how it would generally be used. There are no hard rules, it's something that makes sense to be discussed one by one in a pull request. The default implementation is `BOTH`. -::: +::: #### Subscriptions: @@ -146,15 +146,15 @@ message PositionResponse { } ``` -::: info +::: info Subscriptions also can defined SYNC, ASYNC, or BOTH using `option (mavsdk.options.async_type) = ...;`. The sync implementation of a subscription is just a getter for the last received value. -::: +::: -::: info +::: info Subscriptions can be defined finite using `option (mavsdk.options.is_finite) = true;`. This means that the stream of messages will end at some point instead of continuing indefinitely. An example would be progress updates about a calibration which eventually finishes. -::: +::: ### Add API to proto @@ -182,7 +182,7 @@ Once the proto file has been created, you can generate all files required for th 1. Run the configure step to prepare the tools required: ``` - cmake -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -H. + cmake -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -S. ``` 1. Install `protoc_gen_mavsdk` which is required for the auto-generation: ``` @@ -197,12 +197,12 @@ Once the proto file has been created, you can generate all files required for th tools/fix_style.sh . ``` -::: info +::: info The files `my_new_plugin.h` and `my_new_plugin.cpp` are generated and overwritten every time the script is run. However, the files `my_new_plugin_impl.h` and `my_new_plugin_impl.cpp` are only generated once. To re-generate them, delete them and run the script again. This approach is used to prevent the script from overwriting your local changes. -::: +::: ### Actually implement MAVLink messages @@ -278,23 +278,19 @@ The tests should be exhaustive, and cover all aspects of using the plugin API. The [Google Test Primer](https://google.github.io/googletest/primer.html) provides an excellent overview of how tests are written and used. +### System Tests -### Writing Unit Tests +Most of the existing plugins do not have unit tests as they mostly just translate between MAVSDK APIs and MAVLink message logic. +That sort of logic can be covered by system_tests which basically tests the MAVLink message logic by implementing both "client" and "server" parts, the server being exposed in the server plugin. -Most of the existing plugins do not have unit tests, -because we do not yet have the ability to [mock MAVLink communications](https://github.com/mavlink/MAVSDK/issues/148) (needed to test most plugins). -Unit tests are therefore considered optional! - -::: tip -Comprehensive integration tests should be written instead, with the simulator providing appropriate MAVLink messages. -::: - -#### Adding Unit Tests {#adding_unit_tests} +### Unit Tests +::: tip +Unit tests are a good way to test more intricate functionality as required in a plugin or in the core. They typically cover only one class. +::: Unit test files are stored in the same directory as their associated source code. -In order to include a test in the SDK unit test program (`unit_tests_runner`), -it must be added to the `UNIT_TEST_SOURCES` variable in the plugin **CMakeLists.txt** file. +In order to include a test in `unit_tests_runner`, it must be added to the `UNIT_TEST_SOURCES` variable in the plugin **CMakeLists.txt** file. For example, to add the **example_foo_test.cpp** unit test you would append the following lines to its **CMakeLists.txt**: @@ -306,66 +302,20 @@ list(APPEND UNIT_TEST_SOURCES set(UNIT_TEST_SOURCES ${UNIT_TEST_SOURCES} PARENT_SCOPE) ``` +Unit tests typically include the header file of the class to be tested and ``. -#### Unit Test Code - -Unit tests typically include the file to be tested, **mavsdk.h**, and **gtest.h**. -There are no standard shared test unit resources so test functions are declared using `TEST`. -All tests in a file should share the same test-case name (the first argument to `TEST`). - - -### Writing Integration Tests {#integration_tests} +### Integration tests {#integration_tests} -MAVSDK provides the `integration_tests_runner` application for running the integration tests and some helper code to make it easier to log tests and run them against the simulator. +We have opted to slowly fade out integration tests and use a few examples instead. -::: tip -Check out the [Google Test Primer](https://google.github.io/googletest/primer.html) and the [integration_tests](https://github.com/mavlink/MAVSDK/tree/main/src/integration_tests) for our existing plugins to better understand how to write your own! -::: +The rationale is as follows: the integration tests were used to test functionality against SITL (sofware in the loop) simulation. However, we learnt that it was slow to start up the simulatoin and then run a test all the way through. It was also cumbersome to keep track of the potential test matrix including both MAVSDK and PX4 as well as ArduPilot versions. In reality it's only really possible to test a few full integrations like this, so only a small part of the functionality/code coverage. +At this point, the integration tests ended up quite similar to the examples. For contributors it was then often confusing whether they should provide an integration test or an example, or both. Given the integration tests weren't useful as we had to remove them from CI, we decided to move away from them and instead focus on readable examples instead. -#### Adding Integration Tests - -In order to run an integration test it needs to be added to the `integration_tests_runner` program. - -Integration tests for core functionality and plugins delivered by the project -are stored in [MAVSDK/src/integration_tests](https://github.com/mavlink/MAVSDK/tree/main/src/integration_tests). -The files are added to the test program in that folder's -[CMakeLists.txt](https://github.com/mavlink/MAVSDK/blob/main/src/integration_tests/CMakeLists.txt) file: - -```cmake -# This includes all GTests that run integration tests -add_executable(integration_tests_runner - ../core/unittests_main.cpp - simple_connect.cpp - async_connect.cpp - telemetry_simple.cpp - ... - gimbal.cpp - transition_multicopter_fixedwing.cpp - follow_me.cpp -) -``` - - -#### Integration Test Files/Code - -The main MAVSDK-specific functionality is provided by [integration_test_helper.h](https://github.com/mavlink/MAVSDK/blob/main/src/integration_tests/integration_test_helper.h). -This provides access to the [Plugin/Test Logger](../guide/dev_logging.md) and a shared test class `SitlTest` for setting up and tearing down the PX4 simulator. - -::: info -All tests running against SITL can be declared using `TEST_F` and have a first argument `SitlTest` as shown. -This is required in order to use the shared class to set up and tear down the simulator between tests. -::: - -For reference inspect the [existing integration tests](https://github.com/mavlink/MAVSDK/blob/main/src/integration_tests). +### Examples {#examples} ## Example Code -::: info -It is quicker and easier to write and modify [integration tests](#integration_tests) than examples. -Do not write example code until the plugin has been accepted! -::: - A simple example should be written that demonstrates basic usage of its API by 3rd parties. The example need not cover all functionality, but should demonstrate enough that developers can see how it is used and how the example might be extended. @@ -378,10 +328,10 @@ Where possible examples should demonstrate realistic use cases such that the cod The public API must be fully documented using the proto files. -::: tip +::: tip The in-source comments will be compiled to markdown and included in the [API Reference](../api_reference/index.md). The process is outlined in [Documentation > API Reference](documentation.md#api-reference). -::: +::: Internal/implementation classes need not be documented, but should be written using expressive naming of variables and functions to help the reader. Anything unexpected or special however warrants an explanation as a comment. diff --git a/docs/en/cpp/contributing/release.md b/docs/en/cpp/contributing/release.md index 4e5f4b1d9f..787b2dda7f 100644 --- a/docs/en/cpp/contributing/release.md +++ b/docs/en/cpp/contributing/release.md @@ -3,7 +3,7 @@ These are the instructions on how to get a release out the door. ::: info -The idea is of course to automate this as much as possible! +The idea is of course to automate this as much as possible. ::: ## MAVSDK part @@ -17,10 +17,8 @@ The idea is of course to automate this as much as possible! git tag vX.Y.Z git push origin vX.Y.Z ``` -1. - Generate changelog using `tools/generate_changelog.py --token TOKEN_FROM_GITHUB --verbose --tag vX.Y.Z`. - - If it finds old/wrong PRs, wait a bit or create the release from the tag in the [GitHub UI](https://github.com/mavlink/MAVSDK/releases). - - Once it finds the correct PRs it will check all of them for labels. Make sure all merged PRs have sensible labels (e.g. `enhancement`, `bug`, or `feature`). - - Copy the changelog text to the [release](https://github.com/mavlink/MAVSDK/releases). +1. - Update the version branch (e.g. `v3`) as well to track main. + - Create the release on GitHub for the pushed tag. Generate the changelog using the GitHub button. 1. Check later if all artifacts have been uploaded correctly to the release. 1. Update the Arch AUR repository. This depends on the AUR maintainter's credentials (currently julianoes). - Use the repo: `ssh://aur@aur.archlinux.org/mavsdk.git`. @@ -54,4 +52,4 @@ The idea is of course to automate this as much as possible! ## Other -1. Post a note on Slack #mavsdk. +1. Post a note on Discord #mavsdk. diff --git a/docs/en/cpp/examples/fly_mission.md b/docs/en/cpp/examples/fly_mission.md index 3a352494aa..a480953c3a 100644 --- a/docs/en/cpp/examples/fly_mission.md +++ b/docs/en/cpp/examples/fly_mission.md @@ -11,10 +11,10 @@ The example is built and run in the normal way ([as described here](../examples/ The example terminal output should be similar to that shown below: -::: info +::: info This is from a debug build of the SDK. A release build will omit the "Debug" messages. -::: +::: ``` $ ./fly_mission udp://:14540 diff --git a/docs/en/cpp/examples/follow_me.md b/docs/en/cpp/examples/follow_me.md index afed0ec00d..1cc55f46a1 100644 --- a/docs/en/cpp/examples/follow_me.md +++ b/docs/en/cpp/examples/follow_me.md @@ -5,11 +5,11 @@ It shows how to send the drone both the current position of the target (`FollowM ![Follow Me QGC Screenshot](../../../assets/examples/follow_me/follow_me_example_qgc.jpg) -::: info +::: info A real application using this API will get the position information from the underlying operating system. The example uses a fake position source (`FakeLocationProvider`) to enable it to be run on computers that do not have position information. The `FakeLocationProvider` emulates the typical usage of common positioning APIs used in Android, Linux and iPhone. -::: +::: ## Running the Example {#run_example} @@ -27,10 +27,10 @@ Otherwise the example is built and run in the normal way ([as described here](.. The example terminal output should be similar to that shown below: -::: info +::: info This is from a debug build of the SDK. A release build will omit the "Debug" messages. -::: +::: ``` $ ./follow_me udp://:14540 diff --git a/docs/en/cpp/examples/index.md b/docs/en/cpp/examples/index.md index f604c9201c..da1787a8e1 100644 --- a/docs/en/cpp/examples/index.md +++ b/docs/en/cpp/examples/index.md @@ -1,8 +1,8 @@ # C++ Examples -::: tip +::: tip Information about *writing* example code is covered in the [Contributing > Writing Plugins](../contributing/plugins.md) (*plugin developers* should initially create [integration tests](../contributing/plugins.md#integration_tests) rather than examples for new code). -::: +::: This section contains examples showing how to use MAVSDK. @@ -25,20 +25,20 @@ Example | Description The examples are "largely" built and run in the same way, as described in the following section (any exceptions are covered in the page for the associated example). -::: warning +::: warning Some of the examples define flight behaviour relative to the default home position in the simulator (e.g. [Fly Mission](../examples/fly_mission.md)). Care should be taken if using them on a real vehicle. -::: +::: ## Trying the Examples {#trying_the_examples} The easiest way to test the examples is to use a [simulated PX4 vehicle](https://docs.px4.io/master/en/simulation/) that is running on the same computer. First start PX4 in SITL (Simulation), optionally start *QGroundControl* to observe the vehicle, then build and run the example code. -::: info +::: info The simulator broadcasts to the standard PX4 UDP port for connecting to offboard APIs (14540). The examples connect to this port using either [add_any_connection()](../api_reference/classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a405041a5043c610c86540de090626d97) or [add_udp_connection()](../api_reference/classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1aa43dfb00d5118d26ae5aabd0f9ba56b2). -::: +::: ### Setting up a Simulator @@ -46,10 +46,10 @@ The examples connect to this port using either [add_any_connection()](../api_ref PX4 supports a [number of simulators](https://docs.px4.io/master/en/simulation/). In order to set up the [jMAVSim](https://docs.px4.io/master/en/simulation/jmavsim.html) or [Gazebo](https://docs.px4.io/master/en/simulation/gazebo.html) simulator, you can simply follow the standard PX4 toolchain setup instructions for [macOS](https://docs.px4.io/master/en/dev_setup/dev_env_mac.html) or [Ubuntu Linux](https://docs.px4.io/master/en/dev_setup/dev_env_linux_ubuntu.html). -::: info +::: info JMAVSim can only be used to simulate multicopters. Gazebo additionally supports a number of [other vehicles](https://docs.px4.io/master/en/simulation/gazebo.html#html#running-the-simulation) (e.g. VTOL, Rovers, fixed-wing etc.). -::: +::: After running a standard installation, a simulation can be started from the PX4 **/Firmware** directory using the command: * Multicopter (jMAVSim): `make px4_sitl jmavsim` @@ -75,17 +75,17 @@ See [installation guide](../guide/installation.md) if that is not already the ca Then build the example: ```sh cd examples/takeoff_and_land/ -cmake -Bbuild -H. +cmake -Bbuild -S. cmake --build build -j4 ``` -::: info +::: info if MAVSDK is installed locally (e.g. on Windows) you need to pass the location to cmake: ``` cmake -Bbuild -DCMAKE_PREFIX_PATH=wherever_mavsdk_is_locally_installed ``` -::: +::: ### Running the Examples {#running_the_examples} @@ -102,10 +102,10 @@ For Windows you would run the following (from the **\build\Debug\** directory): build\Debug\takeoff_and_land.exe udp://:14540 ``` -::: tip +::: tip Most examples will create a binary with the same name as the example. The name that is used is specified in the **CMakeLists.txt** file as the first value in the call to `add_executable()`. -::: +::: If you have already started the simulation the example code should connect to PX4, and you will be able to observe behaviour through the SDK terminal, SITL terminal, and/or *QGroundControl*. diff --git a/docs/en/cpp/examples/takeoff_and_land.md b/docs/en/cpp/examples/takeoff_and_land.md index 8a81c45c51..185994bf24 100644 --- a/docs/en/cpp/examples/takeoff_and_land.md +++ b/docs/en/cpp/examples/takeoff_and_land.md @@ -6,9 +6,9 @@ It sets up a UDP connection, waits for a vehicle (system) to appear, arms it, an After a short wait the vehicle lands. While flying the vehicle receives telemetry. The example is implemented in C++ (only). -::: tip +::: tip The full source code for the example [can be found here](https://github.com/mavlink/MAVSDK/tree/main/examples/takeoff_land). -::: +::: ## Running the Example {#run_example} @@ -16,10 +16,10 @@ The example is built and run [as described here](../examples/index.md#trying_the The example terminal output should be similar to that shown below: -::: info +::: info This is from a debug build of the SDK. A release build will omit the "Debug" messages. -::: +::: ```sh $ ./takeoff_and_land udp://:14540 @@ -61,9 +61,9 @@ Finished... ## Source code {#source_code} -::: tip +::: tip The full source code for the example [can be found on Github here](https://github.com/mavlink/MAVSDK/tree/main/examples/takeoff_and_land). -::: +::: - [CMakeLists.txt](https://github.com/mavlink/MAVSDK/blob/main/examples/takeoff_and_land/CMakeLists.txt) - [takeoff_and_land.cpp](https://github.com/mavlink/MAVSDK/blob/main/examples/takeoff_and_land/takeoff_and_land.cpp) diff --git a/docs/en/cpp/examples/transition_vtol_fixed_wing.md b/docs/en/cpp/examples/transition_vtol_fixed_wing.md index 1bfb9c0904..51535b79be 100644 --- a/docs/en/cpp/examples/transition_vtol_fixed_wing.md +++ b/docs/en/cpp/examples/transition_vtol_fixed_wing.md @@ -10,10 +10,10 @@ This example shows how you can use the SDK [Action](../api_reference/classmavsdk The example must be run against a VTOL aircraft (simulated or otherwise). Otherwise the example is built and run [in the standard way](../examples/index.md#trying_the_examples). -::: tip +::: tip Instructions for running the Gazebo simulator for a standard VTOL can be found here: [PX4 Development Guide > Gazebo Simulation](https://docs.px4.io/master/en/simulation/gazebo.html#standard-vtol). jMAVSim does not support VTOL simulation. -::: +::: The example terminal output for a debug build of the SDK should be similar to that shown below (a release build will omit the "Debug" messages): diff --git a/docs/en/cpp/guide/build.md b/docs/en/cpp/guide/build.md index 9c0e7a3ed5..5a09134c19 100644 --- a/docs/en/cpp/guide/build.md +++ b/docs/en/cpp/guide/build.md @@ -77,7 +77,7 @@ For configuration, you specify the type of build you want to execute in the [bui A typical configuration command example would be: -`cmake -DCMAKE_BUILD_TYPE=Debug -Bbuild/default -H.` +`cmake -DCMAKE_BUILD_TYPE=Debug -Bbuild/default -S.` - Build type is set to `Debug` - Build directory is set to `build/default` @@ -118,7 +118,7 @@ To build the MAVSDK C++ Library for development, use the debug build. There are 2 steps in building a library: Configure and build. ```bash -cmake -DCMAKE_BUILD_TYPE=Debug -Bbuild/default -H. +cmake -DCMAKE_BUILD_TYPE=Debug -Bbuild/default -S. cmake --build build/default -j8 ``` @@ -129,14 +129,14 @@ Once you ship software, make sure to use the release build with optimizations tu **Linux/macOS:** ```bash - cmake -Bbuild/default -DCMAKE_BUILD_TYPE=Release -H. + cmake -Bbuild/default -DCMAKE_BUILD_TYPE=Release -S. cmake --build build/default -j8 ``` **Windows:** ```bash -cmake -Bbuild/default -H. -DCMAKE_BUILD_TYPE=Release +cmake -Bbuild/default -S. -DCMAKE_BUILD_TYPE=Release cmake --build build/default -j8 --config Release ``` @@ -175,7 +175,7 @@ The install path can be set in the [configuration step](#configuration_step) usi For example, to install into the `MAVSDK/install/` folder you would set the `CMAKE_INSTALL_PREFIX` variable to specify a path relative to the folder from which you call `cmake` (or an absolute path). ```bash -cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=install -Bbuild/default -H. +cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=install -Bbuild/default -S. cmake --build build/default --target install ``` diff --git a/docs/en/cpp/guide/build_docs.md b/docs/en/cpp/guide/build_docs.md index 2c64e4411d..20379f6567 100644 --- a/docs/en/cpp/guide/build_docs.md +++ b/docs/en/cpp/guide/build_docs.md @@ -13,11 +13,11 @@ rm -rf tools/docs # Remove previous docs ``` The files are created in `/install/docs/markdown`. -::: info +::: info Extracting the API reference does not yet work automatically on Windows. -::: +::: -::: info +::: info The *generate_docs.sh* script [builds the library](build.md), installs it locally to **/install**, and then uses *DOxygen* to create XML documentation in **/install/docs/xml**. The [generate_markdown_from_doxygen_xml.py](https://github.com/mavlink/MAVSDK/blob/main/tools/generate_markdown_from_doxygen_xml.py) script is then run on all files in the */xml* directory to generate markdown files in **/install/docs/markdown**. -::: +::: diff --git a/docs/en/cpp/guide/build_mavsdk_server.md b/docs/en/cpp/guide/build_mavsdk_server.md index 42c4c34a3e..e29dedb1fa 100644 --- a/docs/en/cpp/guide/build_mavsdk_server.md +++ b/docs/en/cpp/guide/build_mavsdk_server.md @@ -15,28 +15,23 @@ The requirements are the same as described in the [library build instructions](b ## Build on Linux ``` -cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_SHARED_LIBS=OFF -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -H. +cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_SHARED_LIBS=OFF -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -S. cmake --build build/default -j8 ``` ## Build on macOS ``` -cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_SHARED_LIBS=OFF -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -H. +cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_SHARED_LIBS=OFF -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -S. cmake --build build/default -j8 ``` -::: info -There is no proper support for the Apple M1 chip yet. -One blocker is that there is currently no M1 hardware in GitHub Actions CI available. -::: - ## Build on Windows -Open the "x64 Native Tools Command Prompt for VS 2022", cd into the MAVSDK directory, and do: +Open the "x64 Native Tools Command Prompt for VS 2022" (or later), cd into the MAVSDK directory, and do: ``` -cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -H. +cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -Bbuild/default -S. cmake --build build/default -j8 ``` @@ -49,19 +44,19 @@ Build for Android using the dockcross cross compiler, as described in the [cross To build for real iOS devices on macOS: ```sh -cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DCMAKE_TOOLCHAIN_FILE=tools/ios.toolchain.cmake -DPLATFORM=OS -Bbuild/ios -H. +cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DCMAKE_TOOLCHAIN_FILE=tools/ios.toolchain.cmake -DPLATFORM=OS -Bbuild/ios -S. cmake --build build/ios ``` Build for the iOS simulator on macOS: ```sh -cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DCMAKE_TOOLCHAIN_FILE=tools/ios.toolchain.cmake -DPLATFORM=SIMULATOR64 -Bbuild/ios_simulator -H. +cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_MAVSDK_SERVER=ON -DBUILD_SHARED_LIBS=OFF -DCMAKE_TOOLCHAIN_FILE=tools/ios.toolchain.cmake -DPLATFORM=SIMULATOR64 -Bbuild/ios_simulator -S. ``` ## Cross compilation using dockcross {#cross_compilation_dockcross} -Cross compilation is usually the fastest way to compile for "embedded" platforms like the Raspberry Pi, BeagleBone Blue or Nvidia Jetson (i.e. typically faster than native compilation on device itself). +Cross compilation is usually the fastest way to compile for "embedded" platforms like the Raspberry Pi, or Nvidia Jetson (i.e. typically faster than native compilation on device itself). We recommend using [dockcross](https://github.com/dockcross/dockcross), which is a very convenient tool for cross compilation based on docker (and which supports many platforms). diff --git a/docs/en/cpp/guide/code_style.md b/docs/en/cpp/guide/code_style.md index 8990acb0e6..950c84a406 100644 --- a/docs/en/cpp/guide/code_style.md +++ b/docs/en/cpp/guide/code_style.md @@ -2,10 +2,10 @@ This topic contains the C++ formatting and coding guidelines for MAVSDK. -::: info +::: info These guidelines are not written in stone! [Start a discussion](../../index.md#getting-help) if you have suggestions for improvement \(the project will consider anything other than "matters of personal taste"\). -::: +::: ## Formatting and White Space diff --git a/docs/en/cpp/guide/connections.md b/docs/en/cpp/guide/connections.md index b6466b3fe3..a7c781e6ba 100644 --- a/docs/en/cpp/guide/connections.md +++ b/docs/en/cpp/guide/connections.md @@ -13,8 +13,10 @@ The connection details are specified using the string formats shown below: Connection | URL Format --- | --- -UDP | `udp://[host][:port]` -TCP | `tcp://[host][:port]` +UDP in | `udpin://[ip][:port]` +UDP out | `udpout://[ip][:port]` +TCP in | `tcpin://[ip][:port]` +TCP out | `tcpout://[ip][:port]` Serial | `serial://[path][:baudrate]` ### Connecting over serial @@ -49,27 +51,35 @@ When connecting over UDP, there are two setups to distinguish: server and client #### Behave like a server -This is the default connection mode for a ground station listening to a system/vehicle (this is the same as [add_udp_connection()](../api_reference/classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1aa43dfb00d5118d26ae5aabd0f9ba56b2)). +In the server mode, we bind to a local networking interface. We can use `0.0.0.0` (INADDR_ANY) to accept UDP datagrams from any network interface, or our IP on a specific network interface to only accept traffic from that interface. -In the server mode, we listen on an local networking interface (`INADDR_ANY`/`0.0.0.0`) on the set port and wait for any heartbeats arriving. -This means that the drone has to send the UDP packets to that local IP, or broadcast them on the network. -The code snippet below shows how to set up a connection in server mode and listen on the "SDK port 14540": +This means that the drone has to send the UDP packets to that IP, or broadcast them on the network. + +The code snippet below shows how to set up a connection in server mode and listen on the "SDK port 14540", on any network network adapter, e.g. WiFi, LAN, or localhost/loopback: ```cpp -Mavsdk mavsdk; -ConnectionResult connection_result = mavsdk.add_any_connection("udp://:14540"); +auto connection_result = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); +if (connection_result != ConnectionResult::Success) { + std::cout << "Adding connection failed: " << connection_result << '\n'; + return; +} +``` + +However, if our IP on WiFi is `192.168.1.42` and you want to only listen to any messages coming over WiFi, we can use this IP + +```cpp +auto connection_result = mavsdk.add_any_connection("udpin://192.168.1.42:14540"); if (connection_result != ConnectionResult::Success) { std::cout << "Adding connection failed: " << connection_result << '\n'; return; } ``` -::: info -The connection string used above (`udp://:14540`) is to the [standard PX4 UDP port](https://docs.px4.io/master/en/simulation/#default-px4-mavlink-udp-ports) for off-board APIs (14540). -This is the normal/most common way for offboard APIs to connect to PX4 over WiFi. -The standard way to talk to a ground station (e.g. QGC is on port 14550). -::: +::: info +The connection string used above (`udpin://0.0.0.0:14540`) is the [standard PX4 UDP port](https://docs.px4.io/master/en/simulation/#default-px4-mavlink-udp-ports) for off-board APIs (14540) used with SITL. + The standard way to talk to a ground station (e.g. QGC is on port 14550). +::: #### Behave like a client @@ -79,8 +89,7 @@ In this case the IP and port, of where it should connect to, has to be set (this E.g. to connect to a ground station on 192.168.1.12, you would do: ```cpp -Mavsdk mavsdk; -ConnectionResult connection_result = mavsdk.add_any_connection("udp://192.168.1.12:14550"); +auto connection_result = mavsdk.add_any_connection("udpout://192.168.1.12:14550"); if (connection_result != ConnectionResult::Success) { std::cout << "Adding connection failed: " << connection_result << '\n'; return; @@ -91,8 +100,7 @@ E.g. to listen locally to a mavlink-router endpoint at 14551, you would do: ```cpp -Mavsdk mavsdk; -ConnectionResult connection_result = mavsdk.add_any_connection("udp://:14551"); +auto connection_result = mavsdk.add_any_connection("udpout://127.0.0.1:14551"); if (connection_result != ConnectionResult::Success) { std::cout << "Adding connection failed: " << connection_result << '\n'; return; @@ -101,12 +109,26 @@ if (connection_result != ConnectionResult::Success) { ### Connecting over TCP -For TCP connections, only the client connection is currently implemented. -This is the same as [add_tcp_connection()](../api_reference/classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a91c7a70c6e8ffa43844f2ce04f2696f0). +For TCP connections, the client as well as server connections are implemented. + +#### Behave like a server + +In this mode we listen on one of our a network interfaces (or all of them) and port: ```cpp -Mavsdk mavsdk; -ConnectionResult connection_result = mavsdk.add_any_connection("tcp://192.168.1.12:14550"); +auto connection_result = mavsdk.add_any_connection("tcpin://0.0.0.0:14550"); +if (connection_result != ConnectionResult::Success) { + std::cout << "Adding connection failed: " << connection_result << '\n'; + return; +} +``` + +#### Behave like a client + +In this mode we connect to an IP and port: + +```cpp +auto connection_result = mavsdk.add_any_connection("tcpout://192.168.1.12:14550"); if (connection_result != ConnectionResult::Success) { std::cout << "Adding connection failed: " << connection_result << '\n'; return; @@ -123,7 +145,7 @@ The code fragment below shows how to register a callback (in this case the callb ```cpp Mavsdk mavsdk; ... //add ports -mavsdk.register_on_new_system([]() { +mavsdk.subscribe_on_new_system([]() { std::cout << "Discovered new system\n"; }); ``` @@ -150,8 +172,6 @@ To access a certain system, pick the one from the vector that you require, or us ```cpp -Mavsdk mavsdk; -mavsdk.add_udp_connection(); // Wait for the system to connect via heartbeat while (mavsdk.systems().size() == 0) { std::this_thread::sleep_for(std::chrono::seconds(1)); @@ -171,7 +191,7 @@ To forward bi-directional from UDP to serial and serial to UDP, you would set bo ```cpp Mavsdk mavsdk; -mavsdk.add_any_connection("udp://:14540", ForwardingOption::ForwardingOn); +mavsdk.add_any_connection("udpin://0.0.0.0:14540", ForwardingOption::ForwardingOn); mavsdk.add_any_connection("serial:///dev/serial/by-id/usb-FTDI_FT232R_USB_UART_XXXXXXXX-if00-port0:57600", ForwardingOption::ForwardingOn); ``` @@ -179,7 +199,7 @@ To forward only in one direction, e.g to send messages arriving on serial over U ```cpp Mavsdk mavsdk; -mavsdk.add_any_connection("udp://:14540", ForwardingOption::ForwardingOn); +mavsdk.add_any_connection("udpin://0.0.0.0:14540", ForwardingOption::ForwardingOn); mavsdk.add_any_connection("serial:///dev/serial/by-id/usb-FTDI_FT232R_USB_UART_XXXXXXXX-if00-port0:57600", `ForwardingOption::ForwardingOff`); ``` diff --git a/docs/en/cpp/guide/dev_logging.md b/docs/en/cpp/guide/dev_logging.md index 29cc1b16b5..0fe8f714f7 100644 --- a/docs/en/cpp/guide/dev_logging.md +++ b/docs/en/cpp/guide/dev_logging.md @@ -8,10 +8,10 @@ Basic [message logging](#message_logging) can be enabled by building with a spec The API methods display a custom message, prepending a timestamp and the type of log message (e.g. debug) and appending the origin of the message (file and line number). -::: tip +::: tip The API should be considered "internal". It is not exported, or intended, for use in SDK apps (and we do not commit to maintaining compatibility in future versions). -::: +::: ### Usage diff --git a/docs/en/cpp/guide/follow_me.md b/docs/en/cpp/guide/follow_me.md index ffb4d5ec9f..01e57bb89d 100644 --- a/docs/en/cpp/guide/follow_me.md +++ b/docs/en/cpp/guide/follow_me.md @@ -9,18 +9,18 @@ Applications must get target position information from the underlying platform ( - Apple: [Core Location Framework](https://developer.apple.com/documentation/corelocation) - Windows: [Windows.Devices.Geolocation](https://docs.microsoft.com/en-us/uwp/api/Windows.Devices.Geolocation) -::: warning +::: warning Running *QGroundControl* at the same time as the SDK *Follow Me* may result in unpredictable behaviour as both send position updates. You **must** ensure that *GSC Position Streaming* is disabled. Use the latest *QGC Daily Build* and ensure that the **[Application Setting > General](https://docs.qgroundcontrol.com/en/SettingsView/General.html) > Miscellaneous > Stream GCS Position** is set to *Never*. -::: +::: ## Create the Plugin -::: tip +::: tip `FollowMe` objects are created in the same way as other SDK plugins. General instructions are provided in the topic: [Using Plugins](../guide/using_plugins.md). -::: +::: The main steps are: @@ -80,9 +80,9 @@ Use [set_target_location()](../api_reference/classmavsdk_1_1_follow_me.md#classm This can be called at any time, but messages will only be sent once following is started. The plugin automatically resends the last set position at the rate required by the autopilot/flight mode (1 Hz). -::: info +::: info Typically you would call `set_target_location()` before or shortly after starting the mode. If you call `start()` without having set any target location, or if the connection is broken, the vehicle will climb to minimum altitude (if needed) and remain in the mode waiting for messages. -::: +::: ```cpp // Start following diff --git a/docs/en/cpp/guide/general_usage.md b/docs/en/cpp/guide/general_usage.md index 6809ac720c..a71fd8d350 100644 --- a/docs/en/cpp/guide/general_usage.md +++ b/docs/en/cpp/guide/general_usage.md @@ -1,4 +1,4 @@ -# SDK Paradigms/Usage +# MAVSDK Paradigms/Usage This topic provides general/overview information about how the MAVSDK is used, designed and some limitations. @@ -21,10 +21,10 @@ All objects are automatically cleaned up when the parent `Mavsdk` object is dest MAVSDK APIs do not raise exceptions! Instead, methods that can fail return success or an error reason as `enum` values. -::: tip +::: tip The error code usually reflects acknowledgment from the vehicle that it will perform the requested action (or not). The operation itself may not yet have completed (e.g. taking off). -::: +::: The various classes also all provide stream operators for getting human readable strings from their associated result enum. You can see how these are used in the example code. @@ -111,7 +111,7 @@ The implication is that developers will need to separately monitor the completio The `Mission` and `MissionItem` APIs provide a the most useful *subset* of MAVLink mission commands as a developer-friendly API. -Not every mission command behaviour supported by the protocol and PX4 will be supported by the SDK. +Not every mission command behaviour supported by the protocol and PX4 will be supported by MAVSDK. For example, at time of writing the API does not allow you to specify commands that jump back to previous mission items. The API allows you to download/import missions. diff --git a/docs/en/cpp/guide/installation.md b/docs/en/cpp/guide/installation.md index e03a0f8b06..f64f33af60 100644 --- a/docs/en/cpp/guide/installation.md +++ b/docs/en/cpp/guide/installation.md @@ -4,35 +4,32 @@ MAVSDK C++ is a library that can be installed and then used in your C++ code. The latest release can be installed using prebuilt artefacts. If you need the latest state or want to debug the library itself, you need to [build it from source](build.md). -## Linux +### Linux -- **Ubuntu:** Download the **.deb** file for your system from [MAVSDK releases](https://github.com/mavlink/MAVSDK/releases) and install it using `dpkg`: - ``` - sudo dpkg -i mavsdk_0.37.0_ubuntu20.04_amd64.deb - ``` +**Ubuntu** -- **Fedora:** Download the **.rpm** file for your system from [MAVSDK releases](https://github.com/mavlink/MAVSDK/releases) and install it using `rpm`: - ``` - sudo rpm -U mavsdk-0.37.0-1.fc33-x86_64.rpm - ``` +If you have an older version already installed remove that first: +``` +sudo apt remove mavsdk +``` + +The prebuilt C++ library can be downloaded as a **.deb** from [releases](https://github.com/mavlink/MAVSDK/releases), e.g.: -- **Arch Linux:** mavsdk is available from the [AUR](https://aur.archlinux.org/) and can be installed e.g. using [yay](https://aur.archlinux.org/packages/yay/): - ``` - yay -S mavsdk - ``` +``` +wget https://github.com/mavlink/MAVSDK/releases/download/v3.0.0/libmavsdk-dev_3.0.0_ubuntu24.04_amd64.deb +sudo dpkg -i libmavsdk-dev_3.0.0_ubuntu24.04_amd64.deb +``` -## macOS +### macOS -**MacOS:** Install [Homebrew](https://brew.sh/) and use it to install the library: +Install [Homebrew](https://brew.sh/) and use it to install the library: ``` brew install mavsdk ``` -## Windows +### Windows + +For Windows you can download the **mavsdk-windows-x64-release.zip** file from [MAVSDK releases](https://github.com/mavlink/MAVSDK/releases) containing the headers and library and extract it locally (see [information how to use a locally installed library](guide/toolchain.md#sdk_local_install)). -For Windows you can download the **mavsdk-windows-x64-release.zip** file from [MAVSDK releases](https://github.com/mavlink/MAVSDK/releases) containing the headers and library and extract it locally (see [information how to use a locally installed library](toolchain.md#sdk_local_install)). +For more detailed instructions or other platforms check out the [installation notes](guide/installation.md). -::: info -As the library is installed locally (in a local directory) you need to point cmake to that directory at configure time using `CMAKE_PREFIX_PATH` when building your application. -i.e.: `cmake -Bbuild -DCMAKE_PREFIX_PATH=../mavsdk_extracted` -H. -::: diff --git a/docs/en/cpp/guide/logging.md b/docs/en/cpp/guide/logging.md index 7e76706e8e..8f0c9363bb 100644 --- a/docs/en/cpp/guide/logging.md +++ b/docs/en/cpp/guide/logging.md @@ -1,46 +1,46 @@ -# Logging -MAVSDK core and plugins output some useful log messages during their work. -By default, the messages are printed to `stdout`. You may want to override this -behavior, e.g. redirect messages to an external logging system, or disable -printing messages unless they are important enough. - -## Usage -It is possible to customize logging with a user-defined callback function: -```c++ -#include - -// ... - -mavsdk::log::subscribe([](mavsdk::log::Level level, // message severity level - const std::string& message, // message text - const std::string& file, // source file from which the message was sent - int line) { // line number in the source file - // process the log message in a way you like - my_nice_log(level, message); - - // returning true from the callback disables printing the message to stdout - return level < mavsdk::log::Level::Warn; -}); -``` - -In this example all log messages will be passed to `my_nice_log`, and all messages -having level `Warn` or `Err` will be printed to stdout as well. -Possible levels are: -```c++ -enum class Level : int { Debug = 0, Info = 1, Warn = 2, Err = 3 }; -``` -Currently, only one callback is supported. Calling `mavsdk::log::subscribe` -the second time will overwrite previous callback. To unsubscribe (revert to default -logging behaviour) call subscribe with a `nullptr` callback: -```c++ -mavsdk::log::subscribe(nullptr); -``` - -## Important notes -Please note that callback can be called from different threads. Synchronization -is not handled on MAVSDK's side for performance reasons. You may want to -implement synchronization yourself if your logging system isn't thread -safe already. - -Avoid doing long duration heavy tasks in the callback, it should return as -quickly as possible. +# Logging +MAVSDK core and plugins output some useful log messages during their work. +By default, the messages are printed to `stdout`. You may want to override this +behavior, e.g. redirect messages to an external logging system, or disable +printing messages unless they are important enough. + +## Usage +It is possible to customize logging with a user-defined callback function: +```c++ +#include + +// ... + +mavsdk::log::subscribe([](mavsdk::log::Level level, // message severity level + const std::string& message, // message text + const std::string& file, // source file from which the message was sent + int line) { // line number in the source file + // process the log message in a way you like + my_nice_log(level, message); + + // returning true from the callback disables printing the message to stdout + return level < mavsdk::log::Level::Warn; +}); +``` + +In this example all log messages will be passed to `my_nice_log`, and all messages +having level `Warn` or `Err` will be printed to stdout as well. +Possible levels are: +```c++ +enum class Level : int { Debug = 0, Info = 1, Warn = 2, Err = 3 }; +``` +Currently, only one callback is supported. Calling `mavsdk::log::subscribe` +the second time will overwrite previous callback. To unsubscribe (revert to default +logging behaviour) call subscribe with a `nullptr` callback: +```c++ +mavsdk::log::subscribe(nullptr); +``` + +## Important notes +Please note that callback can be called from different threads. Synchronization +is not handled on MAVSDK's side for performance reasons. You may want to +implement synchronization yourself if your logging system isn't thread +safe already. + +Avoid doing long duration heavy tasks in the callback, it should return as +quickly as possible. diff --git a/docs/en/cpp/guide/missions.md b/docs/en/cpp/guide/missions.md index ee174a0377..111e203f25 100644 --- a/docs/en/cpp/guide/missions.md +++ b/docs/en/cpp/guide/missions.md @@ -6,10 +6,10 @@ Missions can have multiple "mission items", each which may specify a position, a Missions are *managed* though the [Mission](../api_reference/classmavsdk_1_1_mission.md) class, which communicates with the vehicle to upload mission information and run, pause, track the mission progress etc. The mission that is uploaded to the vehicle is defined as a vector of [MissionItem](../api_reference/structmavsdk_1_1_mission_1_1_mission_item.md) objects. -::: tip +::: tip The [Mission plugin](../api_reference/classmavsdk_1_1_mission.md) described here only supports a small subset of the full functionality of MAVLink missions. If you require the full mission item spec as MAVLink provides it, you might be better off using the [MissionRaw plugin](../api_reference/classmavsdk_1_1_mission_raw.md). Furthermore `MissionRaw` allows importing mission from QGroundControl. -::: +::: ## Supported Mission Commands {#supported_mission_commands} @@ -29,18 +29,18 @@ Additionally, the following commands are supported only for mission import/downl * [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND) * [MAV_CMD_NAV_TAKEOFF](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_TAKEOFF) -::: tip +::: tip The Mission API does not (at time of writing) provide explicit functionality to "repeat", takeoff, return to land etc. The SDK provides some omitted functionality through the [Action](../guide/taking_off_landing.md) API. -::: +::: ## Create the Plugin -::: tip +::: tip `Mission` objects are created in the same way as other MAVSDK plugins. General instructions are provided in the topic: [Using Plugins](../guide/using_plugins.md). -::: +::: The main steps are: @@ -105,15 +105,15 @@ new_item2->camera_photo_interval_s = 1.0f; mission_items.push_back(new_item2); ``` -::: info +::: info The autopilot has sensible default values for the attributes. If you do set a value (e.g. the desired speed) then it will be the default for the remainder of the mission. -::: +::: -::: info +::: info There are also getter methods for querying the current value of `MissionItem` attributes. The default values of most fields are `NaN` (which means they are ignored/not sent). -::: +::: The mission (`mission_items`) can then be uploaded as shown in the section [Uploading a Mission](#uploading_mission) below. @@ -216,9 +216,9 @@ mission.subscribe_mission_progress( [](Mission::MissionProgress mission_progress }); ``` -::: info +::: info The mission is complete when `current == total`. -::: +::: The following synchronous methods is also available for checking mission progress: * [is_mission_finished()](../api_reference/classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1a1ecf4f8798ab9ae96882dfbd34f23466) - Checks if mission has been finished. @@ -240,11 +240,11 @@ If required you can instead use the appropriate commands in the [Action](../guid Use [Mission::download_mission()](../api_reference/classmavsdk_1_1_mission.md#classmavsdk_1_1_mission_1a23e9f7da32f42bcce7ef16ea8044fe53) to download a mission from the vehicle. The mission is downloaded as a vector of [MissionItem](../api_reference/structmavsdk_1_1_mission_1_1_mission_item.md) objects, that you can then view or manipulate as required. -::: info +::: info Mission download will fail if the mission contains a command that is outside the [supported set](#supported_mission_commands). Missions created using *QGroundControl* are not guaranteed to successfully download! Again, for that case [MissionRaw](../api_reference/classmavsdk_1_1_mission_raw.md) might be a better fit. -::: +::: The code fragment below shows how to download a mission: diff --git a/docs/en/cpp/guide/offboard.md b/docs/en/cpp/guide/offboard.md index 592675e09e..c4454d1055 100644 --- a/docs/en/cpp/guide/offboard.md +++ b/docs/en/cpp/guide/offboard.md @@ -3,10 +3,10 @@ The [Offboard](../api_reference/classmavsdk_1_1_offboard.md) MAVSDK plugin provides a simple API for controlling the vehicle using velocity and yaw setpoints. It is useful for tasks requiring direct control from a companion computer; for example to implement collision avoidance. -::: info +::: info The API uses the PX4 [Offboard flight mode](https://docs.px4.io/master/en/flight_modes/offboard.html). The class can only be used with copter and VTOL vehicles (not fixed wing - a PX4 limitation) and currently only supports *velocity setpoint commands* (PX4 additionally supports position and thrust setpoints). -::: +::: Client code must specify a setpoint before starting *Offboard mode*. The Offboard plugin automatically resends setpoints at 20Hz (PX4 requires that setpoints are minimally resent at 2Hz). @@ -15,10 +15,10 @@ If more precise control is required, clients can call the setpoint methods at wh ## Create the Plugin -::: tip +::: tip `Offboard` objects are created in the same way as other SDK plugins. General instructions are provided in the topic: [Using Plugins](../guide/using_plugins.md). -::: +::: The main steps are: @@ -77,9 +77,9 @@ if (result != Offboard::Result::Success) { } ``` -::: info +::: info Offboard mode can also be stopped by moving the vehicle into another mode (e.g. using the `Action` API). -::: +::: ## Velocity Setpoints diff --git a/docs/en/cpp/guide/system_information.md b/docs/en/cpp/guide/system_information.md index 46700a838f..d4e8364ae2 100644 --- a/docs/en/cpp/guide/system_information.md +++ b/docs/en/cpp/guide/system_information.md @@ -2,10 +2,10 @@ The [Info](../api_reference/classmavsdk_1_1_info.md) class is used to get system (vehicle) information, including the UUID (MAVLink `SYS_ID` if no UUID is stored in hardware), PX4 firmware version, vendor firmware version, host OS version (e.g. for NuttX) and vendor and product ids/names. -::: info +::: info Not all version information will necessarily be relevant on all vehicles. Where this occurs the hardware may return garbage values (for example, the simulator provides garbage values for the vendor firmware semantic version). -::: +::: ## Preconditions @@ -24,10 +24,10 @@ auto info = Info{system}; The code below shows how to query the hardware uid, version, and product, information and print it to the console: -::: tip +::: tip The UUID/uid with type uint64_t has been replaced by uid2 called hardware_uid with type char[18]. This was a a change inherited from mavlink in order to prevent ID conflicts. -::: +::: ```cpp std::cout << "hardware uid: " << info.hardware_uid() << '\n'; @@ -64,7 +64,7 @@ std::cout << " vendor_id: " << systemProduct.vendor_id<< '\n' << " product_name: " << systemProduct.product_id<< '\n'; ``` -::: tip +::: tip It is possible to query for the information before all values have been retrieved. Note above how we use `Info::is_complete()` to check that the version information (`Info::Version` and `Info::Product`) has all been obtained from the vehicle before printing it. -::: +::: diff --git a/docs/en/cpp/guide/taking_off_landing.md b/docs/en/cpp/guide/taking_off_landing.md index fddaf9067a..f786974a15 100644 --- a/docs/en/cpp/guide/taking_off_landing.md +++ b/docs/en/cpp/guide/taking_off_landing.md @@ -6,17 +6,16 @@ Most of the methods have both synchronous and asynchronous versions. The methods send commands to a vehicle, and return/complete with the vehicle's response. It is important to understand that a successful response indicates whether or not the vehicle intends to act on the command, not that it has finished the action (e.g. arming, landing, taking off etc.). -::: info +::: info The implication is that you may need to monitor for completion of actions! -::: +::: ## Create the Plugin -::: tip -`Action` objects are created in the same way as for other SDK plugins. +::: tip +`Action` objects are created in the same way as for other MAVSDK plugins. General instructions are provided in the topic: [Using Plugins](../guide/using_plugins.md). -::: The main steps are: @@ -40,20 +39,20 @@ The main steps are: The `action` object can then used to access the plugin API (as shown in the following sections). -::: info +::: info Some of the sections below additionally assume you have created a `Telemetry` instance that can be accessed using `telemetry`. -::: +::: ## Taking Off The recommended way to take off using the SDK (and PX4) is to use either of the [takeoff()](../api_reference/classmavsdk_1_1_action.md#classmavsdk_1_1_action_1a0121d39baf922b1d88283230207ab5d0) or [takeoff_async()](../api_reference/classmavsdk_1_1_action.md#classmavsdk_1_1_action_1ab658d938970326db41709d83e02b41e6) methods. If a takeoff command is accepted the vehicle will change to the [Takeoff mode](https://docs.px4.io/master/en/flight_modes/takeoff.html), fly to the takeoff altitude, and then hover (in takeoff mode) until another instruction is received. -::: info +::: info PX4/SDK also provides other ways to take off: - A copter or VTOL will take off automatically if a mission is started (fixed-wing will not). - You can also take off by manually driving the vehicle using the offboard API. -::: +::: The vehicle will only take off once *armed*, and can only arm once it is "healthy" (has been calibrated, the home position has been set, and there is a high-enough quality GPS lock). After it starts flying, code needs to check that takeoff is complete before sending additional instructions. @@ -114,9 +113,9 @@ while (telemetry.health_all_ok() != true) { } ``` -::: info +::: info Vehicle health can also be checked using [Telemetry:subscribe_health_all_ok()](../api_reference/classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a0f94ea6d707ff314e412367d6681bd8f). -::: +::: ### Arming @@ -133,9 +132,9 @@ if (arm_result != Action::Result::Success) { } ``` -::: tip +::: tip If the `arm()` method returns `Action::Result::Success` then the vehicle is armed and can proceed to takeoff. This can be confirmed using [Telemetry::armed()](../api_reference/classmavsdk_1_1_telemetry.md#classmavsdk_1_1_telemetry_1a6620142adc47f069262e5bf69dbb3876). -::: +::: ### Get/Set Takeoff Altitude @@ -163,9 +162,9 @@ if (takeoff_result != Action::Result::Success) { If the command succeeds the vehicle will takeoff, and hover at the takeoff altitude. Code should wait until takeoff has completed before sending the next instruction. Unfortunately there is no specific indicator to inform code that takeoff is complete. -::: info +::: info One alternative is to simply wait for enough time that the vehicle *should* have reached the takeoff altitude. -::: +::: The code below checks for takeoff completion by polling the current altitude until the target altitude is reached: @@ -185,9 +184,9 @@ while (current_positionset_value()` must only be called once. If your code can potentially call this multiple times, remember to unsubscribe from the callback after it succeeds (e.g. using `telemetry.subscribe_health_all_ok(nullptr)`). -::: +::: Depending on the architecture of your application, you may even wish to arm the vehicle in your callback function. Usually though it is easier to understand program flow using the approach above. diff --git a/docs/en/cpp/guide/test.md b/docs/en/cpp/guide/test.md index 22780c1fdb..8ce62807cd 100644 --- a/docs/en/cpp/guide/test.md +++ b/docs/en/cpp/guide/test.md @@ -1,91 +1,91 @@ -# Testing - -The MAVSDK C++ library has both unit and integration tests, written using the [Google C++ Test Framework](https://google.github.io/googletest/primer.html) (`gtest`). -The unit tests are run every time new code is committed to the library, and must pass before the code can be merged. - -This topic shows how to run the existing tests. - +# Testing + +The MAVSDK C++ library has both unit and integration tests, written using the [Google C++ Test Framework](https://google.github.io/googletest/primer.html) (`gtest`). +The unit tests are run every time new code is committed to the library, and must pass before the code can be merged. + +This topic shows how to run the existing tests. + ::: tip -For information on _writing_ tests see: [Writing Plugins > Test Code](../contributing/plugins.md#testing). +For information on _writing_ tests see: [Writing Plugins > Test Code](../contributing/plugins.md#testing). ::: - -## Running Unit Tests - -To run all unit tests: - -``` -./build/default/src/unit_tests_runner -``` - -## Running Integration Tests - -Tests can be run against the simulator (either manually starting PX4 SITL or letting the tests start it automatically) or against a real vehicle. - + +## Running Unit Tests + +To run all unit tests: + +``` +./build/default/src/unit_tests_runner +``` + +## Running Integration Tests + +Tests can be run against the simulator (either manually starting PX4 SITL or letting the tests start it automatically) or against a real vehicle. + ::: tip -To run SITL you will need to install the _Gazebo_ simulator. -This is included as part of the standard PX4 installation for [macOS](https://docs.px4.io/master/en/dev_setup/dev_env_mac.html) and [Linux](https://docs.px4.io/master/en/dev_setup/dev_env_linux_ubuntu.html). -It does not run on Windows. +To run SITL you will need to install the _Gazebo_ simulator. +This is included as part of the standard PX4 installation for [macOS](https://docs.px4.io/master/en/dev_setup/dev_env_mac.html) and [Linux](https://docs.px4.io/master/en/dev_setup/dev_env_linux_ubuntu.html). +It does not run on Windows. ::: - -### Autostart PX4 SITL - -Make sure that the [PX4 Gazebo simulation](https://docs.px4.io/master/en/simulation/gazebo.html) is built and works: - -``` -cd path/to/Firmware/ -make px4_sitl gazebo -``` - -Then press **Ctrl+C** to stop the simulation and run the integration tests: - -``` -cd path/to/MAVSDK/ -AUTOSTART_SITL=1 ./build/debug/src/integration_tests/integration_tests_runner -``` - -To run the tests without the 3D viewer (_gzclient_), use: - -``` -AUTOSTART_SITL=1 HEADLESS=1 ./build/debug/src/integration_tests/integration_tests_runner -``` - -### Run PX4 SITL Manually - -Build and run the PX4 simulation manually: - -``` -cd path/to/Firmware/ -make px4_sitl gazebo -``` - -Then run the tests as shown: - -``` -cd path/to/MAVSDK/ -./build/debug/src/integration_tests/integration_tests_runner -``` - + +### Autostart PX4 SITL + +Make sure that the [PX4 Gazebo simulation](https://docs.px4.io/master/en/simulation/gazebo.html) is built and works: + +``` +cd path/to/Firmware/ +make px4_sitl gazebo +``` + +Then press **Ctrl+C** to stop the simulation and run the integration tests: + +``` +cd path/to/MAVSDK/ +AUTOSTART_SITL=1 ./build/debug/src/integration_tests/integration_tests_runner +``` + +To run the tests without the 3D viewer (_gzclient_), use: + +``` +AUTOSTART_SITL=1 HEADLESS=1 ./build/debug/src/integration_tests/integration_tests_runner +``` + +### Run PX4 SITL Manually + +Build and run the PX4 simulation manually: + +``` +cd path/to/Firmware/ +make px4_sitl gazebo +``` + +Then run the tests as shown: + +``` +cd path/to/MAVSDK/ +./build/debug/src/integration_tests/integration_tests_runner +``` + ::: tip -The tests are designed to run in simulation, and may not be safe if run on a real vehicle. +The tests are designed to run in simulation, and may not be safe if run on a real vehicle. ::: - -### Gtest Tricks - -To list all integration tests: - -``` -./build/default/src/integration_tests/integration_tests_runner --gtest_list_tests -``` - -To run a single integration test: - -``` -./build/default/src/integration_tests/integration_tests_runner --gtest_filter="SitlTest.TelemetryAsync" -``` - -To run all telemetry tests: - -``` -./build/default/src/integration_tests/integration_tests_runner --gtest_filter="SitlTest.Telemetry*" -``` - + +### Gtest Tricks + +To list all integration tests: + +``` +./build/default/src/integration_tests/integration_tests_runner --gtest_list_tests +``` + +To run a single integration test: + +``` +./build/default/src/integration_tests/integration_tests_runner --gtest_filter="SitlTest.TelemetryAsync" +``` + +To run all telemetry tests: + +``` +./build/default/src/integration_tests/integration_tests_runner --gtest_filter="SitlTest.Telemetry*" +``` + diff --git a/docs/en/cpp/guide/using_plugins.md b/docs/en/cpp/guide/using_plugins.md index dced933eba..e8e2d5391a 100644 --- a/docs/en/cpp/guide/using_plugins.md +++ b/docs/en/cpp/guide/using_plugins.md @@ -5,14 +5,14 @@ For example, the [Action](../api_reference/classmavsdk_1_1_action.md) plugin is while the [Telemetry](../guide/telemetry.md) plugin can be used to query the vehicle GPS status, flight mode, etc. A separate plugin instance must be created for each system that needs it. -::: info +::: info All plugins are declared/used in the same way. This topic uses the `Action` plugin for the purposes of the demonstration. -::: +::: -::: info +::: info Plugins are named using the convention **mavsdk\__plugin\_name_.so**. For more information see [Building C++ Apps](../guide/toolchain.md) -::: +::: In the application source code: diff --git a/docs/en/cpp/guide/vtol.md b/docs/en/cpp/guide/vtol.md index a813056bbf..9ad541781e 100644 --- a/docs/en/cpp/guide/vtol.md +++ b/docs/en/cpp/guide/vtol.md @@ -3,10 +3,10 @@ MAVSDK has only basic support for VTOL vehicles. VTOL waypoint missions are only supported using the [MissionRaw plugin](../api_reference/classmavsdk_1_1_mission_raw.md). -::: info +::: info Most design and test effort has gone into multicopter support. [Get in touch](../../index.md#getting-help) if you would like to help enhance the VTOL/Fixed-wing experience! -::: +::: ## Supported Functionality diff --git a/docs/en/cpp/index.md b/docs/en/cpp/index.md index 14cbf5eca0..28cf20b268 100644 --- a/docs/en/cpp/index.md +++ b/docs/en/cpp/index.md @@ -40,7 +40,7 @@ The most important classes are: - [Geofence](api_reference/classmavsdk_1_1_geofence.md): Specify a geofence. - [Gimbal](api_reference/classmavsdk_1_1_gimbal.md): Control a gimbal. - [Camera](api_reference/classmavsdk_1_1_camera.md): Control a camera. -- [FollowMe](api_reference/classmavsdk_1_1_follow_me.md): Drone tracks a position supplied by the SDK. +- [FollowMe](api_reference/classmavsdk_1_1_follow_me.md): Drone tracks a position supplied by MAVSDK. - [Calibration](api_reference/classmavsdk_1_1_calibration.md): Calibrate sensors (e.g.: gyro, accelerometer, and magnetometer). - [LogFiles](api_reference/classmavsdk_1_1_log_files.md): Download log files from the vehicle. @@ -58,7 +58,7 @@ They should only be used where features are missing from the main APIs above. ## Contributing/Extending -The [Contributing](contributing/index.md) section contains everything you need to contribute to project, including topics about building the SDK from source code, running our integration and unit tests, and all other aspects of core development. +The [Contributing](contributing/index.md) section contains everything you need to contribute to project, including topics about building MAVSDK from source code, running our integration and unit tests, and all other aspects of core development. ## Troubleshooting diff --git a/docs/en/cpp/quickstart.md b/docs/en/cpp/quickstart.md index c4f25fcae3..904e916d2c 100644 --- a/docs/en/cpp/quickstart.md +++ b/docs/en/cpp/quickstart.md @@ -3,10 +3,9 @@ This quickstart shows you how to build and run a simple MAVSDK C++ example application against a simulated vehicle, and observe the operation using the console and in a ground station. ::: info -MAVSDK is essentially a C++ library (or rather multiple library files) that you can include and link in your C++ application. +MAVSDK is essentially a C++ library that you can include in and link from your C++ application. ::: - ## Install MAVSDK library ### Linux @@ -21,8 +20,8 @@ sudo apt remove mavsdk The prebuilt C++ library can be downloaded as a **.deb** from [releases](https://github.com/mavlink/MAVSDK/releases), e.g.: ``` -wget https://github.com/mavlink/MAVSDK/releases/download/v2.6.0/libmavsdk-dev_2.6.0_ubuntu22.04_amd64.deb -sudo dpkg -i libmavsdk-dev_2.6.0_ubuntu22.04_amd64.deb +wget https://github.com/mavlink/MAVSDK/releases/download/v3.0.0/libmavsdk-dev_3.0.0_ubuntu24.04_amd64.deb +sudo dpkg -i libmavsdk-dev_3.0.0_ubuntu24.04_amd64.deb ``` ### macOS @@ -46,7 +45,7 @@ To set up and run the PX4 simulator, you need to either [set up the PX4 SITL dev Or use a [pre-built docker container to run PX4 and the simulator](https://github.com/JonasVautherin/px4-gazebo-headless): ``` -docker run --rm -it jonasvautherin/px4-gazebo-headless:1.11.0 +docker run --rm -it jonasvautherin/px4-gazebo-headless:1.15.3 ``` ## Install QGroundControl @@ -75,24 +74,28 @@ To build the takeoff and land example, you can do: ```sh cd takeoff_and_land/ -cmake -Bbuild -H. +cmake -Bbuild -S. cmake --build build -j4 ``` +::: info +The examples match the MAVSDK version from your current branch. If you have another MAVSDK version installed, you should checkout the examples from that version. For example, if you have installed MAVSDK v2.x.y, you need to switch to the branch `v2`. +""" + ## Running an Example {#running_the_examples} First start PX4 in SITL (Simulation) and *QGroundControl* as described above. Then run the example app (from the **example/takeoff_land/build** directory) as shown: ```sh -build/takeoff_and_land udp://:14540 +build/takeoff_and_land udpin://0.0.0.0:14540 ``` The MAVSDK application should connect to PX4, and you will be able to observe the example running in the SDK terminal, SITL terminal, and/or *QGroundControl*. The expected behaviour is shown here: [Example: Takeoff and Land](examples/takeoff_and_land.md). ::: info -The first argument above is the connection string (`udp://:14540`). +The first argument above is the connection string (`udpin://0.0.0.0:14540`). This is the standard PX4 UDP port for connecting to offboard APIs (also see [Connecting to Systems](guide/connections.md)). ::: diff --git a/docs/en/cpp/troubleshooting.md b/docs/en/cpp/troubleshooting.md index 8e30a94aba..3faa7ef390 100644 --- a/docs/en/cpp/troubleshooting.md +++ b/docs/en/cpp/troubleshooting.md @@ -1,78 +1,78 @@ -# Troubleshooting - -## User callbacks {#user_callbacks} - -All callbacks back to the user of the library are called from one thread. The callbacks are stored in a queue. If the user does not return quickly enough from the callback, it can happen that the user callback queue fills up. - -If a callback takes more than one second, the user sees the warning: -``` -[02:56:26|Warn ] Callback took more than 1 second to run. -See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks (system_impl.cpp:327) -``` - -At 10 queued callbacks, the user sees the warning: -``` -[02:56:26|Warn ] User callback queue too slow. -See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks (system_impl.cpp:1213) -``` -At 100 queued callbacks, the user sees the error message: -``` -[02:56:35|Error] User callback queue overflown -See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks (system_impl.cpp:1218) -``` - -### How to debug this? - -To determine which callback is blocking the queue, you can set the environment variable `MAVSDK_CALLBACK_DEBUGGING` to `1`, which will print more debug information and abort the program as soon as the problem occurs. - -``` -MAVSDK_CALLBACK_DEBUGGING=1 ./my_executable_using_mavsdk -``` -or: -``` -export MAVSDK_CALLBACK_DEBUGGING=1 -./my_executable_using_mavsdk -``` - -You should then see something like this hinting at which callback might be responsible: -``` -[03:00:02|Warn ] Callback called from telemetry_impl.cpp:533 took more than 1 second to run. (system_impl.cpp:320) -[2] 1261673 abort (core dumped) MAVSDK_CALLBACK_DEBUGGING=1 ..." -``` - -Note that this does not point to the blocking code, but only to the place where your blocking callback was called. - -### How to avoid this? - -The rule is to spend as little time and CPU in the callbacks as possible. -For instance, inside the callbacks you should not wait on other events or sleep. - -If you really want to do something that takes longer inside a callback, the workaround is to just spawn that activity on another thread, e.g. using `std::thread`: - -``` -void my_callback(Telemetry::Position position) -{ - std::thread([position]() { - std::this_thread_sleep_for(std::chrono::seconds(3)); - my_delayed_action(position); - }).detach(); -} -``` - -### Why did this use to work? - -Before introducing the callback queue, we used a thread pool of 3 threads to call user callbacks. -The thread pool was written to avoid everything from stalling if a user blocked in one of the callbacks. -It generally worked provided the user did not block in more than 3 callbacks at any given time. - -However, it had also some disadvantages: - -- Due to the thread pool multiple threads could call a function at any given time. - This means that one callback can be called from at least two threads at the same time which is quite likely if the callback is called at a high rate. - This can create race conditions on the user side unless a mutex is used to prevent this. - However, it's not very intuitive that a mutex is needed for that, and mutexes in general should be avoided, if possible, for performance reasons. - Such race conditions also showed up as CI test failures, see: [MAVSDK#1010](https://github.com/mavlink/MAVSDK/issues/1010), [MAVSDK#1045](https://github.com/mavlink/MAVSDK/issues/1045). -- For developers the old thread pool behaviour was unclear and unpredictable. - Basically, without code inspection, it was difficult to know if blocking in a callback is safe or not. - When trying with one blocking callback, it would work, however, this can create a false sense of security as with 3 blocking callbacks it would suddenly lock up. -- Previously, when this happened, it was difficult to debug because it would either lead to a crash on destruction, or lock up at which point the backtrace of all threads need to be looked at using gdb. +# Troubleshooting + +## User callbacks {#user_callbacks} + +All callbacks back to the user of the library are called from one thread. The callbacks are stored in a queue. If the user does not return quickly enough from the callback, it can happen that the user callback queue fills up. + +If a callback takes more than one second, the user sees the warning: +``` +[02:56:26|Warn ] Callback took more than 1 second to run. +See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks (system_impl.cpp:327) +``` + +At 10 queued callbacks, the user sees the warning: +``` +[02:56:26|Warn ] User callback queue too slow. +See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks (system_impl.cpp:1213) +``` +At 100 queued callbacks, the user sees the error message: +``` +[02:56:35|Error] User callback queue overflown +See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks (system_impl.cpp:1218) +``` + +### How to debug this? + +To determine which callback is blocking the queue, you can set the environment variable `MAVSDK_CALLBACK_DEBUGGING` to `1`, which will print more debug information and abort the program as soon as the problem occurs. + +``` +MAVSDK_CALLBACK_DEBUGGING=1 ./my_executable_using_mavsdk +``` +or: +``` +export MAVSDK_CALLBACK_DEBUGGING=1 +./my_executable_using_mavsdk +``` + +You should then see something like this hinting at which callback might be responsible: +``` +[03:00:02|Warn ] Callback called from telemetry_impl.cpp:533 took more than 1 second to run. (system_impl.cpp:320) +[2] 1261673 abort (core dumped) MAVSDK_CALLBACK_DEBUGGING=1 ..." +``` + +Note that this does not point to the blocking code, but only to the place where your blocking callback was called. + +### How to avoid this? + +The rule is to spend as little time and CPU in the callbacks as possible. +For instance, inside the callbacks you should not wait on other events or sleep. + +If you really want to do something that takes longer inside a callback, the workaround is to just spawn that activity on another thread, e.g. using `std::thread`: + +``` +void my_callback(Telemetry::Position position) +{ + std::thread([position]() { + std::this_thread_sleep_for(std::chrono::seconds(3)); + my_delayed_action(position); + }).detach(); +} +``` + +### Why did this use to work? + +Before introducing the callback queue, we used a thread pool of 3 threads to call user callbacks. +The thread pool was written to avoid everything from stalling if a user blocked in one of the callbacks. +It generally worked provided the user did not block in more than 3 callbacks at any given time. + +However, it had also some disadvantages: + +- Due to the thread pool multiple threads could call a function at any given time. + This means that one callback can be called from at least two threads at the same time which is quite likely if the callback is called at a high rate. + This can create race conditions on the user side unless a mutex is used to prevent this. + However, it's not very intuitive that a mutex is needed for that, and mutexes in general should be avoided, if possible, for performance reasons. + Such race conditions also showed up as CI test failures, see: [MAVSDK#1010](https://github.com/mavlink/MAVSDK/issues/1010), [MAVSDK#1045](https://github.com/mavlink/MAVSDK/issues/1045). +- For developers the old thread pool behaviour was unclear and unpredictable. + Basically, without code inspection, it was difficult to know if blocking in a callback is safe or not. + When trying with one blocking callback, it would work, however, this can create a false sense of security as with 3 blocking callbacks it would suddenly lock up. +- Previously, when this happened, it was difficult to debug because it would either lead to a crash on destruction, or lock up at which point the backtrace of all threads need to be looked at using gdb. diff --git a/docs/en/faq.md b/docs/en/faq.md index e7f4018a62..56eba03ea0 100644 --- a/docs/en/faq.md +++ b/docs/en/faq.md @@ -1,12 +1,12 @@ # FAQ -### Why was the core of MAVSDK written in C++? +## Why was the core of MAVSDK written in C++? The aim was to have an API in a language which is cross-platform and has many language bindings. The library also needs to be lightweight and fast, so it does not slow down for onboard usage at higher rate messaging. Additionally, MAVSDK should be able to run efficiently in embedded setups, e.g. as part of an app or onboard a drone on a companion computer, as well as provide a simple and safe API. This favoured C++ over C as it allows for more expressive but type-safe APIs using standard library containers (e.g. `std::vector`) for usage in embedded setups. -### Are multiple vehicles supported? +## Are multiple vehicles supported? Yes. - The MAVSDK C++ library allows C++ applications to connect to multiple vehicles at a time. @@ -22,11 +22,11 @@ Each system has a network-unique MAVLink system ID, with a value between 1 and 2 Each component in a system shares its system id, and has a system-unique component ID, again with a value 1 and 255. ::: -### Is MAVLink 1 supported? +## Is MAVLink 1 supported? No. MAVSDK only supports [MAVLink 2.0](https://mavlink.io/en/guide/mavlink_2.html). -### What sorts of vehicles are supported? +## What sorts of vehicles are supported? The MAVSDK API is designed for interacting with *aircraft*. It has primarily been tested for use with multicopters, but also has basic support for fixed wing and [VTOL](cpp/guide/vtol.md). @@ -34,38 +34,34 @@ It has primarily been tested for use with multicopters, but also has basic suppo The API *may* "work" with ground-based or other types of vehicles, but some methods will not make sense. This use-case is mostly unsupported and untested. -### Does MAVSDK support indoor use? +## Does MAVSDK support indoor use? Indoor use is supported, however, some modes such as mission or position control are not available indoor, unless some additional positioning method is available (e.g. optical flow, visual-inertial odometry, a motion capture system, etc.). Note that PX4 currently does not support missions using "local coordinates" (i.e. meters) but only supports using "global coordinates" (i. e. latitude/longitude). -### What UAV flight stacks are supported? +## What UAV flight stacks are supported? -MAVSDK, so far, is optimised for use with the PX4 flight stack and all testing is done against PX4. +MAVSDK, so far, is optimised for use with the PX4 flight stack and most testing is done against PX4. +That being said, we are more and more trying to test MAVSDK against ArduPilot as well. -While many features should work on other flight stacks there may be implementation differences at the [MAVLink microservices level](https://mavlink.io/en/protocol/overview.html) which means that not every API will work. +While many features work for ArduPilot there are several implementation differences at the [MAVLink microservices level](https://mavlink.io/en/protocol/overview.html) which means that not every API will work. For example, PX4 and ArduPilot implement the parameter protocol differently, and vary slightly in the mission upload/download protocol (e.g. ArduPilot uses the 0 entry as the home position). ::: info -The SDK welcomes contributions to better support flight stacks other than PX4. -We do however expect contributors to also help with testing and maintenance support for using the SDK with their autopilot. +MAVSDK welcomes contributions to better support flight stacks other than PX4. +We do however expect contributors to also help with testing and maintenance support for using the MAVSDK with their autopilot. ::: -### Are serial connections supported? +## Are serial connections supported? Yes. Serial, TCP, and UDP connections are supported, see [notes on connection](cpp/guide/connections.md). -### Why is libCURL a dependency? - -libCURL will be required to download the camera definition file which is referenced in [CAMERA_INFORMATION](https://mavlink.io/en/messages/common.html#CAMERA_INFORMATION). -It might also come in handy whenever any other REST resources are required. - -### How are plugins added? +## How are plugins added? Check out [C++/Contributing/Plugins](cpp/contributing/plugins.md). -### Can a plugin depend on another one? +## Can a plugin depend on another one? Yes - but it should not! The idea is that plugins don't have any coupling between each other which allows for any plugin to be changed or removed without breaking the rest. @@ -74,15 +70,15 @@ If the same code is used in many places, it can always be moved to core and get We have sometimes moved functionality from plugins to the core if it was exposed in multiple plugins. As an example mission upload/download has been moved to the core so it can be used in the Mission plugin as well as the MissionRaw and Geofence plugins. -### Can MAVSDK run on an embedded platform / microcontroller? +## Can MAVSDK run on an embedded platform / microcontroller? -MAVSDK is generally written at a bit higher level, geared towards ARM devices such as a Raspberry Pi, a smartphone, or a similar device with equal/better performance. +MAVSDK is generally written at a bit higher level and using the POSIX interfaces for system calls, depending on the C++ standard library including threads. As MAVSDK does not actually require too much CPU power, it could in theory be run on a microcontroller such as an ARM Cortex M4, however, it would require the POSIX APIs for serial and networking communication, as well as the C++ standard library for classes/functions such as `std::thread` or `std::vector`. The recommendation for usage with a microcontroller would be to use the pure [C MAVLink headers](https://mavlink.io/en/mavgen_c/). -### Why is MAVLink Passthrough only available in C++? +## Why is MAVLink Passthrough only available in C++? The C++ MAVLink passthrough plugin basically exposes the direct C MAVLink API. While it would be nice to have access to all MAVLink messages in the language wrappers, there are some technical challenges: @@ -93,7 +89,7 @@ The C++ MAVLink passthrough plugin basically exposes the direct C MAVLink API. W From a MAVSDK project point of view, there is also an advantage of not having a passthrough available in language wrappers; it encourages that required features are contributed back to the open-source project, rather than implemented in private using passthrough, and thus benefitting everyone. -### Why is gRPC used for the language wrappers? +## Why is gRPC used for the language wrappers? There are multiple ways to support multiple programming languages all with their pros and cons: @@ -122,7 +118,7 @@ You can [read more about the auto-generation](cpp/contributing/autogen.md), and We are not ruling out direct-bindings for the future, there is e.g. a [prototype for Python using pybind11](https://github.com/mavlink/MAVSDK/pull/1283), so this is an ongoing topic. -### Use of deleted function Mavsdk() +## Use of deleted function Mavsdk() ``` error: use of deleted function ‘mavsdk::Mavsdk::Mavsdk()’ @@ -131,3 +127,11 @@ mavsdk::Mavsdk mavsdk; ``` The API to construct `Mavsdk` has changed with v2. Check [API changes](cpp/api_changes.md): + +## What is the difference between unit, system, and integration tests? + +The unit tests are only concerned with one class or less. It's often used for MAVSDK internal logic or helpers. + +System tests are used to test the MAVLink implementation, by running a plugin against it's server plugin counterpart. This way we can test both at the same time while keeping the tests fast because they don't rely on an simulation that would need to be started up. + +We have opted to slowly fade out integration tests and use a few examples instead (also see (explanation)[documentation.md#integration_tests]). diff --git a/docs/en/python/index.md b/docs/en/python/index.md index a8d2d147ce..b0eb259c44 100644 --- a/docs/en/python/index.md +++ b/docs/en/python/index.md @@ -1,4 +1,4 @@ -# MAVSDK-Python - -* [Python QuickStart](quickstart.md) -* [API documentation](http://mavsdk-python-docs.s3-website.eu-central-1.amazonaws.com/) +# MAVSDK-Python + +* [Python QuickStart](quickstart.md) +* [API documentation](http://mavsdk-python-docs.s3-website.eu-central-1.amazonaws.com/) diff --git a/docs/en/swift/index.md b/docs/en/swift/index.md index 261f06a721..1b72bb78bf 100644 --- a/docs/en/swift/index.md +++ b/docs/en/swift/index.md @@ -1,3 +1,3 @@ -# MAVSDK-Swift - -* [API documentation](http://mavsdk-swift-docs.s3.eu-central-1.amazonaws.com/main/index.html) +# MAVSDK-Swift + +* [API documentation](http://mavsdk-swift-docs.s3.eu-central-1.amazonaws.com/main/index.html) diff --git a/proto b/proto index 4d2e9c4c1f..87e6c07f43 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 4d2e9c4c1fef56e4d954fbfd9c550ee945cb50e7 +Subproject commit 87e6c07f43743cfd21e10ebfe4021e3c812c377c diff --git a/src/mavsdk/core/include/mavsdk/autopilot.h b/src/mavsdk/core/include/mavsdk/autopilot.h index f5b339e668..dba59460ea 100644 --- a/src/mavsdk/core/include/mavsdk/autopilot.h +++ b/src/mavsdk/core/include/mavsdk/autopilot.h @@ -2,10 +2,13 @@ namespace mavsdk { +/** + * @brief Autopilot type + */ enum class Autopilot { - Unknown, - Px4, - ArduPilot, + Unknown, // Autopilot unknown + Px4, // PX4 + ArduPilot, // ArduPilot }; } // namespace mavsdk diff --git a/src/mavsdk/core/include/mavsdk/base64.h b/src/mavsdk/core/include/mavsdk/base64.h index 831960d150..4db20c314a 100644 --- a/src/mavsdk/core/include/mavsdk/base64.h +++ b/src/mavsdk/core/include/mavsdk/base64.h @@ -6,7 +6,22 @@ namespace mavsdk { +/** + * @brief Encode raw bytes to a base64 string + * + * @param raw Raw bytes + * + * @return Base64 string + */ std::string base64_encode(std::vector& raw); + +/** + * @brief Decode a base64 string into raw bytes + * + * @param str Base64 string + * + * @return Raw bytes + */ std::vector base64_decode(const std::string& str); } // namespace mavsdk diff --git a/src/mavsdk/core/include/mavsdk/handle.h b/src/mavsdk/core/include/mavsdk/handle.h index 189513bd09..f9833e9a1e 100644 --- a/src/mavsdk/core/include/mavsdk/handle.h +++ b/src/mavsdk/core/include/mavsdk/handle.h @@ -15,6 +15,11 @@ template class Handle { Handle() = default; ~Handle() = default; + /** + * @brief Wheter handle is valid + * + * @return true if handle is valid + */ bool valid() const { return _id != 0; } bool operator<(const Handle& other) const { return _id < other._id; } diff --git a/src/mavsdk/core/include/mavsdk/mavsdk.h b/src/mavsdk/core/include/mavsdk/mavsdk.h index fc7c899c5e..b7da5d5e76 100644 --- a/src/mavsdk/core/include/mavsdk/mavsdk.h +++ b/src/mavsdk/core/include/mavsdk/mavsdk.h @@ -129,8 +129,8 @@ class Mavsdk { * ConnectionError type */ struct ConnectionError { - std::string error_description; - ConnectionHandle connection_handle; + std::string error_description; ///< The error description + ConnectionHandle connection_handle; ///< The connection handle }; /** diff --git a/src/mavsdk/plugins/action/include/plugins/action/action.h b/src/mavsdk/plugins/action/include/plugins/action/action.h index 16bcb20ee7..540c0eaae4 100644 --- a/src/mavsdk/plugins/action/include/plugins/action/action.h +++ b/src/mavsdk/plugins/action/include/plugins/action/action.h @@ -130,7 +130,9 @@ class Action : public PluginBase { * * This function is blocking. See 'arm_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result arm() const; @@ -156,7 +158,9 @@ class Action : public PluginBase { * * This function is blocking. See 'arm_force_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result arm_force() const; @@ -178,7 +182,9 @@ class Action : public PluginBase { * * This function is blocking. See 'disarm_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result disarm() const; @@ -204,7 +210,9 @@ class Action : public PluginBase { * * This function is blocking. See 'takeoff_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result takeoff() const; @@ -224,7 +232,9 @@ class Action : public PluginBase { * * This function is blocking. See 'land_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result land() const; @@ -244,7 +254,9 @@ class Action : public PluginBase { * * This function is blocking. See 'reboot_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result reboot() const; @@ -268,7 +280,9 @@ class Action : public PluginBase { * * This function is blocking. See 'shutdown_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result shutdown() const; @@ -286,11 +300,13 @@ class Action : public PluginBase { * @brief Send command to terminate the drone. * * This will run the terminate routine as configured on the drone (e.g. disarm and open the - * parachute). + parachute). * * This function is blocking. See 'terminate_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result terminate() const; @@ -312,7 +328,9 @@ class Action : public PluginBase { * * This function is blocking. See 'kill_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result kill() const; @@ -332,13 +350,15 @@ class Action : public PluginBase { * @brief Send command to return to the launch (takeoff) position and land. * * This switches the drone into [Return - * mode](https://docs.px4.io/master/en/flight_modes/return.html) which generally means it will - * rise up to a certain altitude to clear any obstacles before heading back to the launch - * (takeoff) position and land there. + mode](https://docs.px4.io/master/en/flight_modes/return.html) which + * generally means it will rise up to a certain altitude to clear any obstacles before heading + * back to the launch (takeoff) position and land there. * * This function is blocking. See 'return_to_launch_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result return_to_launch() const; @@ -369,7 +389,9 @@ class Action : public PluginBase { * * This function is blocking. See 'goto_location_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result goto_location( double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg) const; @@ -397,7 +419,9 @@ class Action : public PluginBase { * * This function is blocking. See 'do_orbit_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result do_orbit( float radius_m, @@ -431,7 +455,9 @@ class Action : public PluginBase { * * This function is blocking. See 'hold_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result hold() const; @@ -451,7 +477,9 @@ class Action : public PluginBase { * * This function is blocking. See 'set_actuator_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_actuator(int32_t index, float value) const; @@ -474,9 +502,11 @@ class Action : public PluginBase { * is already in fixedwing mode. * * This function is blocking. See 'transition_to_fixedwing_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result transition_to_fixedwing() const; @@ -499,9 +529,11 @@ class Action : public PluginBase { * is already in multicopter mode. * * This function is blocking. See 'transition_to_multicopter_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result transition_to_multicopter() const; @@ -538,7 +570,9 @@ class Action : public PluginBase { * * This function is blocking. See 'set_takeoff_altitude_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_takeoff_altitude(float altitude) const; @@ -578,9 +612,11 @@ class Action : public PluginBase { * @brief Set the return to launch minimum return altitude (in meters). * * This function is blocking. See 'set_return_to_launch_altitude_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_return_to_launch_altitude(float relative_altitude_m) const; @@ -602,7 +638,9 @@ class Action : public PluginBase { * * This function is blocking. See 'set_current_speed_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_current_speed(float speed_m_s) const; diff --git a/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h b/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h index f2a3d750d8..4531da7eab 100644 --- a/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h +++ b/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h @@ -302,7 +302,9 @@ class ActionServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_allow_takeoff(bool allow_takeoff) const; @@ -311,7 +313,9 @@ class ActionServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_armable(bool armable, bool force_armable) const; @@ -320,7 +324,9 @@ class ActionServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_disarmable(bool disarmable, bool force_disarmable) const; @@ -329,7 +335,9 @@ class ActionServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_allowable_flight_modes(AllowableFlightModes flight_modes) const; diff --git a/src/mavsdk/plugins/arm_authorizer_server/include/plugins/arm_authorizer_server/arm_authorizer_server.h b/src/mavsdk/plugins/arm_authorizer_server/include/plugins/arm_authorizer_server/arm_authorizer_server.h index 6b58d5c2a8..0abe8fd461 100644 --- a/src/mavsdk/plugins/arm_authorizer_server/include/plugins/arm_authorizer_server/arm_authorizer_server.h +++ b/src/mavsdk/plugins/arm_authorizer_server/include/plugins/arm_authorizer_server/arm_authorizer_server.h @@ -24,7 +24,7 @@ class ServerComponent; class ArmAuthorizerServerImpl; /** - * @brief + * @brief Use arm authorization. */ class ArmAuthorizerServer : public ServerPluginBase { public: @@ -47,7 +47,7 @@ class ArmAuthorizerServer : public ServerPluginBase { ~ArmAuthorizerServer() override; /** - * @brief + * @brief The rejection reason */ enum class RejectionReason { Generic, /**< @brief Not a specific reason. */ @@ -68,7 +68,7 @@ class ArmAuthorizerServer : public ServerPluginBase { operator<<(std::ostream& str, ArmAuthorizerServer::RejectionReason const& rejection_reason); /** - * @brief + * @brief The result */ enum class Result { Unknown, /**< @brief Unknown result. */ @@ -114,7 +114,9 @@ class ArmAuthorizerServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result accept_arm_authorization(int32_t valid_time_s) const; @@ -123,7 +125,9 @@ class ArmAuthorizerServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result reject_arm_authorization(bool temporarily, RejectionReason reason, int32_t extra_info) const; diff --git a/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h b/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h index a3e6529eed..fdd128220b 100644 --- a/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h +++ b/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h @@ -174,7 +174,9 @@ class Calibration : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result cancel() const; diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index de1970fda3..dc30405b5e 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -262,7 +262,7 @@ class Camera : public PluginBase { operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info); /** - * @brief + * @brief An update about the current mode */ struct ModeUpdate { int32_t component_id{}; /**< @brief Component ID */ @@ -284,7 +284,7 @@ class Camera : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Camera::ModeUpdate const& mode_update); /** - * @brief + * @brief An update about a video stream */ struct VideoStreamUpdate { int32_t component_id{}; /**< @brief Component ID */ @@ -379,7 +379,7 @@ class Camera : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Camera::Storage const& storage); /** - * @brief + * @brief An update about storage */ struct StorageUpdate { int32_t component_id{}; /**< @brief Component ID */ @@ -401,7 +401,7 @@ class Camera : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Camera::StorageUpdate const& storage_update); /** - * @brief + * @brief An update about a current setting */ struct CurrentSettingsUpdate { int32_t component_id{}; /**< @brief Component ID */ @@ -425,7 +425,7 @@ class Camera : public PluginBase { operator<<(std::ostream& str, Camera::CurrentSettingsUpdate const& current_settings_update); /** - * @brief + * @brief An update about possible setting options */ struct PossibleSettingOptionsUpdate { int32_t component_id{}; /**< @brief Component ID */ @@ -656,7 +656,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'take_photo_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result take_photo(int32_t component_id) const; @@ -673,7 +675,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'start_photo_interval_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result start_photo_interval(int32_t component_id, float interval_s) const; @@ -689,7 +693,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'stop_photo_interval_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result stop_photo_interval(int32_t component_id) const; @@ -705,7 +711,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'start_video_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result start_video(int32_t component_id) const; @@ -721,7 +729,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'stop_video_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result stop_video(int32_t component_id) const; @@ -730,7 +740,9 @@ class Camera : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result start_video_streaming(int32_t component_id, int32_t stream_id) const; @@ -739,7 +751,9 @@ class Camera : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result stop_video_streaming(int32_t component_id, int32_t stream_id) const; @@ -755,7 +769,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'set_mode_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_mode(int32_t component_id, Mode mode) const; @@ -1004,7 +1020,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'set_setting_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_setting(int32_t component_id, Setting setting) const; @@ -1051,7 +1069,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'format_storage_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result format_storage(int32_t component_id, int32_t storage_id) const; @@ -1071,7 +1091,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'reset_settings_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result reset_settings(int32_t component_id) const; @@ -1087,7 +1109,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'zoom_in_start_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result zoom_in_start(int32_t component_id) const; @@ -1103,7 +1127,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'zoom_out_start_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result zoom_out_start(int32_t component_id) const; @@ -1119,7 +1145,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'zoom_stop_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result zoom_stop(int32_t component_id) const; @@ -1135,7 +1163,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'zoom_range_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result zoom_range(int32_t component_id, float range) const; @@ -1156,7 +1186,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'track_point_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result track_point(int32_t component_id, float point_x, float point_y, float radius) const; @@ -1178,7 +1210,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'track_rectangle_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result track_rectangle( int32_t component_id, @@ -1199,7 +1233,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'track_stop_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result track_stop(int32_t component_id) const; @@ -1215,7 +1251,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'focus_in_start_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result focus_in_start(int32_t component_id) const; @@ -1231,7 +1269,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'focus_out_start_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result focus_out_start(int32_t component_id) const; @@ -1247,7 +1287,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'focus_stop_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result focus_stop(int32_t component_id) const; @@ -1263,7 +1305,9 @@ class Camera : public PluginBase { * * This function is blocking. See 'focus_range_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result focus_range(int32_t component_id, float range) const; diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 29238c9511..89a4f30cf1 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -321,11 +321,11 @@ class CameraServer : public ServerPluginBase { operator<<(std::ostream& str, CameraServer::StorageInformation const& storage_information); /** - * @brief + * @brief Capture status */ struct CaptureStatus { /** - * @brief + * @brief The image status */ enum class ImageStatus { Idle, /**< @brief idle. */ @@ -343,7 +343,7 @@ class CameraServer : public ServerPluginBase { operator<<(std::ostream& str, CameraServer::CaptureStatus::ImageStatus const& image_status); /** - * @brief + * @brief The video status */ enum class VideoStatus { Idle, /**< @brief idle. */ @@ -447,11 +447,13 @@ class CameraServer : public ServerPluginBase { /** * @brief Sets the camera information. This must be called as soon as the camera server is - * created. + created. * * This function is blocking. * + * @return Result of request. + */ Result set_information(Information information) const; @@ -460,17 +462,21 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_video_streaming(VideoStreaming video_streaming) const; /** * @brief Sets image capture in progress status flags. This should be set to true when the - * camera is busy taking a photo and false when it is done. + camera is busy taking a photo and false when it is done. * * This function is blocking. * + * @return Result of request. + */ Result set_in_progress(bool in_progress) const; @@ -500,7 +506,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_take_photo(CameraFeedback take_photo_feedback, CaptureInfo capture_info) const; @@ -527,11 +535,13 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to stop video requests. Each request received should respond using - * StopVideoResponse + StopVideoResponse * * This function is blocking. * + * @return Result of request. + */ Result respond_start_video(CameraFeedback start_video_feedback) const; @@ -561,7 +571,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_stop_video(CameraFeedback stop_video_feedback) const; @@ -592,7 +604,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_start_video_streaming(CameraFeedback start_video_streaming_feedback) const; @@ -623,7 +637,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_stop_video_streaming(CameraFeedback stop_video_streaming_feedback) const; @@ -653,7 +669,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_set_mode(CameraFeedback set_mode_feedback) const; @@ -684,7 +702,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_storage_information( CameraFeedback storage_information_feedback, StorageInformation storage_information) const; @@ -715,7 +735,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_capture_status( CameraFeedback capture_status_feedback, CaptureStatus capture_status) const; @@ -746,7 +768,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_format_storage(CameraFeedback format_storage_feedback) const; @@ -776,7 +800,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_reset_settings(CameraFeedback reset_settings_feedback) const; @@ -805,7 +831,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_zoom_in_start(CameraFeedback zoom_in_start_feedback) const; @@ -834,7 +862,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_zoom_out_start(CameraFeedback zoom_out_start_feedback) const; @@ -863,7 +893,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_zoom_stop(CameraFeedback zoom_stop_feedback) const; @@ -892,7 +924,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_zoom_range(CameraFeedback zoom_range_feedback) const; @@ -901,7 +935,7 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * - * @return Result of request. + */ void set_tracking_rectangle_status(TrackRectangle tracked_rectangle) const; @@ -910,7 +944,7 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * - * @return Result of request. + */ void set_tracking_off_status() const; @@ -982,7 +1016,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_tracking_point_command(CameraFeedback stop_video_feedback) const; @@ -991,7 +1027,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_tracking_rectangle_command(CameraFeedback stop_video_feedback) const; @@ -1000,7 +1038,9 @@ class CameraServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result respond_tracking_off_command(CameraFeedback stop_video_feedback) const; diff --git a/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h b/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h index 19be566c0e..045c0c656e 100644 --- a/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h +++ b/src/mavsdk/plugins/component_metadata/include/plugins/component_metadata/component_metadata.h @@ -60,7 +60,7 @@ class ComponentMetadata : public PluginBase { ~ComponentMetadata() override; /** - * @brief + * @brief The metadata type */ enum class MetadataType { AllCompleted, /**< @brief This is set in the subscription callback when all metadata types @@ -102,18 +102,18 @@ class ComponentMetadata : public PluginBase { operator<<(std::ostream& str, ComponentMetadata::MetadataData const& metadata_data); /** - * @brief Possible results returned for GetMetadata + * @brief Possible results returned */ enum class Result { - Success, /**< @brief. */ - NotAvailable, /**< @brief. */ - ConnectionError, /**< @brief. */ - Unsupported, /**< @brief. */ - Denied, /**< @brief. */ - Failed, /**< @brief. */ - Timeout, /**< @brief. */ - NoSystem, /**< @brief. */ - NotRequested, /**< @brief. */ + Success, /**< @brief Success. */ + NotAvailable, /**< @brief Not available. */ + ConnectionError, /**< @brief Connection error. */ + Unsupported, /**< @brief Unsupported. */ + Denied, /**< @brief Denied. */ + Failed, /**< @brief Failed. */ + Timeout, /**< @brief Timeout. */ + NoSystem, /**< @brief No system. */ + NotRequested, /**< @brief Not requested. */ }; /** @@ -155,23 +155,23 @@ class ComponentMetadata : public PluginBase { /** * @brief Request metadata from a specific component. This is used to start requesting metadata - * from a component. The metadata can later be accessed via subscription (see below) or - * GetMetadata. + from a component. + * The metadata can later be accessed via subscription (see below) or GetMetadata. * * This function is blocking. * - * @return Result of request. + */ void request_component(uint32_t compid) const; /** * @brief Request metadata from the autopilot component. This is used to start requesting - * metadata from the autopilot. The metadata can later be accessed via subscription (see below) - * or GetMetadata. + metadata from the autopilot. + * The metadata can later be accessed via subscription (see below) or GetMetadata. * * This function is blocking. * - * @return Result of request. + */ void request_autopilot_component() const; diff --git a/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h b/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h index eed0a64122..cb9e3e9b54 100644 --- a/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h +++ b/src/mavsdk/plugins/component_metadata_server/include/plugins/component_metadata_server/component_metadata_server.h @@ -47,7 +47,7 @@ class ComponentMetadataServer : public ServerPluginBase { ~ComponentMetadataServer() override; /** - * @brief + * @brief The metadata type */ enum class MetadataType { Parameter, /**< @brief Parameter metadata. */ @@ -64,7 +64,7 @@ class ComponentMetadataServer : public ServerPluginBase { operator<<(std::ostream& str, ComponentMetadataServer::MetadataType const& metadata_type); /** - * @brief + * @brief The metadata type and content */ struct Metadata { MetadataType type{}; /**< @brief The metadata type */ @@ -92,7 +92,7 @@ class ComponentMetadataServer : public ServerPluginBase { * * This function is blocking. * - * @return Result of request. + */ void set_metadata(std::vector metadata) const; diff --git a/src/mavsdk/plugins/events/events.cpp b/src/mavsdk/plugins/events/events.cpp index f70519dffb..8d250ba4c7 100644 --- a/src/mavsdk/plugins/events/events.cpp +++ b/src/mavsdk/plugins/events/events.cpp @@ -190,6 +190,8 @@ std::ostream& operator<<(std::ostream& str, Events::Result const& result) return str << "Timeout"; case Events::Result::NoSystem: return str << "No System"; + case Events::Result::Unknown: + return str << "Unknown"; default: return str << "Unknown"; } diff --git a/src/mavsdk/plugins/events/include/plugins/events/events.h b/src/mavsdk/plugins/events/include/plugins/events/events.h index a06e555ee9..cab5401839 100644 --- a/src/mavsdk/plugins/events/include/plugins/events/events.h +++ b/src/mavsdk/plugins/events/include/plugins/events/events.h @@ -59,17 +59,17 @@ class Events : public PluginBase { ~Events() override; /** - * @brief + * @brief Log level type */ enum class LogLevel { - Emergency, /**< @brief. */ - Alert, /**< @brief. */ - Critical, /**< @brief. */ - Error, /**< @brief. */ - Warning, /**< @brief. */ - Notice, /**< @brief. */ - Info, /**< @brief. */ - Debug, /**< @brief. */ + Emergency, /**< @brief Emergency. */ + Alert, /**< @brief Alert. */ + Critical, /**< @brief Critical. */ + Error, /**< @brief Error. */ + Warning, /**< @brief Warning. */ + Notice, /**< @brief Notice. */ + Info, /**< @brief Info. */ + Debug, /**< @brief Debug. */ }; /** @@ -80,14 +80,14 @@ class Events : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Events::LogLevel const& log_level); /** - * @brief + * @brief Event type */ struct Event { uint32_t compid{}; /**< @brief The source component ID of the event */ std::string message{}; /**< @brief Short, single-line message */ std::string description{}; /**< @brief Detailed description (optional, might be multiple lines) */ - LogLevel log_level{}; /**< @brief */ + LogLevel log_level{}; /**< @brief Log level of message */ std::string event_namespace{}; /**< @brief Namespace, e.g. "px4" */ std::string event_name{}; /**< @brief Event name (unique within the namespace) */ }; @@ -107,13 +107,13 @@ class Events : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Events::Event const& event); /** - * @brief + * @brief Health and arming check problem type */ struct HealthAndArmingCheckProblem { std::string message{}; /**< @brief Short, single-line message */ std::string description{}; /**< @brief Detailed description (optional, might be multiple lines) */ - LogLevel log_level{}; /**< @brief */ + LogLevel log_level{}; /**< @brief Log level of message */ std::string health_component{}; /**< @brief Associated health component, e.g. "gps" */ }; @@ -163,7 +163,7 @@ class Events : public PluginBase { std::ostream& str, Events::HealthAndArmingCheckMode const& health_and_arming_check_mode); /** - * @brief + * @brief Health component report type */ struct HealthComponentReport { std::string name{}; /**< @brief Unique component name, e.g. "gps" */ @@ -191,7 +191,7 @@ class Events : public PluginBase { operator<<(std::ostream& str, Events::HealthComponentReport const& health_component_report); /** - * @brief + * @brief Health and arming check report type */ struct HealthAndArmingCheckReport { HealthAndArmingCheckMode @@ -221,17 +221,18 @@ class Events : public PluginBase { Events::HealthAndArmingCheckReport const& health_and_arming_check_report); /** - * @brief + * @brief Possible results returned */ enum class Result { - Success, /**< @brief. */ - NotAvailable, /**< @brief. */ - ConnectionError, /**< @brief. */ - Unsupported, /**< @brief. */ - Denied, /**< @brief. */ - Failed, /**< @brief. */ - Timeout, /**< @brief. */ - NoSystem, /**< @brief. */ + Success, /**< @brief Successful result. */ + NotAvailable, /**< @brief Not available. */ + ConnectionError, /**< @brief Connection error. */ + Unsupported, /**< @brief Unsupported. */ + Denied, /**< @brief Denied. */ + Failed, /**< @brief Failed. */ + Timeout, /**< @brief Timeout. */ + NoSystem, /**< @brief No system available. */ + Unknown, /**< @brief Unknown result. */ }; /** diff --git a/src/mavsdk/plugins/failure/include/plugins/failure/failure.h b/src/mavsdk/plugins/failure/include/plugins/failure/failure.h index 7a191e0373..bf7731eeda 100644 --- a/src/mavsdk/plugins/failure/include/plugins/failure/failure.h +++ b/src/mavsdk/plugins/failure/include/plugins/failure/failure.h @@ -138,7 +138,9 @@ class Failure : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result inject(FailureUnit failure_unit, FailureType failure_type, int32_t instance) const; diff --git a/src/mavsdk/plugins/follow_me/include/plugins/follow_me/follow_me.h b/src/mavsdk/plugins/follow_me/include/plugins/follow_me/follow_me.h index 65c84b7f9b..90472a8e35 100644 --- a/src/mavsdk/plugins/follow_me/include/plugins/follow_me/follow_me.h +++ b/src/mavsdk/plugins/follow_me/include/plugins/follow_me/follow_me.h @@ -186,7 +186,9 @@ class FollowMe : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_config(Config config) const; @@ -204,7 +206,9 @@ class FollowMe : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_target_location(TargetLocation location) const; @@ -222,7 +226,9 @@ class FollowMe : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result start() const; @@ -231,7 +237,9 @@ class FollowMe : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result stop() const; diff --git a/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h b/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h index 62ff3c9035..fe17b7c85c 100644 --- a/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h +++ b/src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h @@ -59,7 +59,7 @@ class Ftp : public PluginBase { ~Ftp() override; /** - * @brief + * @brief The output of a directory list */ struct ListDirectoryData { std::vector dirs{}; /**< @brief The found directories. */ @@ -192,7 +192,9 @@ class Ftp : public PluginBase { * * This function is blocking. See 'create_directory_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result create_directory(std::string remote_dir) const; @@ -208,7 +210,9 @@ class Ftp : public PluginBase { * * This function is blocking. See 'remove_directory_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result remove_directory(std::string remote_dir) const; @@ -224,7 +228,9 @@ class Ftp : public PluginBase { * * This function is blocking. See 'remove_file_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result remove_file(std::string remote_file_path) const; @@ -241,7 +247,9 @@ class Ftp : public PluginBase { * * This function is blocking. See 'rename_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result rename(std::string remote_from_path, std::string remote_to_path) const; @@ -275,7 +283,9 @@ class Ftp : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_target_compid(uint32_t compid) const; diff --git a/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h b/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h index 0a4e79cd9d..4f55583477 100644 --- a/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h +++ b/src/mavsdk/plugins/ftp_server/include/plugins/ftp_server/ftp_server.h @@ -77,7 +77,9 @@ class FtpServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_root_dir(std::string path) const; diff --git a/src/mavsdk/plugins/geofence/include/plugins/geofence/geofence.h b/src/mavsdk/plugins/geofence/include/plugins/geofence/geofence.h index 40b95d12d3..bb3571718c 100644 --- a/src/mavsdk/plugins/geofence/include/plugins/geofence/geofence.h +++ b/src/mavsdk/plugins/geofence/include/plugins/geofence/geofence.h @@ -202,11 +202,14 @@ class Geofence : public PluginBase { * @brief Upload geofences. * * Polygon and Circular geofences are uploaded to a drone. Once uploaded, the geofence will - * remain on the drone even if a connection is lost. + remain + * on the drone even if a connection is lost. * * This function is blocking. See 'upload_geofence_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result upload_geofence(GeofenceData geofence_data) const; @@ -222,7 +225,9 @@ class Geofence : public PluginBase { * * This function is blocking. See 'clear_geofence_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result clear_geofence() const; diff --git a/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h b/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h index 91b34bb272..21214fc12b 100644 --- a/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h +++ b/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h @@ -90,7 +90,7 @@ class Gimbal : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Gimbal::ControlMode const& control_mode); /** - * @brief + * @brief The send mode type */ enum class SendMode { Once, /**< @brief Send command exactly once with quality of service (use for sporadic @@ -356,7 +356,9 @@ class Gimbal : public PluginBase { * * This function is blocking. See 'set_angles_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_angles( int32_t gimbal_id, @@ -397,7 +399,9 @@ class Gimbal : public PluginBase { * * This function is blocking. See 'set_angular_rates_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_angular_rates( int32_t gimbal_id, @@ -436,7 +440,9 @@ class Gimbal : public PluginBase { * * This function is blocking. See 'set_roi_location_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_roi_location( int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m) const; @@ -470,7 +476,9 @@ class Gimbal : public PluginBase { * * This function is blocking. See 'take_control_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result take_control(int32_t gimbal_id, ControlMode control_mode) const; @@ -490,7 +498,9 @@ class Gimbal : public PluginBase { * * This function is blocking. See 'release_control_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result release_control(int32_t gimbal_id) const; diff --git a/src/mavsdk/plugins/gripper/include/plugins/gripper/gripper.h b/src/mavsdk/plugins/gripper/include/plugins/gripper/gripper.h index bd05937c25..f4cec369ef 100644 --- a/src/mavsdk/plugins/gripper/include/plugins/gripper/gripper.h +++ b/src/mavsdk/plugins/gripper/include/plugins/gripper/gripper.h @@ -114,7 +114,9 @@ class Gripper : public PluginBase { * * This function is blocking. See 'grab_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result grab(uint32_t instance) const; @@ -130,7 +132,9 @@ class Gripper : public PluginBase { * * This function is blocking. See 'release_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result release(uint32_t instance) const; diff --git a/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h b/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h index 43552a03d0..ae6cfa2311 100644 --- a/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h +++ b/src/mavsdk/plugins/log_files/include/plugins/log_files/log_files.h @@ -167,7 +167,9 @@ class LogFiles : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result erase_all_log_files() const; diff --git a/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h b/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h index 0a3f06b3fb..67a911dc43 100644 --- a/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h +++ b/src/mavsdk/plugins/log_streaming/include/plugins/log_streaming/log_streaming.h @@ -119,7 +119,9 @@ class LogStreaming : public PluginBase { * * This function is blocking. See 'start_log_streaming_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result start_log_streaming() const; @@ -135,7 +137,9 @@ class LogStreaming : public PluginBase { * * This function is blocking. See 'stop_log_streaming_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result stop_log_streaming() const; diff --git a/src/mavsdk/plugins/manual_control/include/plugins/manual_control/manual_control.h b/src/mavsdk/plugins/manual_control/include/plugins/manual_control/manual_control.h index b2ad772a0a..0b002cc486 100644 --- a/src/mavsdk/plugins/manual_control/include/plugins/manual_control/manual_control.h +++ b/src/mavsdk/plugins/manual_control/include/plugins/manual_control/manual_control.h @@ -103,9 +103,11 @@ class ManualControl : public PluginBase { * Requires a valid position using e.g. GPS, external vision, or optical flow. * * This function is blocking. See 'start_position_control_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result start_position_control() const; @@ -126,9 +128,11 @@ class ManualControl : public PluginBase { * Does not require a valid position e.g. GPS. * * This function is blocking. See 'start_altitude_control_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result start_altitude_control() const; @@ -140,7 +144,9 @@ class ManualControl : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_manual_control_input(float x, float y, float z, float r) const; diff --git a/src/mavsdk/plugins/mission/include/plugins/mission/mission.h b/src/mavsdk/plugins/mission/include/plugins/mission/mission.h index 3f0be00a7a..341592abf7 100644 --- a/src/mavsdk/plugins/mission/include/plugins/mission/mission.h +++ b/src/mavsdk/plugins/mission/include/plugins/mission/mission.h @@ -297,7 +297,9 @@ class Mission : public PluginBase { * * This function is blocking. See 'upload_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result upload_mission(MissionPlan mission_plan) const; @@ -320,7 +322,9 @@ class Mission : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result cancel_mission_upload() const; @@ -369,7 +373,9 @@ class Mission : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result cancel_mission_download() const; @@ -389,7 +395,9 @@ class Mission : public PluginBase { * * This function is blocking. See 'start_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result start_mission() const; @@ -415,7 +423,9 @@ class Mission : public PluginBase { * * This function is blocking. See 'pause_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result pause_mission() const; @@ -431,7 +441,9 @@ class Mission : public PluginBase { * * This function is blocking. See 'clear_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result clear_mission() const; @@ -458,9 +470,11 @@ class Mission : public PluginBase { * are used. * * This function is blocking. See 'set_current_mission_item_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_current_mission_item(int32_t index) const; @@ -520,7 +534,9 @@ class Mission : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_return_to_launch_after_mission(bool enable) const; diff --git a/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h b/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h index 4269c9ab2c..eb7643cc84 100644 --- a/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h +++ b/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h @@ -201,7 +201,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. See 'upload_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result upload_mission(std::vector mission_items) const; @@ -218,7 +220,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. See 'upload_geofence_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result upload_geofence(std::vector mission_items) const; @@ -235,7 +239,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. See 'upload_rally_points_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result upload_rally_points(std::vector mission_items) const; @@ -244,7 +250,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result cancel_mission_upload() const; @@ -316,7 +324,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result cancel_mission_download() const; @@ -336,7 +346,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. See 'start_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result start_mission() const; @@ -362,7 +374,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. See 'pause_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result pause_mission() const; @@ -378,7 +392,9 @@ class MissionRaw : public PluginBase { * * This function is blocking. See 'clear_mission_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result clear_mission() const; @@ -399,9 +415,11 @@ class MissionRaw : public PluginBase { * to a specific index of a raw mission item, the mission will be set to this item. * * This function is blocking. See 'set_current_mission_item_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_current_mission_item(int32_t index) const; @@ -443,8 +461,7 @@ class MissionRaw : public PluginBase { using MissionChangedHandle = Handle; /** - * @brief * - * Subscribes to mission changed. + * @brief Subscribes to mission changed. * * This notification can be used to be informed if a ground station has * been uploaded or changed by a ground station or companion computer. diff --git a/src/mavsdk/plugins/mission_raw_server/include/plugins/mission_raw_server/mission_raw_server.h b/src/mavsdk/plugins/mission_raw_server/include/plugins/mission_raw_server/mission_raw_server.h index 25c20e69f8..c45b5c149f 100644 --- a/src/mavsdk/plugins/mission_raw_server/include/plugins/mission_raw_server/mission_raw_server.h +++ b/src/mavsdk/plugins/mission_raw_server/include/plugins/mission_raw_server/mission_raw_server.h @@ -211,7 +211,7 @@ class MissionRawServer : public ServerPluginBase { * * This function is blocking. * - * @return Result of request. + */ void set_current_item_complete() const; diff --git a/src/mavsdk/plugins/mocap/include/plugins/mocap/mocap.h b/src/mavsdk/plugins/mocap/include/plugins/mocap/mocap.h index b058b388ec..a6d16e9bbf 100644 --- a/src/mavsdk/plugins/mocap/include/plugins/mocap/mocap.h +++ b/src/mavsdk/plugins/mocap/include/plugins/mocap/mocap.h @@ -23,8 +23,7 @@ class System; class MocapImpl; /** - * @brief * - * Allows interfacing a vehicle with a motion capture system in + * @brief Allows interfacing a vehicle with a motion capture system in * order to allow navigation without global positioning sources available * (e.g. indoors, or when flying under a bridge. etc.). */ @@ -343,7 +342,9 @@ class Mocap : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_vision_position_estimate(VisionPositionEstimate vision_position_estimate) const; @@ -352,7 +353,9 @@ class Mocap : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_attitude_position_mocap(AttitudePositionMocap attitude_position_mocap) const; @@ -361,7 +364,9 @@ class Mocap : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_odometry(Odometry odometry) const; diff --git a/src/mavsdk/plugins/offboard/include/plugins/offboard/offboard.h b/src/mavsdk/plugins/offboard/include/plugins/offboard/offboard.h index ba1e0f2589..81ca24fab9 100644 --- a/src/mavsdk/plugins/offboard/include/plugins/offboard/offboard.h +++ b/src/mavsdk/plugins/offboard/include/plugins/offboard/offboard.h @@ -23,8 +23,7 @@ class System; class OffboardImpl; /** - * @brief * - * Control a drone with position, velocity, attitude or motor commands. + * @brief Control a drone with position, velocity, attitude or motor commands. * * The module is called offboard because the commands can be sent from external sources * as opposed to onboard control right inside the autopilot "board". @@ -370,7 +369,9 @@ class Offboard : public PluginBase { * * This function is blocking. See 'start_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result start() const; @@ -390,7 +391,9 @@ class Offboard : public PluginBase { * * This function is blocking. See 'stop_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result stop() const; @@ -411,7 +414,9 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_attitude(Attitude attitude) const; @@ -423,7 +428,9 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_actuator_control(ActuatorControl actuator_control) const; @@ -432,7 +439,9 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_attitude_rate(AttitudeRate attitude_rate) const; @@ -441,7 +450,9 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_position_ned(PositionNedYaw position_ned_yaw) const; @@ -450,17 +461,21 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_position_global(PositionGlobalYaw position_global_yaw) const; /** * @brief Set the velocity in body coordinates and yaw angular rate. Not available for - * fixed-wing aircraft. + fixed-wing aircraft. * * This function is blocking. * + * @return Result of request. + */ Result set_velocity_body(VelocityBodyYawspeed velocity_body_yawspeed) const; @@ -469,7 +484,9 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_velocity_ned(VelocityNedYaw velocity_ned_yaw) const; @@ -478,18 +495,22 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_position_velocity_ned( PositionNedYaw position_ned_yaw, VelocityNedYaw velocity_ned_yaw) const; /** * @brief Set the position, velocity and acceleration in NED coordinates, with velocity and - * acceleration used as feed-forward. + acceleration used as feed-forward. * * This function is blocking. * + * @return Result of request. + */ Result set_position_velocity_acceleration_ned( PositionNedYaw position_ned_yaw, @@ -501,7 +522,9 @@ class Offboard : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_acceleration_ned(AccelerationNed acceleration_ned) const; diff --git a/src/mavsdk/plugins/param/include/plugins/param/param.h b/src/mavsdk/plugins/param/include/plugins/param/param.h index 67e07e35ab..89f25cafef 100644 --- a/src/mavsdk/plugins/param/include/plugins/param/param.h +++ b/src/mavsdk/plugins/param/include/plugins/param/param.h @@ -211,7 +211,9 @@ class Param : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_param_int(std::string name, int32_t value) const; @@ -233,7 +235,9 @@ class Param : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_param_float(std::string name, float value) const; @@ -255,7 +259,9 @@ class Param : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_param_custom(std::string name, std::string value) const; @@ -275,7 +281,9 @@ class Param : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result select_component(int32_t component_id, ProtocolVersion protocol_version) const; diff --git a/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h b/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h index 81768b7a29..6753db5f63 100644 --- a/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h +++ b/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h @@ -173,7 +173,9 @@ class ParamServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result set_protocol(bool extended_protocol) const; @@ -195,7 +197,9 @@ class ParamServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result provide_param_int(std::string name, int32_t value) const; @@ -217,7 +221,9 @@ class ParamServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result provide_param_float(std::string name, float value) const; @@ -239,7 +245,9 @@ class ParamServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result provide_param_custom(std::string name, std::string value) const; diff --git a/src/mavsdk/plugins/rtk/include/plugins/rtk/rtk.h b/src/mavsdk/plugins/rtk/include/plugins/rtk/rtk.h index d21175f3e7..29ac24566a 100644 --- a/src/mavsdk/plugins/rtk/include/plugins/rtk/rtk.h +++ b/src/mavsdk/plugins/rtk/include/plugins/rtk/rtk.h @@ -107,7 +107,9 @@ class Rtk : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result send_rtcm_data(RtcmData rtcm_data) const; diff --git a/src/mavsdk/plugins/server_utility/include/plugins/server_utility/server_utility.h b/src/mavsdk/plugins/server_utility/include/plugins/server_utility/server_utility.h index 29fa3e9348..e8634a2c0a 100644 --- a/src/mavsdk/plugins/server_utility/include/plugins/server_utility/server_utility.h +++ b/src/mavsdk/plugins/server_utility/include/plugins/server_utility/server_utility.h @@ -109,7 +109,9 @@ class ServerUtility : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result send_status_text(StatusTextType type, std::string text) const; diff --git a/src/mavsdk/plugins/shell/include/plugins/shell/shell.h b/src/mavsdk/plugins/shell/include/plugins/shell/shell.h index 90647c6768..e96b77699a 100644 --- a/src/mavsdk/plugins/shell/include/plugins/shell/shell.h +++ b/src/mavsdk/plugins/shell/include/plugins/shell/shell.h @@ -23,8 +23,7 @@ class System; class ShellImpl; /** - * @brief * - * Allow to communicate with the vehicle's system shell. + * @brief Allow to communicate with the vehicle's system shell. */ class Shell : public PluginBase { public: @@ -88,7 +87,9 @@ class Shell : public PluginBase { * * This function is blocking. * + * @return Result of request. + */ Result send(std::string command) const; diff --git a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h index d4ea624ddd..72876bb454 100644 --- a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -1906,7 +1906,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_position_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_position(double rate_hz) const; @@ -1922,7 +1924,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_home_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_home(double rate_hz) const; @@ -1938,7 +1942,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_in_air_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_in_air(double rate_hz) const; @@ -1953,9 +1959,11 @@ class Telemetry : public PluginBase { * @brief Set rate to landed state updates * * This function is blocking. See 'set_rate_landed_state_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_landed_state(double rate_hz) const; @@ -1971,7 +1979,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_vtol_state_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_vtol_state(double rate_hz) const; @@ -1987,9 +1997,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'attitude euler angle' updates. * * This function is blocking. See 'set_rate_attitude_quaternion_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_attitude_quaternion(double rate_hz) const; @@ -2004,9 +2016,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'attitude quaternion' updates. * * This function is blocking. See 'set_rate_attitude_euler_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_attitude_euler(double rate_hz) const; @@ -2023,9 +2037,11 @@ class Telemetry : public PluginBase { * Set rate to 'ground speed' updates (NED). * * This function is blocking. See 'set_rate_velocity_ned_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_velocity_ned(double rate_hz) const; @@ -2041,7 +2057,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_gps_info_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_gps_info(double rate_hz) const; @@ -2057,7 +2075,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_battery_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_battery(double rate_hz) const; @@ -2073,7 +2093,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_rc_status_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_rc_status(double rate_hz) const; @@ -2089,9 +2111,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'actuator control target' updates. * * This function is blocking. See 'set_rate_actuator_control_target_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_actuator_control_target(double rate_hz) const; @@ -2107,9 +2131,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'actuator output status' updates. * * This function is blocking. See 'set_rate_actuator_output_status_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_actuator_output_status(double rate_hz) const; @@ -2125,7 +2151,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_odometry_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_odometry(double rate_hz) const; @@ -2141,9 +2169,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'position velocity' updates. * * This function is blocking. See 'set_rate_position_velocity_ned_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_position_velocity_ned(double rate_hz) const; @@ -2158,9 +2188,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'ground truth' updates. * * This function is blocking. See 'set_rate_ground_truth_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_ground_truth(double rate_hz) const; @@ -2175,9 +2207,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'fixedwing metrics' updates. * * This function is blocking. See 'set_rate_fixedwing_metrics_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_fixedwing_metrics(double rate_hz) const; @@ -2193,7 +2227,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_imu_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_imu(double rate_hz) const; @@ -2209,7 +2245,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_scaled_imu_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_scaled_imu(double rate_hz) const; @@ -2225,7 +2263,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_raw_imu_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_raw_imu(double rate_hz) const; @@ -2240,9 +2280,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'unix epoch time' updates. * * This function is blocking. See 'set_rate_unix_epoch_time_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_unix_epoch_time(double rate_hz) const; @@ -2257,9 +2299,11 @@ class Telemetry : public PluginBase { * @brief Set rate to 'Distance Sensor' updates. * * This function is blocking. See 'set_rate_distance_sensor_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result set_rate_distance_sensor(double rate_hz) const; @@ -2275,7 +2319,9 @@ class Telemetry : public PluginBase { * * This function is blocking. See 'set_rate_altitude_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_altitude(double rate_hz) const; diff --git a/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h b/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h index 7ffd54e84f..b6f049dcbb 100644 --- a/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h +++ b/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h @@ -920,7 +920,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_position(Position position, VelocityNed velocity_ned, Heading heading) const; @@ -929,7 +931,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_home(Position home) const; @@ -938,7 +942,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_sys_status( Battery battery, @@ -953,7 +959,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_extended_sys_state(VtolState vtol_state, LandedState landed_state) const; @@ -962,7 +970,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_raw_gps(RawGps raw_gps, GpsInfo gps_info) const; @@ -971,7 +981,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_battery(Battery battery) const; @@ -980,7 +992,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_status_text(StatusText status_text) const; @@ -989,7 +1003,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_odometry(Odometry odometry) const; @@ -998,7 +1014,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_position_velocity_ned(PositionVelocityNed position_velocity_ned) const; @@ -1007,7 +1025,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_ground_truth(GroundTruth ground_truth) const; @@ -1016,7 +1036,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_imu(Imu imu) const; @@ -1025,7 +1047,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_scaled_imu(Imu imu) const; @@ -1034,7 +1058,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_raw_imu(Imu imu) const; @@ -1043,7 +1069,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_unix_epoch_time(uint64_t time_us) const; @@ -1052,7 +1080,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_distance_sensor(DistanceSensor distance_sensor) const; @@ -1061,7 +1091,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_attitude(EulerAngle angle, AngularVelocityBody angular_velocity) const; @@ -1070,7 +1102,9 @@ class TelemetryServer : public ServerPluginBase { * * This function is blocking. * + * @return Result of request. + */ Result publish_visual_flight_rules_hud(FixedwingMetrics fixed_wing_metrics) const; diff --git a/src/mavsdk/plugins/transponder/include/plugins/transponder/transponder.h b/src/mavsdk/plugins/transponder/include/plugins/transponder/transponder.h index 7da52a261d..65fcd36816 100644 --- a/src/mavsdk/plugins/transponder/include/plugins/transponder/transponder.h +++ b/src/mavsdk/plugins/transponder/include/plugins/transponder/transponder.h @@ -209,7 +209,9 @@ class Transponder : public PluginBase { * * This function is blocking. See 'set_rate_transponder_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result set_rate_transponder(double rate_hz) const; diff --git a/src/mavsdk/plugins/tune/include/plugins/tune/tune.h b/src/mavsdk/plugins/tune/include/plugins/tune/tune.h index c2ef960115..d2d61a0b41 100644 --- a/src/mavsdk/plugins/tune/include/plugins/tune/tune.h +++ b/src/mavsdk/plugins/tune/include/plugins/tune/tune.h @@ -152,7 +152,9 @@ class Tune : public PluginBase { * * This function is blocking. See 'play_tune_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result play_tune(TuneDescription tune_description) const; diff --git a/src/mavsdk/plugins/winch/include/plugins/winch/winch.h b/src/mavsdk/plugins/winch/include/plugins/winch/winch.h index 2191127bf3..9966232076 100644 --- a/src/mavsdk/plugins/winch/include/plugins/winch/winch.h +++ b/src/mavsdk/plugins/winch/include/plugins/winch/winch.h @@ -221,7 +221,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'relax_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result relax(uint32_t instance) const; @@ -237,9 +239,11 @@ class Winch : public PluginBase { * @brief Wind or unwind specified length of line, optionally using specified rate. * * This function is blocking. See 'relative_length_control_async' for the non-blocking - * counterpart. + counterpart. * + * @return Result of request. + */ Result relative_length_control(uint32_t instance, float length_m, float rate_m_s) const; @@ -255,7 +259,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'rate_control_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result rate_control(uint32_t instance, float rate_m_s) const; @@ -271,7 +277,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'lock_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result lock(uint32_t instance) const; @@ -287,7 +295,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'deliver_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result deliver(uint32_t instance) const; @@ -303,7 +313,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'hold_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result hold(uint32_t instance) const; @@ -319,7 +331,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'retract_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result retract(uint32_t instance) const; @@ -337,11 +351,13 @@ class Winch : public PluginBase { * @brief Load the reel with line. * * The winch will calculate the total loaded length and stop when the tension exceeds a - * threshold. + threshold. * * This function is blocking. See 'load_line_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result load_line(uint32_t instance) const; @@ -357,7 +373,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'abandon_line_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result abandon_line(uint32_t instance) const; @@ -373,7 +391,9 @@ class Winch : public PluginBase { * * This function is blocking. See 'load_payload_async' for the non-blocking counterpart. * + * @return Result of request. + */ Result load_payload(uint32_t instance) const; diff --git a/src/mavsdk_server/src/generated/arm_authorizer_server/arm_authorizer_server.grpc.pb.h b/src/mavsdk_server/src/generated/arm_authorizer_server/arm_authorizer_server.grpc.pb.h index f33c4a664c..ac07971289 100644 --- a/src/mavsdk_server/src/generated/arm_authorizer_server/arm_authorizer_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/arm_authorizer_server/arm_authorizer_server.grpc.pb.h @@ -29,6 +29,7 @@ namespace mavsdk { namespace rpc { namespace arm_authorizer_server { +// Use arm authorization. class ArmAuthorizerServerService final { public: static constexpr char const* service_full_name() { diff --git a/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc index 9c1c269530..dd2bbe64ee 100644 --- a/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc +++ b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.cc @@ -304,6 +304,14 @@ const ::uint32_t ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestComponentRequest, _impl_.compid_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestComponentResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::GetMetadataRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -345,14 +353,6 @@ const ::uint32_t PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::ComponentMetadataResult, _impl_.result_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::ComponentMetadataResult, _impl_.result_str_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestComponentResponse, _internal_metadata_), - ~0u, // no _extensions_ - ~0u, // no _oneof_case_ - ~0u, // no _weak_field_map_ - ~0u, // no _inlined_string_donated_ - ~0u, // no _split_ - ~0u, // no sizeof(Split) - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -402,11 +402,11 @@ const ::uint32_t static const ::_pbi::MigrationSchema schemas[] ABSL_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { {0, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestComponentRequest)}, - {9, -1, -1, sizeof(::mavsdk::rpc::component_metadata::GetMetadataRequest)}, - {19, 29, -1, sizeof(::mavsdk::rpc::component_metadata::GetMetadataResponse)}, - {31, -1, -1, sizeof(::mavsdk::rpc::component_metadata::MetadataData)}, - {40, -1, -1, sizeof(::mavsdk::rpc::component_metadata::ComponentMetadataResult)}, - {50, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestComponentResponse)}, + {9, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestComponentResponse)}, + {17, -1, -1, sizeof(::mavsdk::rpc::component_metadata::GetMetadataRequest)}, + {27, 37, -1, sizeof(::mavsdk::rpc::component_metadata::GetMetadataResponse)}, + {39, -1, -1, sizeof(::mavsdk::rpc::component_metadata::MetadataData)}, + {48, -1, -1, sizeof(::mavsdk::rpc::component_metadata::ComponentMetadataResult)}, {58, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestAutopilotComponentRequest)}, {66, -1, -1, sizeof(::mavsdk::rpc::component_metadata::RequestAutopilotComponentResponse)}, {74, -1, -1, sizeof(::mavsdk::rpc::component_metadata::SubscribeMetadataAvailableRequest)}, @@ -415,11 +415,11 @@ static const ::_pbi::MigrationSchema }; static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::component_metadata::_RequestComponentRequest_default_instance_._instance, + &::mavsdk::rpc::component_metadata::_RequestComponentResponse_default_instance_._instance, &::mavsdk::rpc::component_metadata::_GetMetadataRequest_default_instance_._instance, &::mavsdk::rpc::component_metadata::_GetMetadataResponse_default_instance_._instance, &::mavsdk::rpc::component_metadata::_MetadataData_default_instance_._instance, &::mavsdk::rpc::component_metadata::_ComponentMetadataResult_default_instance_._instance, - &::mavsdk::rpc::component_metadata::_RequestComponentResponse_default_instance_._instance, &::mavsdk::rpc::component_metadata::_RequestAutopilotComponentRequest_default_instance_._instance, &::mavsdk::rpc::component_metadata::_RequestAutopilotComponentResponse_default_instance_._instance, &::mavsdk::rpc::component_metadata::_SubscribeMetadataAvailableRequest_default_instance_._instance, @@ -431,24 +431,24 @@ const char descriptor_table_protodef_component_5fmetadata_2fcomponent_5fmetadata "\n+component_metadata/component_metadata." "proto\022\035mavsdk.rpc.component_metadata\032\024ma" "vsdk_options.proto\")\n\027RequestComponentRe" - "quest\022\016\n\006compid\030\001 \001(\r\"h\n\022GetMetadataRequ" - "est\022\016\n\006compid\030\001 \001(\r\022B\n\rmetadata_type\030\002 \001" - "(\0162+.mavsdk.rpc.component_metadata.Metad" - "ataType\"\257\001\n\023GetMetadataResponse\022Y\n\031compo" - "nent_metadata_result\030\001 \001(\01326.mavsdk.rpc." - "component_metadata.ComponentMetadataResu" - "lt\022=\n\010response\030\002 \001(\0132+.mavsdk.rpc.compon" - "ent_metadata.MetadataData\"%\n\014MetadataDat" - "a\022\025\n\rjson_metadata\030\001 \001(\t\"\324\002\n\027ComponentMe" - "tadataResult\022M\n\006result\030\001 \001(\0162=.mavsdk.rp" - "c.component_metadata.ComponentMetadataRe" - "sult.Result\022\022\n\nresult_str\030\002 \001(\t\"\325\001\n\006Resu" - "lt\022\022\n\016RESULT_SUCCESS\020\000\022\030\n\024RESULT_NOT_AVA" - "ILABLE\020\001\022\033\n\027RESULT_CONNECTION_ERROR\020\002\022\026\n" - "\022RESULT_UNSUPPORTED\020\003\022\021\n\rRESULT_DENIED\020\004" - "\022\021\n\rRESULT_FAILED\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022" - "\024\n\020RESULT_NO_SYSTEM\020\007\022\030\n\024RESULT_NOT_REQU" - "ESTED\020\010\"\032\n\030RequestComponentResponse\"\"\n R" + "quest\022\016\n\006compid\030\001 \001(\r\"\032\n\030RequestComponen" + "tResponse\"h\n\022GetMetadataRequest\022\016\n\006compi" + "d\030\001 \001(\r\022B\n\rmetadata_type\030\002 \001(\0162+.mavsdk." + "rpc.component_metadata.MetadataType\"\257\001\n\023" + "GetMetadataResponse\022Y\n\031component_metadat" + "a_result\030\001 \001(\01326.mavsdk.rpc.component_me" + "tadata.ComponentMetadataResult\022=\n\010respon" + "se\030\002 \001(\0132+.mavsdk.rpc.component_metadata" + ".MetadataData\"%\n\014MetadataData\022\025\n\rjson_me" + "tadata\030\001 \001(\t\"\324\002\n\027ComponentMetadataResult" + "\022M\n\006result\030\001 \001(\0162=.mavsdk.rpc.component_" + "metadata.ComponentMetadataResult.Result\022" + "\022\n\nresult_str\030\002 \001(\t\"\325\001\n\006Result\022\022\n\016RESULT" + "_SUCCESS\020\000\022\030\n\024RESULT_NOT_AVAILABLE\020\001\022\033\n\027" + "RESULT_CONNECTION_ERROR\020\002\022\026\n\022RESULT_UNSU" + "PPORTED\020\003\022\021\n\rRESULT_DENIED\020\004\022\021\n\rRESULT_F" + "AILED\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\024\n\020RESULT_NO" + "_SYSTEM\020\007\022\030\n\024RESULT_NOT_REQUESTED\020\010\"\"\n R" "equestAutopilotComponentRequest\"#\n!Reque" "stAutopilotComponentResponse\"#\n!Subscrib" "eMetadataAvailableRequest\"X\n\031MetadataAva" @@ -748,6 +748,109 @@ ::google::protobuf::Metadata RequestComponentRequest::GetMetadata() const { } // =================================================================== +class RequestComponentResponse::_Internal { + public: +}; + +RequestComponentResponse::RequestComponentResponse(::google::protobuf::Arena* arena) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::internal::ZeroFieldsBase(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::internal::ZeroFieldsBase(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.RequestComponentResponse) +} +RequestComponentResponse::RequestComponentResponse( + ::google::protobuf::Arena* arena, + const RequestComponentResponse& from) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::internal::ZeroFieldsBase(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::internal::ZeroFieldsBase(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + RequestComponentResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.RequestComponentResponse) +} + +inline void* RequestComponentResponse::PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena) { + return ::new (mem) RequestComponentResponse(arena); +} +constexpr auto RequestComponentResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(RequestComponentResponse), + alignof(RequestComponentResponse)); +} +PROTOBUF_CONSTINIT +PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::google::protobuf::internal::ClassDataFull RequestComponentResponse::_class_data_ = { + ::google::protobuf::internal::ClassData{ + &_RequestComponentResponse_default_instance_._instance, + &_table_.header, + nullptr, // OnDemandRegisterArenaDtor + nullptr, // IsInitialized + &RequestComponentResponse::MergeImpl, + ::google::protobuf::internal::ZeroFieldsBase::GetNewImpl(), +#if defined(PROTOBUF_CUSTOM_VTABLE) + &RequestComponentResponse::SharedDtor, + ::google::protobuf::internal::ZeroFieldsBase::GetClearImpl(), &RequestComponentResponse::ByteSizeLong, + &RequestComponentResponse::_InternalSerialize, +#endif // PROTOBUF_CUSTOM_VTABLE + PROTOBUF_FIELD_OFFSET(RequestComponentResponse, _impl_._cached_size_), + false, + }, + &RequestComponentResponse::kDescriptorMethods, + &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto, + nullptr, // tracker +}; +const ::google::protobuf::internal::ClassData* RequestComponentResponse::GetClassData() const { + ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); + ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); + return _class_data_.base(); +} +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 0, 0, 0, 2> RequestComponentResponse::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 0, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967295, // skipmap + offsetof(decltype(_table_), field_names), // no field_entries + 0, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + _class_data_.base(), + nullptr, // post_loop_handler + ::_pbi::TcParser::GenericFallback, // fallback + #ifdef PROTOBUF_PREFETCH_PARSE_TABLE + ::_pbi::TcParser::GetTable<::mavsdk::rpc::component_metadata::RequestComponentResponse>(), // to_prefetch + #endif // PROTOBUF_PREFETCH_PARSE_TABLE + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + }}, {{ + 65535, 65535 + }}, + // no field_entries, or aux_entries + {{ + }}, +}; + + + + + + + + +::google::protobuf::Metadata RequestComponentResponse::GetMetadata() const { + return ::google::protobuf::internal::ZeroFieldsBase::GetMetadataImpl(GetClassData()->full()); +} +// =================================================================== + class GetMetadataRequest::_Internal { public: }; @@ -1778,109 +1881,6 @@ ::google::protobuf::Metadata ComponentMetadataResult::GetMetadata() const { } // =================================================================== -class RequestComponentResponse::_Internal { - public: -}; - -RequestComponentResponse::RequestComponentResponse(::google::protobuf::Arena* arena) -#if defined(PROTOBUF_CUSTOM_VTABLE) - : ::google::protobuf::internal::ZeroFieldsBase(arena, _class_data_.base()) { -#else // PROTOBUF_CUSTOM_VTABLE - : ::google::protobuf::internal::ZeroFieldsBase(arena) { -#endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.component_metadata.RequestComponentResponse) -} -RequestComponentResponse::RequestComponentResponse( - ::google::protobuf::Arena* arena, - const RequestComponentResponse& from) -#if defined(PROTOBUF_CUSTOM_VTABLE) - : ::google::protobuf::internal::ZeroFieldsBase(arena, _class_data_.base()) { -#else // PROTOBUF_CUSTOM_VTABLE - : ::google::protobuf::internal::ZeroFieldsBase(arena) { -#endif // PROTOBUF_CUSTOM_VTABLE - RequestComponentResponse* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.component_metadata.RequestComponentResponse) -} - -inline void* RequestComponentResponse::PlacementNew_(const void*, void* mem, - ::google::protobuf::Arena* arena) { - return ::new (mem) RequestComponentResponse(arena); -} -constexpr auto RequestComponentResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(RequestComponentResponse), - alignof(RequestComponentResponse)); -} -PROTOBUF_CONSTINIT -PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull RequestComponentResponse::_class_data_ = { - ::google::protobuf::internal::ClassData{ - &_RequestComponentResponse_default_instance_._instance, - &_table_.header, - nullptr, // OnDemandRegisterArenaDtor - nullptr, // IsInitialized - &RequestComponentResponse::MergeImpl, - ::google::protobuf::internal::ZeroFieldsBase::GetNewImpl(), -#if defined(PROTOBUF_CUSTOM_VTABLE) - &RequestComponentResponse::SharedDtor, - ::google::protobuf::internal::ZeroFieldsBase::GetClearImpl(), &RequestComponentResponse::ByteSizeLong, - &RequestComponentResponse::_InternalSerialize, -#endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(RequestComponentResponse, _impl_._cached_size_), - false, - }, - &RequestComponentResponse::kDescriptorMethods, - &descriptor_table_component_5fmetadata_2fcomponent_5fmetadata_2eproto, - nullptr, // tracker -}; -const ::google::protobuf::internal::ClassData* RequestComponentResponse::GetClassData() const { - ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); - ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); - return _class_data_.base(); -} -PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 0, 0, 0, 2> RequestComponentResponse::_table_ = { - { - 0, // no _has_bits_ - 0, // no _extensions_ - 0, 0, // max_field_number, fast_idx_mask - offsetof(decltype(_table_), field_lookup_table), - 4294967295, // skipmap - offsetof(decltype(_table_), field_names), // no field_entries - 0, // num_field_entries - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - _class_data_.base(), - nullptr, // post_loop_handler - ::_pbi::TcParser::GenericFallback, // fallback - #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::component_metadata::RequestComponentResponse>(), // to_prefetch - #endif // PROTOBUF_PREFETCH_PARSE_TABLE - }, {{ - {::_pbi::TcParser::MiniParse, {}}, - }}, {{ - 65535, 65535 - }}, - // no field_entries, or aux_entries - {{ - }}, -}; - - - - - - - - -::google::protobuf::Metadata RequestComponentResponse::GetMetadata() const { - return ::google::protobuf::internal::ZeroFieldsBase::GetMetadataImpl(GetClassData()->full()); -} -// =================================================================== - class RequestAutopilotComponentRequest::_Internal { public: }; diff --git a/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h index 084defe499..3d01e227ce 100644 --- a/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h +++ b/src/mavsdk_server/src/generated/component_metadata/component_metadata.pb.h @@ -387,7 +387,7 @@ class RequestComponentResponse final return reinterpret_cast( &_RequestComponentResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 5; + static constexpr int kIndexInFileMessages = 1; friend void swap(RequestComponentResponse& a, RequestComponentResponse& b) { a.Swap(&b); } inline void Swap(RequestComponentResponse* other) { if (other == this) return; @@ -1238,7 +1238,7 @@ class MetadataData final return reinterpret_cast( &_MetadataData_default_instance_); } - static constexpr int kIndexInFileMessages = 3; + static constexpr int kIndexInFileMessages = 4; friend void swap(MetadataData& a, MetadataData& b) { a.Swap(&b); } inline void Swap(MetadataData* other) { if (other == this) return; @@ -1435,7 +1435,7 @@ class GetMetadataRequest final return reinterpret_cast( &_GetMetadataRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 1; + static constexpr int kIndexInFileMessages = 2; friend void swap(GetMetadataRequest& a, GetMetadataRequest& b) { a.Swap(&b); } inline void Swap(GetMetadataRequest* other) { if (other == this) return; @@ -1638,7 +1638,7 @@ class ComponentMetadataResult final return reinterpret_cast( &_ComponentMetadataResult_default_instance_); } - static constexpr int kIndexInFileMessages = 4; + static constexpr int kIndexInFileMessages = 5; friend void swap(ComponentMetadataResult& a, ComponentMetadataResult& b) { a.Swap(&b); } inline void Swap(ComponentMetadataResult* other) { if (other == this) return; @@ -2070,7 +2070,7 @@ class GetMetadataResponse final return reinterpret_cast( &_GetMetadataResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 2; + static constexpr int kIndexInFileMessages = 3; friend void swap(GetMetadataResponse& a, GetMetadataResponse& b) { a.Swap(&b); } inline void Swap(GetMetadataResponse* other) { if (other == this) return; @@ -2263,6 +2263,10 @@ inline void RequestComponentRequest::_internal_set_compid(::uint32_t value) { // ------------------------------------------------------------------- +// RequestComponentResponse + +// ------------------------------------------------------------------- + // GetMetadataRequest // uint32 compid = 1; @@ -2633,10 +2637,6 @@ inline void ComponentMetadataResult::set_allocated_result_str(std::string* value // ------------------------------------------------------------------- -// RequestComponentResponse - -// ------------------------------------------------------------------- - // RequestAutopilotComponentRequest // ------------------------------------------------------------------- diff --git a/src/mavsdk_server/src/generated/events/events.pb.cc b/src/mavsdk_server/src/generated/events/events.pb.cc index a8be93a821..778c5447f1 100644 --- a/src/mavsdk_server/src/generated/events/events.pb.cc +++ b/src/mavsdk_server/src/generated/events/events.pb.cc @@ -539,41 +539,42 @@ const char descriptor_table_protodef_events_2fevents_2eproto[] ABSL_ATTRIBUTE_SE "ode\022C\n\021health_components\030\002 \003(\0132(.mavsdk." "rpc.events.HealthComponentReport\022D\n\014all_" "problems\030\003 \003(\0132..mavsdk.rpc.events.Healt" - "hAndArmingCheckProblem\"\230\002\n\014EventsResult\022" + "hAndArmingCheckProblem\"\254\002\n\014EventsResult\022" "6\n\006result\030\001 \001(\0162&.mavsdk.rpc.events.Even" - "tsResult.Result\022\022\n\nresult_str\030\002 \001(\t\"\273\001\n\006" + "tsResult.Result\022\022\n\nresult_str\030\002 \001(\t\"\317\001\n\006" "Result\022\022\n\016RESULT_SUCCESS\020\000\022\030\n\024RESULT_NOT" "_AVAILABLE\020\001\022\033\n\027RESULT_CONNECTION_ERROR\020" "\002\022\026\n\022RESULT_UNSUPPORTED\020\003\022\021\n\rRESULT_DENI" "ED\020\004\022\021\n\rRESULT_FAILED\020\005\022\022\n\016RESULT_TIMEOU" - "T\020\006\022\024\n\020RESULT_NO_SYSTEM\020\007\"\030\n\026SubscribeEv" - "entsRequest\"9\n\016EventsResponse\022\'\n\005event\030\001" - " \001(\0132\030.mavsdk.rpc.events.Event\"\'\n%Subscr" - "ibeHealthAndArmingChecksRequest\"^\n\035Healt" - "hAndArmingChecksResponse\022=\n\006report\030\001 \001(\013" - "2-.mavsdk.rpc.events.HealthAndArmingChec" - "kReport\"\'\n%GetHealthAndArmingChecksRepor" - "tRequest\"\237\001\n&GetHealthAndArmingChecksRep" - "ortResponse\0226\n\revents_result\030\001 \001(\0132\037.mav" - "sdk.rpc.events.EventsResult\022=\n\006report\030\002 " - "\001(\0132-.mavsdk.rpc.events.HealthAndArmingC" - "heckReport*\273\001\n\010LogLevel\022\027\n\023LOG_LEVEL_EME" - "RGENCY\020\000\022\023\n\017LOG_LEVEL_ALERT\020\001\022\026\n\022LOG_LEV" - "EL_CRITICAL\020\002\022\023\n\017LOG_LEVEL_ERROR\020\003\022\025\n\021LO" - "G_LEVEL_WARNING\020\004\022\024\n\020LOG_LEVEL_NOTICE\020\005\022" - "\022\n\016LOG_LEVEL_INFO\020\006\022\023\n\017LOG_LEVEL_DEBUG\020\007" - "2\255\003\n\rEventsService\022g\n\017SubscribeEvents\022)." - "mavsdk.rpc.events.SubscribeEventsRequest" - "\032!.mavsdk.rpc.events.EventsResponse\"\004\200\265\030" - "\0000\001\022\224\001\n\036SubscribeHealthAndArmingChecks\0228" - ".mavsdk.rpc.events.SubscribeHealthAndArm" - "ingChecksRequest\0320.mavsdk.rpc.events.Hea" - "lthAndArmingChecksResponse\"\004\200\265\030\0000\001\022\233\001\n\036G" - "etHealthAndArmingChecksReport\0228.mavsdk.r" - "pc.events.GetHealthAndArmingChecksReport" - "Request\0329.mavsdk.rpc.events.GetHealthAnd" - "ArmingChecksReportResponse\"\004\200\265\030\001B\037\n\020io.m" - "avsdk.eventsB\013EventsProtob\006proto3" + "T\020\006\022\024\n\020RESULT_NO_SYSTEM\020\007\022\022\n\016RESULT_UNKN" + "OWN\020\010\"\030\n\026SubscribeEventsRequest\"9\n\016Event" + "sResponse\022\'\n\005event\030\001 \001(\0132\030.mavsdk.rpc.ev" + "ents.Event\"\'\n%SubscribeHealthAndArmingCh" + "ecksRequest\"^\n\035HealthAndArmingChecksResp" + "onse\022=\n\006report\030\001 \001(\0132-.mavsdk.rpc.events" + ".HealthAndArmingCheckReport\"\'\n%GetHealth" + "AndArmingChecksReportRequest\"\237\001\n&GetHeal" + "thAndArmingChecksReportResponse\0226\n\revent" + "s_result\030\001 \001(\0132\037.mavsdk.rpc.events.Event" + "sResult\022=\n\006report\030\002 \001(\0132-.mavsdk.rpc.eve" + "nts.HealthAndArmingCheckReport*\273\001\n\010LogLe" + "vel\022\027\n\023LOG_LEVEL_EMERGENCY\020\000\022\023\n\017LOG_LEVE" + "L_ALERT\020\001\022\026\n\022LOG_LEVEL_CRITICAL\020\002\022\023\n\017LOG" + "_LEVEL_ERROR\020\003\022\025\n\021LOG_LEVEL_WARNING\020\004\022\024\n" + "\020LOG_LEVEL_NOTICE\020\005\022\022\n\016LOG_LEVEL_INFO\020\006\022" + "\023\n\017LOG_LEVEL_DEBUG\020\0072\255\003\n\rEventsService\022g" + "\n\017SubscribeEvents\022).mavsdk.rpc.events.Su" + "bscribeEventsRequest\032!.mavsdk.rpc.events" + ".EventsResponse\"\004\200\265\030\0000\001\022\224\001\n\036SubscribeHea" + "lthAndArmingChecks\0228.mavsdk.rpc.events.S" + "ubscribeHealthAndArmingChecksRequest\0320.m" + "avsdk.rpc.events.HealthAndArmingChecksRe" + "sponse\"\004\200\265\030\0000\001\022\233\001\n\036GetHealthAndArmingChe" + "cksReport\0228.mavsdk.rpc.events.GetHealthA" + "ndArmingChecksReportRequest\0329.mavsdk.rpc" + ".events.GetHealthAndArmingChecksReportRe" + "sponse\"\004\200\265\030\001B\037\n\020io.mavsdk.eventsB\013Events" + "Protob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_events_2fevents_2eproto_deps[1] = { @@ -583,7 +584,7 @@ static ::absl::once_flag descriptor_table_events_2fevents_2eproto_once; PROTOBUF_CONSTINIT const ::_pbi::DescriptorTable descriptor_table_events_2fevents_2eproto = { false, false, - 2233, + 2253, descriptor_table_protodef_events_2fevents_2eproto, "events/events.proto", &descriptor_table_events_2fevents_2eproto_once, @@ -604,9 +605,9 @@ const ::google::protobuf::EnumDescriptor* EventsResult_Result_descriptor() { return file_level_enum_descriptors_events_2fevents_2eproto[0]; } PROTOBUF_CONSTINIT const uint32_t EventsResult_Result_internal_data_[] = { - 524288u, 0u, }; + 589824u, 0u, }; bool EventsResult_Result_IsValid(int value) { - return 0 <= value && value <= 7; + return 0 <= value && value <= 8; } #if (__cplusplus < 201703) && \ (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) @@ -619,6 +620,7 @@ constexpr EventsResult_Result EventsResult::RESULT_DENIED; constexpr EventsResult_Result EventsResult::RESULT_FAILED; constexpr EventsResult_Result EventsResult::RESULT_TIMEOUT; constexpr EventsResult_Result EventsResult::RESULT_NO_SYSTEM; +constexpr EventsResult_Result EventsResult::RESULT_UNKNOWN; constexpr EventsResult_Result EventsResult::Result_MIN; constexpr EventsResult_Result EventsResult::Result_MAX; constexpr int EventsResult::Result_ARRAYSIZE; diff --git a/src/mavsdk_server/src/generated/events/events.pb.h b/src/mavsdk_server/src/generated/events/events.pb.h index 3873c6207f..a432eccfb6 100644 --- a/src/mavsdk_server/src/generated/events/events.pb.h +++ b/src/mavsdk_server/src/generated/events/events.pb.h @@ -113,6 +113,7 @@ enum EventsResult_Result : int { EventsResult_Result_RESULT_FAILED = 5, EventsResult_Result_RESULT_TIMEOUT = 6, EventsResult_Result_RESULT_NO_SYSTEM = 7, + EventsResult_Result_RESULT_UNKNOWN = 8, EventsResult_Result_EventsResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::int32_t>::min(), EventsResult_Result_EventsResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = @@ -122,8 +123,8 @@ enum EventsResult_Result : int { bool EventsResult_Result_IsValid(int value); extern const uint32_t EventsResult_Result_internal_data_[]; constexpr EventsResult_Result EventsResult_Result_Result_MIN = static_cast(0); -constexpr EventsResult_Result EventsResult_Result_Result_MAX = static_cast(7); -constexpr int EventsResult_Result_Result_ARRAYSIZE = 7 + 1; +constexpr EventsResult_Result EventsResult_Result_Result_MAX = static_cast(8); +constexpr int EventsResult_Result_Result_ARRAYSIZE = 8 + 1; const ::google::protobuf::EnumDescriptor* EventsResult_Result_descriptor(); template @@ -136,7 +137,7 @@ const std::string& EventsResult_Result_Name(T value) { template <> inline const std::string& EventsResult_Result_Name(EventsResult_Result value) { return ::google::protobuf::internal::NameOfDenseEnum( + 0, 8>( static_cast(value)); } inline bool EventsResult_Result_Parse(absl::string_view name, EventsResult_Result* value) { @@ -1275,6 +1276,7 @@ class EventsResult final static constexpr Result RESULT_FAILED = EventsResult_Result_RESULT_FAILED; static constexpr Result RESULT_TIMEOUT = EventsResult_Result_RESULT_TIMEOUT; static constexpr Result RESULT_NO_SYSTEM = EventsResult_Result_RESULT_NO_SYSTEM; + static constexpr Result RESULT_UNKNOWN = EventsResult_Result_RESULT_UNKNOWN; static inline bool Result_IsValid(int value) { return EventsResult_Result_IsValid(value); } diff --git a/src/mavsdk_server/src/generated/mission_raw/mission_raw.grpc.pb.h b/src/mavsdk_server/src/generated/mission_raw/mission_raw.grpc.pb.h index 81bea770e7..eec9a9a5f8 100644 --- a/src/mavsdk_server/src/generated/mission_raw/mission_raw.grpc.pb.h +++ b/src/mavsdk_server/src/generated/mission_raw/mission_raw.grpc.pb.h @@ -170,7 +170,7 @@ class MissionRawService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::mission_raw::MissionProgressResponse>> PrepareAsyncSubscribeMissionProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::mission_raw::SubscribeMissionProgressRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::mission_raw::MissionProgressResponse>>(PrepareAsyncSubscribeMissionProgressRaw(context, request, cq)); } - // * + // // Subscribes to mission changed. // // This notification can be used to be informed if a ground station has @@ -283,7 +283,7 @@ class MissionRawService final { // // Subscribe to mission progress updates. virtual void SubscribeMissionProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::mission_raw::SubscribeMissionProgressRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::mission_raw::MissionProgressResponse>* reactor) = 0; - // * + // // Subscribes to mission changed. // // This notification can be used to be informed if a ground station has @@ -623,7 +623,7 @@ class MissionRawService final { // // Subscribe to mission progress updates. virtual ::grpc::Status SubscribeMissionProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::mission_raw::SubscribeMissionProgressRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::mission_raw::MissionProgressResponse>* writer); - // * + // // Subscribes to mission changed. // // This notification can be used to be informed if a ground station has diff --git a/src/mavsdk_server/src/generated/mocap/mocap.grpc.pb.h b/src/mavsdk_server/src/generated/mocap/mocap.grpc.pb.h index 3bd450bd1a..4fa4b768af 100644 --- a/src/mavsdk_server/src/generated/mocap/mocap.grpc.pb.h +++ b/src/mavsdk_server/src/generated/mocap/mocap.grpc.pb.h @@ -29,7 +29,7 @@ namespace mavsdk { namespace rpc { namespace mocap { -// * +// // Allows interfacing a vehicle with a motion capture system in // order to allow navigation without global positioning sources available // (e.g. indoors, or when flying under a bridge. etc.). diff --git a/src/mavsdk_server/src/generated/offboard/offboard.grpc.pb.h b/src/mavsdk_server/src/generated/offboard/offboard.grpc.pb.h index 3395202f51..28fc3faa0e 100644 --- a/src/mavsdk_server/src/generated/offboard/offboard.grpc.pb.h +++ b/src/mavsdk_server/src/generated/offboard/offboard.grpc.pb.h @@ -29,7 +29,7 @@ namespace mavsdk { namespace rpc { namespace offboard { -// * +// // Control a drone with position, velocity, attitude or motor commands. // // The module is called offboard because the commands can be sent from external sources diff --git a/src/mavsdk_server/src/generated/shell/shell.grpc.pb.h b/src/mavsdk_server/src/generated/shell/shell.grpc.pb.h index ac530317b5..ed223fd5ae 100644 --- a/src/mavsdk_server/src/generated/shell/shell.grpc.pb.h +++ b/src/mavsdk_server/src/generated/shell/shell.grpc.pb.h @@ -29,7 +29,7 @@ namespace mavsdk { namespace rpc { namespace shell { -// * +// // Allow to communicate with the vehicle's system shell. class ShellService final { public: diff --git a/src/mavsdk_server/src/plugins/events/events_service_impl.h b/src/mavsdk_server/src/plugins/events/events_service_impl.h index 06f33a6172..01f040c690 100644 --- a/src/mavsdk_server/src/plugins/events/events_service_impl.h +++ b/src/mavsdk_server/src/plugins/events/events_service_impl.h @@ -303,6 +303,8 @@ class EventsServiceImpl final : public rpc::events::EventsService::Service { return rpc::events::EventsResult_Result_RESULT_TIMEOUT; case mavsdk::Events::Result::NoSystem: return rpc::events::EventsResult_Result_RESULT_NO_SYSTEM; + case mavsdk::Events::Result::Unknown: + return rpc::events::EventsResult_Result_RESULT_UNKNOWN; } } @@ -329,6 +331,8 @@ class EventsServiceImpl final : public rpc::events::EventsService::Service { return mavsdk::Events::Result::Timeout; case rpc::events::EventsResult_Result_RESULT_NO_SYSTEM: return mavsdk::Events::Result::NoSystem; + case rpc::events::EventsResult_Result_RESULT_UNKNOWN: + return mavsdk::Events::Result::Unknown; } } diff --git a/templates/plugin_h/call.j2 b/templates/plugin_h/call.j2 index 654e11eeaf..8d2961ff0f 100644 --- a/templates/plugin_h/call.j2 +++ b/templates/plugin_h/call.j2 @@ -13,7 +13,9 @@ void {{ name.lower_snake_case }}_async({% for param in params %}{% if param.type * * This function is blocking.{% if is_async %} See '{{ name.lower_snake_case }}_async' for the non-blocking counterpart.{% endif %} * + {% if has_result %} * @return Result of request. + {% endif %} */ {% if has_result %}Result{% else %}void{% endif %} {{ name.lower_snake_case }}({% for param in params %}{% if param.type_info.name.endswith("Result") %}Result{% else %}{{ param.type_info.name }}{% endif %} {{ param.name.lower_snake_case }}{{ ", " if not loop.last }}{% endfor %}) const; {% endif %} diff --git a/tools/.doxygen b/tools/.doxygen index f1f8174207..d4244e6bed 100644 --- a/tools/.doxygen +++ b/tools/.doxygen @@ -975,7 +975,7 @@ FILTER_SOURCE_PATTERNS = # (index.html). This can be useful if you have a project on for instance GitHub # and want to reuse the introduction page also for the doxygen output. -USE_MDFILE_AS_MAINPAGE = "README.md" +#USE_MDFILE_AS_MAINPAGE = "README.md" #--------------------------------------------------------------------------- # Configuration options related to source browsing @@ -1201,15 +1201,6 @@ HTML_COLORSTYLE_SAT = 100 HTML_COLORSTYLE_GAMMA = 80 -# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML -# page will contain the date and time when the page was generated. Setting this -# to YES can help to show when doxygen was last run and thus if the -# documentation is up to date. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_TIMESTAMP = NO - # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML # documentation will contain sections that can be hidden and shown after the # page has loaded. @@ -1480,17 +1471,6 @@ EXT_LINKS_IN_WINDOW = NO FORMULA_FONTSIZE = 10 -# Use the FORMULA_TRANPARENT tag to determine whether or not the images -# generated for formulas are transparent PNGs. Transparent PNGs are not -# supported properly for IE 6.0, but are supported on all modern browsers. -# -# Note that when changing this option you need to delete any form_*.png files in -# the HTML output directory before the changes have effect. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_TRANSPARENT = YES - # Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see # http://www.mathjax.org) which uses client side Javascript for the rendering # instead of using pre-rendered bitmaps. Use this if you do not have LaTeX @@ -1769,16 +1749,6 @@ LATEX_BATCHMODE = NO LATEX_HIDE_INDICES = NO -# If the LATEX_SOURCE_CODE tag is set to YES then doxygen will include source -# code with syntax highlighting in the LaTeX output. -# -# Note that which sources are shown also depends on other settings such as -# SOURCE_BROWSER. -# The default value is: NO. -# This tag requires that the tag GENERATE_LATEX is set to YES. - -LATEX_SOURCE_CODE = NO - # The LATEX_BIB_STYLE tag can be used to specify the style to use for the # bibliography, e.g. plainnat, or ieeetr. See # http://en.wikipedia.org/wiki/BibTeX and \cite for more info. @@ -1787,14 +1757,6 @@ LATEX_SOURCE_CODE = NO LATEX_BIB_STYLE = plain -# If the LATEX_TIMESTAMP tag is set to YES then the footer of each generated -# page will contain the date and time when the page was generated. Setting this -# to NO can help when comparing the output of multiple runs. -# The default value is: NO. -# This tag requires that the tag GENERATE_LATEX is set to YES. - -LATEX_TIMESTAMP = NO - #--------------------------------------------------------------------------- # Configuration options related to the RTF output #--------------------------------------------------------------------------- @@ -1851,16 +1813,6 @@ RTF_STYLESHEET_FILE = RTF_EXTENSIONS_FILE = -# If the RTF_SOURCE_CODE tag is set to YES then doxygen will include source code -# with syntax highlighting in the RTF output. -# -# Note that which sources are shown also depends on other settings such as -# SOURCE_BROWSER. -# The default value is: NO. -# This tag requires that the tag GENERATE_RTF is set to YES. - -RTF_SOURCE_CODE = NO - #--------------------------------------------------------------------------- # Configuration options related to the man page output #--------------------------------------------------------------------------- @@ -1950,15 +1902,6 @@ GENERATE_DOCBOOK = NO DOCBOOK_OUTPUT = docbook -# If the DOCBOOK_PROGRAMLISTING tag is set to YES, doxygen will include the -# program listings (including syntax highlighting and cross-referencing -# information) to the DOCBOOK output. Note that enabling this will significantly -# increase the size of the DOCBOOK output. -# The default value is: NO. -# This tag requires that the tag GENERATE_DOCBOOK is set to YES. - -DOCBOOK_PROGRAMLISTING = NO - #--------------------------------------------------------------------------- # Configuration options for the AutoGen Definitions output #--------------------------------------------------------------------------- @@ -2137,15 +2080,6 @@ EXTERNAL_PAGES = YES # Configuration options related to the dot tool #--------------------------------------------------------------------------- -# If the CLASS_DIAGRAMS tag is set to YES, doxygen will generate a class diagram -# (in HTML and LaTeX) for classes with base or super classes. Setting the tag to -# NO turns the diagrams off. Note that this option also works with HAVE_DOT -# disabled, but it is recommended to install and use dot, since it yields more -# powerful graphs. -# The default value is: YES. - -CLASS_DIAGRAMS = YES - # You can include diagrams made with dia in doxygen documentation. Doxygen will # then run dia to produce the diagram and insert it in the documentation. The # DIA_PATH tag allows you to specify the directory where the dia binary resides. @@ -2178,23 +2112,6 @@ HAVE_DOT = NO DOT_NUM_THREADS = 0 -# When you want a differently looking font in the dot files that doxygen -# generates you can specify the font name using DOT_FONTNAME. You need to make -# sure dot is able to find the font, which can be done by putting it in a -# standard location or by setting the DOTFONTPATH environment variable or by -# setting DOT_FONTPATH to the directory containing the font. -# The default value is: Helvetica. -# This tag requires that the tag HAVE_DOT is set to YES. - -DOT_FONTNAME = Helvetica - -# The DOT_FONTSIZE tag can be used to set the size (in points) of the font of -# dot graphs. -# Minimum value: 4, maximum value: 24, default value: 10. -# This tag requires that the tag HAVE_DOT is set to YES. - -DOT_FONTSIZE = 10 - # By default doxygen will tell dot to use the default font as specified with # DOT_FONTNAME. If you specify a different font using DOT_FONTNAME you can set # the path where dot can find it using this tag. @@ -2407,18 +2324,6 @@ DOT_GRAPH_MAX_NODES = 50 MAX_DOT_GRAPH_DEPTH = 0 -# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent -# background. This is disabled by default, because dot on Windows does not seem -# to support this out of the box. -# -# Warning: Depending on the platform used, enabling this option may lead to -# badly anti-aliased labels on the edges of a graph (i.e. they become hard to -# read). -# The default value is: NO. -# This tag requires that the tag HAVE_DOT is set to YES. - -DOT_TRANSPARENT = NO - # Set the DOT_MULTI_TARGETS tag to YES to allow dot to generate multiple output # files in one run (i.e. multiple -o and -T options on the command line). This # makes dot run faster, but since only newer versions of dot (>1.8.10) support diff --git a/tools/generate_changelog.py b/tools/generate_changelog.py deleted file mode 100755 index aec0154692..0000000000 --- a/tools/generate_changelog.py +++ /dev/null @@ -1,199 +0,0 @@ -#!/usr/bin/env python - -from gql import gql, Client -from gql.transport.requests import RequestsHTTPTransport - -import argparse -import dateutil.parser -import datetime -import json - -debug = False - -def create_gql_client(token): - transport = RequestsHTTPTransport(url='https://api.github.com/graphql', use_json=True) - transport.headers = { "Authorization": "Bearer {}".format(token) } - client = Client(transport=transport) - - return client - -def query_releases(gql_client, debug=False): - query_releases = gql(''' - { - repository(owner: "mavlink", name: "MAVSDK") { - releases(last: 10) { - nodes { - name - createdAt - tag { - name - } - } - } - } - } - ''') - - - releases = gql_client.execute(query_releases) - releases = releases["repository"]["releases"]["nodes"] - - if debug: - print(json.dumps(releases, indent=2)) - - return releases - -def plus_one_minute(date_str): - date = dateutil.parser.parse(date_str) - date += datetime.timedelta(minutes=1) - return date.isoformat().replace('+00:00', 'Z') - -def query_pull_requests(gql_client, releases, release_tag, debug=False): - previous_wanted_release = None - wanted_release = None - for release in releases: - previous_wanted_release = wanted_release - wanted_release = release - - if not release["tag"]: - continue - if release["tag"]["name"] == release_tag: - break - - if debug: - print(previous_wanted_release) - print(wanted_release) - - merged_predicate = None - if previous_wanted_release is None: - merged_predicate = f"<={wanted_release['createdAt']}" - else: - # We add one minute because otherwise the last PR of the previous release - # tends to get included as well. - merged_predicate = f"{plus_one_minute(previous_wanted_release['createdAt'])[:-4]}..{wanted_release['createdAt'][:-4]}" - - query_pull_requests_str = ''' - {{ - search(query: "repo:mavlink/MAVSDK is:pr is:merged merged:{merged_predicate}", type: ISSUE, last: 100) {{ - edges {{ - node {{ - ... on PullRequest {{ - url - number - title - author {{ - login - }} - reviews(last: 15) {{ - nodes {{ - author {{ - login - }} - }} - }} - labels(last: 1) {{ - edges {{ - node {{ - name - }} - }} - }} - mergedAt - }} - }} - }} - }} - }} - '''.format(merged_predicate=merged_predicate) - - if debug: - print(query_pull_requests_str) - - query_pull_requests = gql(query_pull_requests_str) - results_query = gql_client.execute(query_pull_requests) - result_pull_requests = list(map(lambda node: node["node"], results_query["search"]["edges"])) - - if debug: - print(json.dumps(result_pull_requests, indent=2)) - - return result_pull_requests - -def filter_by_label(pull_requests, label): - if debug: - print(json.dumps(pull_requests, indent=2)) - - for pull_request in pull_requests: - if (len(pull_request["labels"]["edges"]) == 0): - print(f"ERROR: PR is missing a label: {pull_request['url']}") - exit(1) - - return list(filter(lambda pull_request: pull_request["labels"]["edges"][0]["node"]["name"] == label, pull_requests)) - -def collect_contributors(pull_requests): - contributors = [] - - for pull_request in pull_requests: - author = pull_request["author"]["login"] - contributors.append(f"@{author}") - - contributors = set(contributors) - contributors = sorted(list(contributors), key=str.lower) - - return contributors - -def print_markdown_output(features, bugfixes, enhancements, documentation, contributors): - print("-----------") - print("CHANGELOG") - print("-----------") - - if features: - print("### Features:\n") - - for feature in features: - print(f"* {feature['title']} (#{feature['number']}).") - - if bugfixes: - print("\n### Bugfixes:\n") - - for bugfix in bugfixes: - print(f"* {bugfix['title']} (#{bugfix['number']}).") - - if enhancements: - print("\n### Enhancements:\n") - - for enhancement in enhancements: - print(f"* {enhancement['title']} (#{enhancement['number']}).") - - if documentation: - print("\n### Documentation:\n") - - for doc in documentation: - print(f"* {doc['title']} (#{doc['number']}).") - - if contributors: - print("\n### Contributors:\n") - - print(', '.join(contributors)) - -def main(): - parser = argparse.ArgumentParser(description='Generate a changelog from pull requests between a given release tag and the previous one.') - parser.add_argument("--tag", help="The release tag for which the changelog should be generated") - parser.add_argument("--token", help="The token to access MAVSDK's GitHub API.") - parser.add_argument("--verbose", type=bool, nargs='?', const=True, default=False, help="Enable verbose output.") - - args = parser.parse_args() - - gql_client = create_gql_client(args.token) - releases = query_releases(gql_client, debug=args.verbose) - pull_requests = query_pull_requests(gql_client, releases, args.tag, debug=args.verbose) - - features = filter_by_label(pull_requests, "feature") - bugfixes = filter_by_label(pull_requests, "bug") - enhancements = filter_by_label(pull_requests, "enhancement") - documentation = filter_by_label(pull_requests, "documentation") - contributors = collect_contributors(pull_requests) - - print_markdown_output(features, bugfixes, enhancements, documentation, contributors) - -if __name__ == '__main__': - main() diff --git a/tools/generate_docs.sh b/tools/generate_docs.sh index 79c21743c8..5a78aa0962 100755 --- a/tools/generate_docs.sh +++ b/tools/generate_docs.sh @@ -18,11 +18,22 @@ command -v doxygen >/dev/null 2>&1 || { echo "ERROR: 'doxygen' is required and w SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" skip_checks=false -if [ "$#" -eq 1 -a "$1" == "--skip-checks" ]; then - skip_checks=true +overwrite=false + +if [ "$#" -ge 1 ]; then + for arg in "$@"; do + case "$arg" in + --skip-checks) + skip_checks=true + ;; + --overwrite) + overwrite=true + ;; + esac + done fi -BUILD_DIR="${SCRIPT_DIR}/docs" +BUILD_DIR="${SCRIPT_DIR}/../build-docs" INSTALL_DIR="${BUILD_DIR}/install" if [ "$skip_checks" = false ]; then @@ -33,8 +44,8 @@ if [ "$skip_checks" = false ]; then fi # Build and install locally. -cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=${INSTALL_DIR} -B${BUILD_DIR} -H.; -make -C${BUILD_DIR} install -j4; +cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=${INSTALL_DIR} -B${BUILD_DIR} -H. +make -C${BUILD_DIR} install -j$(nproc --all) return_result=0 # Doxygen likes to run where the source is (because INPUT in .doxygen is empty), @@ -45,7 +56,7 @@ pushd ${INSTALL_DIR}/include/mavsdk doxygen_output_file=".doxygen_output.tmp" doxygen ${SCRIPT_DIR}/.doxygen &> $doxygen_output_file cat $doxygen_output_file -if cat $doxygen_output_file | grep "warning" | grep -v "ignoring unsupported tag" +if cat $doxygen_output_file | grep "warning" | grep -v "ignoring unsupported tag" | grep -v "operator" then return_result=1 echo "Please check doxygen warnings." @@ -55,4 +66,11 @@ fi ${SCRIPT_DIR}/generate_markdown_from_doxygen_xml.py ${INSTALL_DIR}/docs ${INSTALL_DIR}/docs popd + +if [ "$overwrite" = true ]; then + # Clear folder first except index.md + find ${SCRIPT_DIR}/../docs/en/cpp/api_reference/ -type f -not -name 'index.md' -delete + cp ${INSTALL_DIR}/docs/markdown/* ${SCRIPT_DIR}/../docs/en/cpp/api_reference/ +fi + exit $return_result