mavsdk::TelemetryServer Class Reference
#include: telemetry_server.h
Allow users to provide vehicle telemetry and state information (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates.
Data Structures
struct AccelerationFrd
struct ActuatorControlTarget
struct ActuatorOutputStatus
struct AngularVelocityBody
struct AngularVelocityFrd
struct Battery
struct Covariance
struct DistanceSensor
struct EulerAngle
struct FixedwingMetrics
struct GpsInfo
struct GroundTruth
struct Heading
struct Imu
struct MagneticFieldFrd
struct Odometry
struct Position
struct PositionBody
struct PositionNed
struct PositionVelocityNed
struct Quaternion
struct RawGps
struct RcStatus
struct ScaledPressure
struct StatusText
struct VelocityBody
struct VelocityNed
Public Types
Type | Description |
---|---|
enum FixType | GPS fix type. |
enum VtolState | Maps to MAV_VTOL_STATE. |
enum StatusTextType | Status types. |
enum LandedState | Landed State enumeration. |
enum Result | Possible results returned for telemetry requests. |
std::function< void(Result)> ResultCallback | Callback type for asynchronous TelemetryServer calls. |
Public Member Functions
Type | Name | Description |
---|---|---|
TelemetryServer (std::shared_ptr< ServerComponent > server_component) | Constructor. Creates the plugin for a ServerComponent instance. | |
~TelemetryServer () override | Destructor (internal use only). | |
TelemetryServer (const TelemetryServer & other) | Copy constructor. | |
Result | publish_position (Position position, VelocityNed velocity_ned, Heading heading)const | Publish to 'position' updates. |
Result | publish_home (Position home)const | Publish to 'home position' updates. |
Result | publish_sys_status (Battery battery, bool rc_receiver_status, bool gyro_status, bool accel_status, bool mag_status, bool gps_status)const | Publish 'sys status' updates. |
Result | publish_extended_sys_state (VtolState vtol_state, LandedState landed_state)const | Publish 'extended sys state' updates. |
Result | publish_raw_gps (RawGps raw_gps, GpsInfo gps_info)const | Publish to 'Raw GPS' updates. |
Result | publish_battery (Battery battery)const | Publish to 'battery' updates. |
Result | publish_status_text (StatusText status_text)const | Publish to 'status text' updates. |
Result | publish_odometry (Odometry odometry)const | Publish to 'odometry' updates. |
Result | publish_position_velocity_ned (PositionVelocityNed position_velocity_ned)const | Publish to 'position velocity' updates. |
Result | publish_ground_truth (GroundTruth ground_truth)const | Publish to 'ground truth' updates. |
Result | publish_imu (Imu imu)const | Publish to 'IMU' updates (in SI units in NED body frame). |
Result | publish_scaled_imu (Imu imu)const | Publish to 'Scaled IMU' updates. |
Result | publish_raw_imu (Imu imu)const | Publish to 'Raw IMU' updates. |
Result | publish_unix_epoch_time (uint64_t time_us)const | Publish to 'unix epoch time' updates. |
Result | publish_distance_sensor (DistanceSensor distance_sensor)const | Publish to "distance sensor" updates. |
const TelemetryServer & | operator= (const TelemetryServer &)=delete | Equality operator (object is not copyable). |
Constructor & Destructor Documentation
TelemetryServer()
mavsdk::TelemetryServer::TelemetryServer(std::shared_ptr< ServerComponent > server_component)
Constructor. Creates the plugin for a ServerComponent instance.
The plugin is typically created as shown below:
auto telemetry_server = TelemetryServer(server_component);
Parameters
- std::shared_ptr< ServerComponent > server_component - The ServerComponent instance associated with this server plugin.
~TelemetryServer()
mavsdk::TelemetryServer::~TelemetryServer() override
Destructor (internal use only).
TelemetryServer()
mavsdk::TelemetryServer::TelemetryServer(const TelemetryServer &other)
Copy constructor.
Parameters
- const TelemetryServer& other -
Member Typdef Documentation
typedef ResultCallback
using mavsdk::TelemetryServer::ResultCallback = std::function<void(Result)>
Callback type for asynchronous TelemetryServer calls.
Member Enumeration Documentation
enum FixType
GPS fix type.
Value | Description |
---|---|
NoGps |
No GPS connected. |
NoFix |
No position information, GPS is connected. |
Fix2D |
2D position. |
Fix3D |
3D position. |
FixDgps |
DGPS/SBAS aided 3D position. |
RtkFloat |
RTK float, 3D position. |
RtkFixed |
RTK Fixed, 3D position. |
enum VtolState
Maps to MAV_VTOL_STATE.
Value | Description |
---|---|
Undefined |
Not VTOL. |
TransitionToFw |
Transitioning to fixed-wing. |
TransitionToMc |
Transitioning to multi-copter. |
Mc |
Multi-copter. |
Fw |
Fixed-wing. |
enum StatusTextType
Status types.
Value | Description |
---|---|
Debug |
Debug. |
Info |
Information. |
Notice |
Notice. |
Warning |
Warning. |
Error |
Error. |
Critical |
Critical. |
Alert |
Alert. |
Emergency |
Emergency. |
enum LandedState
Landed State enumeration.
Value | Description |
---|---|
Unknown |
Landed state is unknown. |
OnGround |
The vehicle is on the ground. |
InAir |
The vehicle is in the air. |
TakingOff |
The vehicle is taking off. |
Landing |
The vehicle is landing. |
enum Result
Possible results returned for telemetry requests.
Value | Description |
---|---|
Unknown |
Unknown result. |
Success |
Success: the telemetry command was accepted by the vehicle. |
NoSystem |
No system connected. |
ConnectionError |
Connection error. |
Busy |
Vehicle is busy. |
CommandDenied |
Command refused by vehicle. |
Timeout |
Request timed out. |
Unsupported |
Request not supported. |
Member Function Documentation
publish_position()
Result mavsdk::TelemetryServer::publish_position(Position position, VelocityNed velocity_ned, Heading heading) const
Publish to 'position' updates.
This function is blocking.
Parameters
- Position position -
- VelocityNed velocity_ned -
- Heading heading -
Returns
Result - Result of request.
publish_home()
Result mavsdk::TelemetryServer::publish_home(Position home) const
Publish to 'home position' updates.
This function is blocking.
Parameters
- Position home -
Returns
Result - Result of request.
publish_sys_status()
Result mavsdk::TelemetryServer::publish_sys_status(Battery battery, bool rc_receiver_status, bool gyro_status, bool accel_status, bool mag_status, bool gps_status) const
Publish 'sys status' updates.
This function is blocking.
Parameters
- Battery battery -
- bool rc_receiver_status -
- bool gyro_status -
- bool accel_status -
- bool mag_status -
- bool gps_status -
Returns
Result - Result of request.
publish_extended_sys_state()
Result mavsdk::TelemetryServer::publish_extended_sys_state(VtolState vtol_state, LandedState landed_state) const
Publish 'extended sys state' updates.
This function is blocking.
Parameters
- VtolState vtol_state -
- LandedState landed_state -
Returns
Result - Result of request.
publish_raw_gps()
Result mavsdk::TelemetryServer::publish_raw_gps(RawGps raw_gps, GpsInfo gps_info) const
Publish to 'Raw GPS' updates.
This function is blocking.
Parameters
Returns
Result - Result of request.
publish_battery()
Result mavsdk::TelemetryServer::publish_battery(Battery battery) const
Publish to 'battery' updates.
This function is blocking.
Parameters
- Battery battery -
Returns
Result - Result of request.
publish_status_text()
Result mavsdk::TelemetryServer::publish_status_text(StatusText status_text) const
Publish to 'status text' updates.
This function is blocking.
Parameters
- StatusText status_text -
Returns
Result - Result of request.
publish_odometry()
Result mavsdk::TelemetryServer::publish_odometry(Odometry odometry) const
Publish to 'odometry' updates.
This function is blocking.
Parameters
- Odometry odometry -
Returns
Result - Result of request.
publish_position_velocity_ned()
Result mavsdk::TelemetryServer::publish_position_velocity_ned(PositionVelocityNed position_velocity_ned) const
Publish to 'position velocity' updates.
This function is blocking.
Parameters
- PositionVelocityNed position_velocity_ned -
Returns
Result - Result of request.
publish_ground_truth()
Result mavsdk::TelemetryServer::publish_ground_truth(GroundTruth ground_truth) const
Publish to 'ground truth' updates.
This function is blocking.
Parameters
- GroundTruth ground_truth -
Returns
Result - Result of request.
publish_imu()
Result mavsdk::TelemetryServer::publish_imu(Imu imu) const
Publish to 'IMU' updates (in SI units in NED body frame).
This function is blocking.
Parameters
- Imu imu -
Returns
Result - Result of request.
publish_scaled_imu()
Result mavsdk::TelemetryServer::publish_scaled_imu(Imu imu) const
Publish to 'Scaled IMU' updates.
This function is blocking.
Parameters
- Imu imu -
Returns
Result - Result of request.
publish_raw_imu()
Result mavsdk::TelemetryServer::publish_raw_imu(Imu imu) const
Publish to 'Raw IMU' updates.
This function is blocking.
Parameters
- Imu imu -
Returns
Result - Result of request.
publish_unix_epoch_time()
Result mavsdk::TelemetryServer::publish_unix_epoch_time(uint64_t time_us) const
Publish to 'unix epoch time' updates.
This function is blocking.
Parameters
- uint64_t time_us -
Returns
Result - Result of request.
publish_distance_sensor()
Result mavsdk::TelemetryServer::publish_distance_sensor(DistanceSensor distance_sensor) const
Publish to "distance sensor" updates.
This function is blocking.
Parameters
- DistanceSensor distance_sensor -
Returns
Result - Result of request.
operator=()
const TelemetryServer& mavsdk::TelemetryServer::operator=(const TelemetryServer &)=delete
Equality operator (object is not copyable).
Parameters
- const TelemetryServer& -
Returns
const TelemetryServer & -