rm_control
Loading...
Searching...
No Matches
video_transmission_sender.h
Go to the documentation of this file.
1//
2// Created by ljyi on 2026/4/6.
3//
4
5#pragma once
6
7#include <ros/ros.h>
8#include <cstring>
9#include "common/data.h"
10#include "common/protocol.h"
11#include "rm_msgs/VideoPacket.h"
12
13namespace rm_vt
14{
16{
17public:
18 explicit VideoTransmissionSender(ros::NodeHandle& nh, Base& base) : base_(base)
19 {
20 ROS_INFO("Video transmission sender load.");
21 deploy_video_stream_sub_ = nh.subscribe("/video_stream", 10, &VideoTransmissionSender::deployVideoStreamCB, this);
22 }
23 virtual ~VideoTransmissionSender() = default;
24
25private:
26 void deployVideoStreamCB(const rm_msgs::VideoPacketConstPtr& msg);
27 void sendDeployVideoStream(const uint8_t* data);
28 void pack(uint8_t* tx_buffer, uint8_t* data, int cmd_id, int len);
29 void clearTxBuffer()
30 {
31 for (int i = 0; i < k_frame_length_; i++)
32 tx_buffer_[i] = 0;
33 tx_len_ = 0;
34 }
35
36 ros::Subscriber deploy_video_stream_sub_;
37 ros::Time deploy_video_stream_last_send_;
38 Base& base_;
39 uint8_t tx_buffer_[309]{};
40 int tx_len_{};
41
42 const int k_frame_length_ = 309, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
43};
44
45} // namespace rm_vt
Definition data.h:31
Definition video_transmission_sender.h:16
virtual ~VideoTransmissionSender()=default
VideoTransmissionSender(ros::NodeHandle &nh, Base &base)
Definition video_transmission_sender.h:18
Definition data.h:29