rm_control
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
video_transmission.h
Go to the documentation of this file.
1//
2// Created by ch on 24-11-23.
3//
4#pragma once
5
6#include <cstdint>
7#include <ros/ros.h>
8
9#include "rm_vt/common/data.h"
10
11namespace rm_vt
12{
14{
15public:
16 explicit VideoTransmission(ros::NodeHandle& nh) : last_get_data_time_(ros::Time::now())
17 {
18 ROS_INFO("Video transmission load.");
19 custom_controller_cmd_pub_ = nh.advertise<rm_msgs::CustomControllerData>("custom_controller_data", 1);
20 vt_keyboard_mouse_pub_ = nh.advertise<rm_msgs::VTKeyboardMouseData>("keyboard_mouse_data", 1);
21 vt_receiver_control_pub_ = nh.advertise<rm_msgs::VTReceiverControlData>("receiver_control_data", 1);
23 }
24 void read();
26 {
27 rx_buffer_.clear();
28 rx_len_ = 0;
29 }
30
32
34 std::vector<uint8_t> rx_buffer_;
36
37private:
38 int unpack(uint8_t* rx_data);
39 int control_data_unpack(uint8_t* rx_data);
40 ros::Time last_get_data_time_;
41 const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
42 const int k_unpack_buffer_length_ = 256;
43 uint8_t unpack_buffer_[256]{};
44};
45} // namespace rm_vt
Definition data.h:28
void initSerial()
Definition data.h:33
Definition video_transmission.h:14
Base base_
Definition video_transmission.h:33
std::vector< uint8_t > rx_buffer_
Definition video_transmission.h:34
void clearRxBuffer()
Definition video_transmission.h:25
ros::Publisher custom_controller_cmd_pub_
Definition video_transmission.h:31
ros::Publisher vt_keyboard_mouse_pub_
Definition video_transmission.h:31
ros::Publisher vt_receiver_control_pub_
Definition video_transmission.h:31
void read()
Definition video_transmission.cpp:8
int rx_len_
Definition video_transmission.h:35
VideoTransmission(ros::NodeHandle &nh)
Definition video_transmission.h:16
Definition data.h:26