Class TelemetryModule

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class TelemetryModule : public rclcpp_lifecycle::LifecycleNode

Public Types

using Trigger = std_srvs::srv::Trigger

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

Public Members

CopterState current_state_
TelemetryParams params_

Friends

friend T_DjiReturnCode c_attitude_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_velocity_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_angular_rate_ground_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_angular_rate_body_raw_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_imu_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_vo_position_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gps_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gps_position_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gps_velocity_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gps_details_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gps_signal_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gps_control_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rtk_position_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rtk_velocity_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rtk_yaw_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rtk_position_info_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rtk_yaw_info_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rtk_connection_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_magnetometer_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rc_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_esc_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_rc_connection_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_flight_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_display_mode_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_landing_gear_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_motor_start_error_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_flight_anomaly_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_battery_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_height_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_control_mode_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_home_point_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_home_point_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_acceleration_ground_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_acceleration_body_fused_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_acceleration_body_raw_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_avoid_data_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_altitude_sl_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_altitude_barometric_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_single_battery_index1_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_single_battery_index2_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_home_point_altitude_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gimbal_angles_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
friend T_DjiReturnCode c_gimbal_status_callback(const uint8_t *data, uint16_t data_size, const T_DjiDataTimestamp *timestamp)
struct CopterState

Public Functions

inline void initialize_state()

Public Members

psdk_interfaces::msg::PositionFused local_position
sensor_msgs::msg::NavSatFix gps_position
tf2::Quaternion attitude
geometry_msgs::msg::Vector3Stamped gimbal_angles
struct TelemetryParams

Public Members

std::string imu_frame
std::string body_frame
std::string map_frame
std::string gimbal_frame
std::string gimbal_base_frame
std::string camera_frame
std::string tf_frame_prefix
bool publish_transforms
int imu_frequency
int attitude_frequency
int acceleration_frequency
int velocity_frequency
int angular_rate_frequency
int position_frequency
int altitude_frequency
int gps_fused_position_frequency
int gps_data_frequency
int rtk_data_frequency
int magnetometer_frequency
int rc_channels_data_frequency
int gimbal_data_frequency
int flight_status_frequency
int battery_level_frequency
int control_information_frequency
int esc_data_frequency