Program Listing for File liveview.hpp
↰ Return to documentation for file (include/psdk_wrapper/modules/liveview.hpp
)
/*
* Copyright (C) 2024 Unmanned Life
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#ifndef PSDK_WRAPPER_INCLUDE_PSDK_WRAPPER_MODULES_LIVEVIEW_HPP_
#define PSDK_WRAPPER_INCLUDE_PSDK_WRAPPER_MODULES_LIVEVIEW_HPP_
#include <dji_liveview.h>
#include <dji_camera_stream_decoder.hpp> //NOLINT
#include <map>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <shared_mutex>
#include <string>
#include "psdk_interfaces/srv/camera_setup_streaming.hpp"
#include "psdk_wrapper/utils/psdk_wrapper_utils.hpp"
namespace psdk_ros2
{
class LiveviewModule : public rclcpp_lifecycle::LifecycleNode
{
public:
using CameraSetupStreaming = psdk_interfaces::srv::CameraSetupStreaming;
explicit LiveviewModule(const std::string& name);
~LiveviewModule();
CallbackReturn on_configure(const rclcpp_lifecycle::State& state);
CallbackReturn on_activate(const rclcpp_lifecycle::State& state);
CallbackReturn on_cleanup(const rclcpp_lifecycle::State& state);
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& state);
CallbackReturn on_shutdown(const rclcpp_lifecycle::State& state);
bool init();
bool deinit();
private:
friend void c_publish_main_streaming_callback(CameraRGBImage img,
void* user_data);
friend void c_publish_fpv_streaming_callback(CameraRGBImage img,
void* user_data);
friend void c_LiveviewConvertH264ToRgbCallback(
E_DjiLiveViewCameraPosition position, const uint8_t* buffer,
uint32_t buffer_length);
/* Streaming callbacks */
void LiveviewConvertH264ToRgbCallback(E_DjiLiveViewCameraPosition position,
const uint8_t* buffer,
uint32_t buffer_length);
void camera_setup_streaming_cb(
const std::shared_ptr<CameraSetupStreaming::Request> request,
const std::shared_ptr<CameraSetupStreaming::Response> response);
bool start_camera_stream(CameraImageCallback callback, void* user_data,
const E_DjiLiveViewCameraPosition payload_index,
const E_DjiLiveViewCameraSource camera_source);
bool stop_main_camera_stream(const E_DjiLiveViewCameraPosition payload_index,
const E_DjiLiveViewCameraSource camera_source);
void publish_main_camera_images(CameraRGBImage rgb_img, void* user_data);
void publish_main_camera_images(const uint8_t* buffer,
uint32_t buffer_length);
void publish_fpv_camera_images(CameraRGBImage rgb_img, void* user_data);
void publish_fpv_camera_images(const uint8_t* buffer, uint32_t buffer_length);
std::string get_optical_frame_id();
rclcpp::Service<CameraSetupStreaming>::SharedPtr
camera_setup_streaming_service_;
rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>::SharedPtr
main_camera_stream_pub_;
rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>::SharedPtr
fpv_camera_stream_pub_;
std::map<::E_DjiLiveViewCameraPosition, DJICameraStreamDecoder*>
stream_decoder_;
E_DjiLiveViewCameraSource selected_camera_source_;
const rmw_qos_profile_t& qos_profile_{rmw_qos_profile_services_default};
bool decode_stream_{true};
bool is_module_initialized_{false};
E_DjiLiveViewCameraPosition payload_index_;
mutable std::shared_mutex global_ptr_mutex_;
};
extern std::shared_ptr<LiveviewModule> global_liveview_ptr_;
} // namespace psdk_ros2
#endif // PSDK_WRAPPER_INCLUDE_PSDK_WRAPPER_MODULES_LIVEVIEW_HPP_