Class TelemetryModule

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class psdk_ros2::TelemetryModule : public rclcpp_lifecycle::LifecycleNode

Public Functions

explicit TelemetryModule(const std::string &name)

Construct a new TelemetryModule object.

Parameters

node_name – Name of the node

~TelemetryModule()

Destroy the telemetry module object.

CallbackReturn on_configure(const rclcpp_lifecycle::State &state)

Configures the telemetry module. Creates the ROS 2 subscribers and services.

Parameters

state – rclcpp_lifecycle::State. Current state of the node.

Returns

CallbackReturn SUCCESS or FAILURE

CallbackReturn on_activate(const rclcpp_lifecycle::State &state)

Activates the telemetry module.

Parameters

state – rclcpp_lifecycle::State. Current state of the node.

Returns

CallbackReturn SUCCESS or FAILURE

CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state)

Cleans the telemetry module. Resets the ROS 2 subscribers and services.

Parameters

state – rclcpp_lifecycle::State. Current state of the node.

Returns

CallbackReturn SUCCESS or FAILURE

CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state)

Deactivates the telemetry module.

Parameters

state – rclcpp_lifecycle::State. Current state of the node.

Returns

CallbackReturn SUCCESS or FAILURE

CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state)

Shuts down the telemetry module.

Parameters

state – rclcpp_lifecycle::State. Current state of the node.

Returns

CallbackReturn SUCCESS or FAILURE

bool init()

Initialize the telemetry module.

Returns

true/false

bool deinit()

Deinitialize the telemetry module.

Returns

true/false

inline sensor_msgs::msg::NavSatFix get_current_gps()

Get the current gps object.

Returns

sensor_msgs::msg::NavSatFix

void subscribe_psdk_topics()

Subscribe to telemetry topics exposed by the DJI PSDK library.

void unsubscribe_psdk_topics()

Unsubscribe the telemetry topics.

void set_aircraft_base(const T_DjiAircraftInfoBaseInfo aircraft_base)

Set the aircraft base object.

Parameters

aircraft_base – the type of aircraft base

void set_camera_type(const E_DjiCameraType camera_type)

Set the camera type object.

Parameters

camera_type – the type of camera attached to the aircraft

Private Functions

T_DjiReturnCode attitude_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the attitude quaternion provided by DJI PSDK lib and publishes it on a ROS 2 topic. The attitude is published as a quaternion with respect to a FLU body frame.

Parameters
  • data – pointer to a T_DjiFcSubscriptionQuaternion type quaternion

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode velocity_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the copter x, y and z velocity provided by DJI PSDK lib and publishes it on a ROS 2 topic. The velocity vector is given wrt. a global ENU frame.

Parameters
  • data – pointer to T_DjiFcSubscriptionVelocity data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode angular_rate_ground_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the copter x, y and z angular velocity fused provided by DJI PSDK lib and publishes it on a ROS 2 topic. The angular velocity is given wrt. a ground-fixed ENU frame at up to 200 Hz.

Parameters
  • data – pointer to T_DjiFcSubscriptionAngularRateFusioned data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode angular_rate_body_raw_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the copter x, y and z angular velocity provided by DJI PSDK lib and publishes it on a ROS 2 topic. The velocity vector is given in an IMU-centered, body-fixed FLU frame at up to 400 Hz.

Parameters
  • data – pointer to T_DjiFcSubscriptionAngularRateRaw data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode imu_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the IMU data provided by DJI PSDK lib and publishes it on a ROS 2 topic. The quaternion is given wrt. a FLU coordinate frame.

Parameters
  • data – pointer to T_DjiFcSubscriptionHardSync data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode vo_position_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the fused position data provided by DJI PSDK lib and publishes it on a ROS 2 topic.

Fused copter position wrt. to a Cartesian global frame with ENU orientation (best effort). As documented in the PSDK libraries, if no GPS is available this topic uses the VO + compass information to determine the XY axis orientation. If any malfunction is present, these axis will not point to the East, Norh directions as expected. This position output is the fusion of the following sensors: @sensors IMU, VO, GPS (if available), RTK (if available), ultrasonic, magnetometer, barometer A health flag for each axis offers an indication if the data is valid or not.

Note

This information should be used with care, specially when intended for control purposes.

Parameters
  • data – pointer to T_DjiFcSubscriptionPositionVO data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gps_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the GPS data provided by DJI PSDK lib and publishes it on a ROS 2 topic. This topic provides the GPS longitude [deg], latitude [deg] and altitude (WGS84 reference ellipsoid [m]) data along with the number of visible satellites.

Parameters
  • data – pointer to T_DjiFcSubscriptionPositionFused data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gps_position_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the GPS data provided by DJI PSDK lib and publishes it on a ROS 2 topic. This topic provides GPS the longitude [deg], latitude [deg] and altitude [m].

Parameters
  • data – pointer to T_DjiFcSubscriptionGpsPosition data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gps_velocity_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the GPS velocity data provided by DJI PSDK lib and publishes it on a ROS 2 topic. The data published is x, y, and z GPS velocity in [m/s].

Parameters
  • data – pointer to T_DjiFcSubscriptionGpsVelocity data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gps_details_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the GPS details provided by DJI PSDK lib and publishes it on a ROS 2 topic. The information provided by this topic is related with the accuracy and well functioning of the GPS sensors. The type of information given by this topic is described in psdk_interfaces::msg::GPSDetails.

Parameters
  • data – pointer to T_DjiFcSubscriptionGpsDetails data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gps_signal_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the GPS signal data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Signal level is represented from 0 to 5, being 0 the worst and 5 the best GPS signal value.

Parameters
  • data – pointer to T_DjiFcSubscriptionGpsSignalLevel data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gps_control_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the GPS control data provided by DJI PSDK lib and publishes it on a ROS 2 topic.Provides similar data as the topic gps_signal_level with the main difference being that if the home point is not set, it always returns 0.

Parameters
  • data – pointer to T_DjiFcSubscriptionGpsControlLevel data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rtk_position_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RTK position data provided by DJI PSDK lib and publishes it on a ROS 2 topic. The data published is RTK longitude [deg], latitude [deg], and HFSL Height above mean sea level [m].

Parameters
  • data – pointer to T_DjiFcSubscriptionRtkPosition data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rtk_velocity_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RTK velocity data provided by DJI PSDK lib and publishes it on a ROS 2 topic. The data published is x, y and z RTK velocity data in [m/s].

Parameters
  • data – pointer to T_DjiFcSubscriptionRtkVelocity data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rtk_yaw_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RTK yaw data provided by DJI PSDK lib and publishes it on a ROS 2 topic. As documented in the PSDK libraries, this yaw value represents the vector from ANT1 to ANT2 as configured in DJI Assistant 2. This means that the value of RTK yaw will be 90deg offset from the yaw of the aircraft.

Parameters
  • data – pointer to T_DjiFcSubscriptionRtkYaw data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rtk_position_info_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RTK position info data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides state information regarding the RTK position solution. Uses the enum RTKSolutionState to define the quality of the solution.

Parameters
  • data – pointer to T_DjiFcSubscriptionRtkPositionInfo data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rtk_yaw_info_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RTK yaw info data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides state information regarding the RTK yaw solution. Uses the enum RTKSolutionState to define the quality of the solution.

Parameters
  • data – pointer to T_DjiFcSubscriptionRtkYawInfo data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rtk_connection_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Provides RTK connection status. This topic will update in real time whether the RTK GPS system is connected or not; typical uses include app-level logic to switch between GPS and RTK sources of positioning based on this flag.

Parameters
  • data – pointer to T_DjiFcSubscriptionRTKConnectStatus data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode magnetometer_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the magnetometer data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides magnetometer readings in x, y, z, fused with IMU and GPS @ up to 100Hz yaw solution.

Parameters
  • data – pointer to T_DjiFcSubscriptionCompass data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rc_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RC data provided by DJI PSDK lib and publishes it on a ROS 2 topic.This topic provides stick inputs, mode switch and landing gear switch up to 100 Hz.

Parameters
  • data – pointer to T_DjiFcSubscriptionRC data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode rc_connection_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the RC connection status provided by DJI PSDK lib and publishes it on a ROS 2 topic.This topic provides connection status for air system, ground system and MSDK apps. The connection status also includes a logicConnected element, which will change to false if either the air system or the ground system radios are disconnected for >3s. (up to 50Hz)

Parameters
  • data – pointer to T_DjiFcSubscriptionRCWithFlagData data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode esc_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the gimbal angle data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides the roll, pitch and yaw of the gimbal up to 50Hz. These angles are in [rad]. The roll and pitch are wrt. to a FLU frame while the yaw is given wrt. an ENU oriented reference frame attached to the gimbal structure.

Retrieves the ESC data provided by DJI PSDK lib and publishes it on a ROS 2 topic.This topic provides esc data

Parameters
  • data – pointer to T_DjiFcSubscriptionGimbalAngles data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

  • data – pointer to T_DjiFcSubscriptionEscData data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode flight_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the flight status data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Indicates if the copter is either stopped, on ground or in air. More information regarding the flight status data can be found in psdk_interfaces::msg::FlightStatus.

Parameters
  • data – pointer to T_DjiFcSubscriptionFlightStatus data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode display_mode_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the diplay mode data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides information regarding the state of the copter @ up to 50Hz Please refer to either the enum DisplayMode or the msg definition psdk_interfaces::msg::DisplayMode for more details.

Parameters
  • data – pointer to T_DjiFcSubscriptionDisplaymode data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode landing_gear_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the landing gear status data provided by DJI PSDK lib and publishes it on a ROS 2 topic.

Parameters
  • data – pointer to T_DjiFcSubscriptionLandinggear data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode motor_start_error_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the motor start error status data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides information regarding the reason why the motors could not be started. Available @ up to 50Hz. The information provided here corresponds to an error code as defined in dji_error.h.

Parameters
  • data – pointer to T_DjiFcSubscriptionMotorStartError data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode flight_anomaly_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the flight anomaly data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides information regarding different errors the aircraft may encounter in flight @ up to 50Hz. Please refer to the msg definition psdk_interfaces::msg::FlightAnomaly for more details.

Parameters
  • data – pointer to T_DjiFcSubscriptionFlightAnomaly data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode battery_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the battery status data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides information regarding the battery capacity, current, voltage and percentage. Please refer to the msg definition sensor_msgs::msg::BatteryState for more details.

Parameters
  • data – pointer to T_DjiFcSubscriptionWholeBatteryInfo data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode height_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the heigh data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides the relative height above ground in [m] at up to 100Hz. This data is the result of the fusion between the Visual Odometry and Ultrasonic sensor.

Note

This topic does not have a ‘valid’ flag. Thus, if the copter is too far from an object to be detected by the ultrasonic/VO sensors, the values will latch and there is no feedback given to the user.

Parameters
  • data – pointer to T_DjiFcSubscriptionHeightFusion data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode control_mode_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Provides the control mode of the aircraft related to SDK/RC control.

Parameters
  • data – pointer to T_DjiFcSubscriptionControlDevice data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode home_point_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Provides the latitude and longitude of the home point.

Parameters
  • data – pointer to T_DjiFcSubscriptionHomePointInfo data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode home_point_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Provides status of whether the home point was set or not.

Parameters
  • data – pointer to T_DjiFcSubscriptionHomePointSetStatus data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode acceleration_ground_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the copter linear acceleration wrt. a ground-fixed ENU frame in [m/s^2] up to 200 Hz. This output is the result of a fusion performed within the flight control system.

Parameters
  • data – pointer to T_DjiFcSubscriptionAccelerationGround data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode acceleration_body_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the copter linear acceleration wrt. a body-fixed FLU frame in [m/s^2] up to 200 Hz. This output is the result of a fusion performed within the flight control system.

Parameters
  • data – pointer to T_DjiFcSubscriptionAccelerationBody data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode acceleration_body_raw_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the copter linear acceleration wrt. a body-fixed FLU frame in [m/s^2] up to 400 Hz. This output is the filtered output from the IMU on-board the flight control system.

Parameters
  • data – pointer to T_DjiFcSubscriptionAccelerationRaw data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode avoid_data_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the obstacle avoidance data around the vehicle at a frequency up to 100 Hz. It also provides a health flag for each sensor direction. Please refer to the msg definition psdk_interfaces::msg::RelativeObstacleInfo for more details.

Parameters
  • data – pointer to T_DjiFcSubscriptionAvoidData data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode altitude_sl_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the fused sea level altitude in meters.

Parameters
  • data – pointer to T_DjiFcSubscriptionAltitudeFused data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode altitude_barometric_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the barometric altitude from sea level using the ICAO model @ up to 200Hz. More information about this topic can be found in the dji_fc_subscription.h.

Parameters
  • data – pointer to T_DjiFcSubscriptionAltitudeBarometer data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode single_battery_index1_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves single information of battery with index 1. More information about this topic can be found in the dji_fc_subscription.h.

Parameters
  • data – pointer to T_DjiFcSubscriptionSingleBatteryInfo data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode single_battery_index2_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves single information of battery with index 2. More information about this topic can be found in the dji_fc_subscription.h.

Parameters
  • data – pointer to T_DjiFcSubscriptionSingleBatteryInfo data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode home_point_altitude_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the altitude from sea level when the aircraft last took off. This is a fused value. More information about this topic can be found in dji_fc_subscription.h.

Parameters
  • data – pointer to T_DjiFcSubscriptionAltitudeOfHomePoint data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

T_DjiReturnCode gimbal_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)

Retrieves the gimbal status data provided by DJI PSDK lib and publishes it on a ROS 2 topic. Provides the gimbal status data following data up to 50 Hz. More information regarding the gimbal status data can be found in psdk_interfaces::msg::GimbalStatus.

Parameters
  • data – pointer to T_DjiFcSubscriptionGimbalStatus data

  • data_size – size of data. Unused parameter.

  • timestamp – timestamp provided by DJI

Returns

T_DjiReturnCode error code indicating if the subscription has been done correctly

E_DjiDataSubscriptionTopicFreq get_frequency(const int frequency)

Get the DJI frequency object associated with a certain frequency.

Parameters

frequency – variable to store the output frequency

Returns

E_DjiDataSubscriptionTopicFreq

void set_local_position_ref_cb(const std::shared_ptr<Trigger::Request> request, const std::shared_ptr<Trigger::Response> response)

Sets the current position as the new origin for the local position.

Parameters
  • request – Trigger service request

  • response – Trigger service response

inline int get_gps_signal_level()

Get the gps signal level.

Returns

int gps signal level

inline void set_gps_signal_level(const int gps_signal)

Set the gps signal level object.

Parameters

gps_signal

inline bool is_local_altitude_reference_set()

Checks if local altitude reference is set or not.

Returns

true if set, false otherwise

inline float get_local_altitude_reference()

Get the local altitude reference value. If it is not set, default value is 0.

Returns

float local_altitude_reference

void set_local_altitude_reference(const float altitude)

Sets the local altitude reference object.

Parameters

altitude – value to which to set the local altitude reference

void publish_static_transforms()

Publish all static transforms for a given copter.

void publish_dynamic_transforms()

Method which publishes the dynamic transforms for a given copter.

double get_yaw_gimbal()

Method which computes the yaw angle difference between the gimbal base (static frame attached to the robot) and the gimbal frame (frame attached to the gimbal).

Returns

the yaw angle difference between these two frames.

std::string add_tf_prefix(const std::string &frame_name)

Method to generate a tf adding the tf_prefix to the frame name.

Parameters

frame_name – name of the frame to be transformed

Returns

string with the tf name

void initialize_aircraft_base_info()

Set default unknown values for the aircraft base info.

struct CopterState
struct TelemetryParams