Class LiveviewModule

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class psdk_ros2::LiveviewModule : public rclcpp_lifecycle::LifecycleNode

Public Functions

explicit LiveviewModule(const std::string &name)

Construct a new LiveviewModule object.

Parameters

node_name – Name of the node

~LiveviewModule()

Destroy the LiveviewModule object.

CallbackReturn on_configure(const rclcpp_lifecycle::State &state)

Configures the LiveviewModule. 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 LiveviewModule.

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 LiveviewModule. 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 LiveviewModule.

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 LiveviewModule.

Parameters

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

Returns

CallbackReturn SUCCESS or FAILURE

bool init()

Initialize the LiveviewModule.

Returns

true/false

bool deinit()

Deinitialize the LiveviewModule.

Returns

true/false

Private Functions

void camera_setup_streaming_cb(const std::shared_ptr<CameraSetupStreaming::Request> request, const std::shared_ptr<CameraSetupStreaming::Response> response)

Request to start/stop streming of a certain camera.

Parameters
  • request – CameraSetupStreaming service request. The camera mounted position for which the request is made needs to be specified as well as the camera source (e.g. using the wide or the zoom camera). Moreover, the user can choose to stream the images raw or decoded.

  • response – CameraSetupStreaming service response.

bool start_camera_stream(CameraImageCallback callback, void *user_data, const E_DjiLiveViewCameraPosition payload_index, const E_DjiLiveViewCameraSource camera_source)

Starts the camera streaming.

Parameters
  • callback – function to be executed when a frame is received

  • user_data – unused parameter

  • payload_index – select which camera to use to retrieve the streaming. See enum E_DjiLiveViewCameraPosition in dji_liveview.h for more details.

  • camera_source – select which sub-camera to use to retrieve the streaming (e.g. zoom, wide). See enum E_DjiLiveViewCameraSource for more details.

Returns

true/false Returns true if the streaming has been started correctly and False otherwise.

bool stop_main_camera_stream(const E_DjiLiveViewCameraPosition payload_index, const E_DjiLiveViewCameraSource camera_source)

Stops the main camera streaming.

Parameters
  • payload_index – select which camera to use to retrieve the streaming. See enum E_DjiLiveViewCameraPosition in dji_liveview.h for more details.

  • camera_source – select which sub-camera to use to retrieve the streaming (e.g. zoom, wide). See enum E_DjiLiveViewCameraSource for more details.

Returns

true/false Returns true if the streaming has been stopped correctly and False otherwise.

void publish_main_camera_images(CameraRGBImage rgb_img, void *user_data)

Publishes the main camera streaming to a ROS 2 topic.

Parameters
  • rgb_img – decoded RGB frame retrieved from the camera

  • user_data – unused parameter

void publish_main_camera_images(const uint8_t *buffer, uint32_t buffer_length)

Publishes the raw (not decoded) main camera streaming to a ROS 2 topic.

Parameters
  • buffer – raw buffer retrieved from the camera

  • buffer_length – length of the buffer

void publish_fpv_camera_images(CameraRGBImage rgb_img, void *user_data)

Publishes the FPV camera streaming to a ROS 2 topic.

Parameters
  • rgb_img – decoded RGB frame retrieved from the camera

  • user_data – unused parameter

void publish_fpv_camera_images(const uint8_t *buffer, uint32_t buffer_length)

Publishes the raw (not decoded) FPV camera streaming to a ROS 2 topic.

Parameters
  • buffer – raw buffer retrieved from the camera

  • buffer_length – length of the buffer

std::string get_optical_frame_id()

Get the optical frame id for a certain lens.

Returns

string with the optical frame id name