rm_control
Loading...
Searching...
No Matches
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);
22 robot_custom_data_pub_ = nh.advertise<rm_msgs::RobotCustomData>("robot_custom_data", 1);
23 robot_custom_data_2_pub_ = nh.advertise<rm_msgs::RobotCustomData2>("robot_custom_data_2", 1);
24 custom_client_cmd_pub_ = nh.advertise<rm_msgs::CustomClientCmdData>("custom_client_cmd_data", 1);
26 }
27 void read();
29 {
30 rx_buffer_.clear();
31 rx_len_ = 0;
32 }
33
36
38 std::vector<uint8_t> rx_buffer_;
40
41private:
42 int unpack(uint8_t* rx_data);
43 int control_data_unpack(uint8_t* rx_data);
44 ros::Time last_get_data_time_;
45 const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
46 const int k_unpack_buffer_length_ = 256;
47 uint8_t unpack_buffer_[256]{};
48};
49} // namespace rm_vt
Definition data.h:31
void initSerial()
Definition data.h:36
Definition video_transmission.h:14
Base base_
Definition video_transmission.h:37
ros::Publisher custom_client_cmd_pub_
Definition video_transmission.h:35
std::vector< uint8_t > rx_buffer_
Definition video_transmission.h:38
void clearRxBuffer()
Definition video_transmission.h:28
ros::Publisher custom_controller_cmd_pub_
Definition video_transmission.h:34
ros::Publisher vt_keyboard_mouse_pub_
Definition video_transmission.h:34
ros::Publisher robot_custom_data_2_pub_
Definition video_transmission.h:35
ros::Publisher robot_custom_data_pub_
Definition video_transmission.h:35
ros::Publisher vt_receiver_control_pub_
Definition video_transmission.h:34
void read()
Definition video_transmission.cpp:8
int rx_len_
Definition video_transmission.h:39
VideoTransmission(ros::NodeHandle &nh)
Definition video_transmission.h:16
Definition data.h:29