rm_control
Loading...
Searching...
No Matches
data.h
Go to the documentation of this file.
1//
2// Created by ch on 24-11-23.
3//
4
5#pragma once
6
7#include <ros/ros.h>
8#include <unistd.h>
9#include <serial/serial.h>
10#include <nav_msgs/Odometry.h>
11#include <sensor_msgs/JointState.h>
12#include <std_msgs/Float64.h>
13#include <std_msgs/Int8MultiArray.h>
14#include <tf2_ros/buffer.h>
15#include <tf2_ros/transform_listener.h>
16#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
17#include "std_msgs/UInt32.h"
18#include "rm_msgs/VisualizeStateData.h"
19#include "rm_msgs/CustomControllerData.h"
20#include "rm_msgs/VTKeyboardMouseData.h"
21#include "rm_msgs/VTReceiverControlData.h"
22#include "rm_msgs/RobotCustomData.h"
23#include "rm_msgs/RobotCustomData2.h"
24#include "rm_msgs/CustomClientCmdData.h"
25
27
28namespace rm_vt
29{
30class Base
31{
32public:
33 serial::Serial serial_;
35
37 {
38 serial::Timeout timeout = serial::Timeout::simpleTimeout(50);
39 serial_.setPort("/dev/usbImagetran");
40 serial_.setBaudrate(921600);
41 serial_.setTimeout(timeout);
42 if (serial_.isOpen())
43 return;
44 try
45 {
46 serial_.open();
47 }
48 catch (serial::IOException& e)
49 {
50 ROS_ERROR("Cannot open image transmitter port");
51 }
52 }
53
54 // CRC check
55 uint8_t getCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length, unsigned char uc_crc_8)
56 {
57 unsigned char uc_index;
58 while (dw_length--)
59 {
60 uc_index = uc_crc_8 ^ (*pch_message++);
61 uc_crc_8 = rm_vt::kCrc8Table[uc_index];
62 }
63 return (uc_crc_8);
64 }
65
66 uint32_t verifyCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length)
67 {
68 unsigned char uc_expected;
69 if ((pch_message == nullptr) || (dw_length <= 2))
70 return 0;
71 uc_expected = getCRC8CheckSum(pch_message, dw_length - 1, rm_vt::kCrc8Init);
72 return (uc_expected == pch_message[dw_length - 1]);
73 }
74
75 void appendCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length)
76 {
77 unsigned char uc_crc;
78 if ((pch_message == nullptr) || (dw_length <= 2))
79 return;
80 uc_crc = getCRC8CheckSum((unsigned char*)pch_message, dw_length - 1, rm_vt::kCrc8Init);
81 pch_message[dw_length - 1] = uc_crc;
82 }
83
84 uint16_t getCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length, uint16_t w_crc)
85 {
86 uint8_t chData;
87 if (pch_message == nullptr)
88 return 0xFFFF;
89 while (dw_length--)
90 {
91 chData = *pch_message++;
92 (w_crc) = (static_cast<uint16_t>(w_crc) >> 8) ^
93 rm_vt::wCRC_table[(static_cast<uint16_t>(w_crc) ^ static_cast<uint16_t>(chData)) & 0x00ff];
94 }
95 return w_crc;
96 }
97
98 uint32_t verifyCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length)
99 {
100 uint16_t w_expected;
101 if ((pch_message == nullptr) || (dw_length <= 2))
102 return 0;
103 w_expected = getCRC16CheckSum(pch_message, dw_length - 2, rm_vt::kCrc16Init);
104 return ((w_expected & 0xff) == pch_message[dw_length - 2] &&
105 ((w_expected >> 8) & 0xff) == pch_message[dw_length - 1]);
106 }
107
108 void appendCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length)
109 {
110 uint16_t wCRC;
111 if ((pch_message == nullptr) || (dw_length <= 2))
112 return;
113 wCRC = getCRC16CheckSum(static_cast<uint8_t*>(pch_message), dw_length - 2, rm_vt::kCrc16Init);
114 pch_message[dw_length - 2] = static_cast<uint8_t>((wCRC & 0x00ff));
115 pch_message[dw_length - 1] = static_cast<uint8_t>(((wCRC >> 8) & 0x00ff));
116 }
117};
118} // namespace rm_vt
Definition data.h:31
uint32_t verifyCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition data.h:66
serial::Serial serial_
Definition data.h:33
void initSerial()
Definition data.h:36
uint8_t getCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length, unsigned char uc_crc_8)
Definition data.h:55
void appendCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition data.h:108
uint32_t verifyCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition data.h:98
bool video_transmission_is_online_
Definition data.h:34
void appendCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition data.h:75
uint16_t getCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length, uint16_t w_crc)
Definition data.h:84
Definition data.h:29
const uint16_t wCRC_table[256]
Definition protocol.h:165
const uint16_t kCrc16Init
Definition protocol.h:164
const uint8_t kCrc8Init
Definition protocol.h:147
const uint8_t kCrc8Table[256]
Definition protocol.h:148