18 ROS_INFO(
"Video transmission load.");
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]{};
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