rm_control
Loading...
Searching...
No Matches
data.h
Go to the documentation of this file.
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2021, Qiayuan Liao
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions are met:
9 *
10 * * Redistributions of source code must retain the above copyright notice, this
11 * list of conditions and the following disclaimer.
12 *
13 * * Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * and/or other materials provided with the distribution.
16 *
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived from
19 * this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24 * ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 *******************************************************************************/
33
34//
35// Created by peter on 2021/7/17.
36//
37
38#pragma once
39
40#include <ros/ros.h>
41#include <unistd.h>
42#include <serial/serial.h>
43#include <nav_msgs/Odometry.h>
44#include <sensor_msgs/JointState.h>
45#include <std_msgs/Float64.h>
46#include <std_msgs/Int8MultiArray.h>
47#include <tf2_ros/buffer.h>
48#include <tf2_ros/transform_listener.h>
49#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
50#include "std_msgs/UInt32.h"
51#include "rm_msgs/VisualizeStateData.h"
52
54
55#include <rm_msgs/ShootCmd.h>
56#include <rm_msgs/ShootState.h>
57#include <rm_msgs/DbusData.h>
58#include <rm_msgs/StateCmd.h>
59#include <rm_msgs/EventData.h>
60#include <rm_msgs/GimbalCmd.h>
61#include <rm_msgs/RobotHurt.h>
62#include <rm_msgs/ShootData.h>
63#include <rm_msgs/DartStatus.h>
64#include <rm_msgs/ChassisActiveSusCmd.h>
65#include <rm_msgs/ChassisCmd.h>
66#include <rm_msgs/GameStatus.h>
67#include <rm_msgs/RfidStatus.h>
68#include <rm_msgs/EngineerUi.h>
69#include <rm_msgs/GameRobotHp.h>
70#include <rm_msgs/BalanceState.h>
71#include <rm_msgs/DartClientCmd.h>
72#include <rm_msgs/ActuatorState.h>
73#include <rm_msgs/MapSentryData.h>
74#include <rm_msgs/RadarMarkData.h>
75#include <rm_msgs/PowerHeatData.h>
76#include <rm_msgs/GimbalDesError.h>
77#include <rm_msgs/BulletAllowance.h>
78#include <rm_msgs/GameRobotStatus.h>
79#include <rm_msgs/ManualToReferee.h>
80#include <rm_msgs/ClientMapSendData.h>
81#include <rm_msgs/RobotsPositionData.h>
82#include <rm_msgs/DartInfo.h>
83#include <rm_msgs/StatusChangeRequest.h>
84#include <rm_msgs/ClientMapReceiveData.h>
85#include <rm_msgs/SupplyProjectileAction.h>
86#include <rm_msgs/IcraBuffDebuffZoneStatus.h>
87#include <rm_msgs/GameRobotPosData.h>
88#include "rm_msgs/SentryInfo.h"
89#include "rm_msgs/SentryCmd.h"
90#include "rm_msgs/RadarInfo.h"
91#include "rm_msgs/RadarCmd.h"
92#include "rm_msgs/Buff.h"
93#include "rm_msgs/TrackData.h"
94#include "rm_msgs/SentryAttackingTarget.h"
95#include "rm_msgs/RadarToSentry.h"
96#include "rm_msgs/RadarWirelessEnemyRobotPos.h"
97#include "rm_msgs/RadarWirelessEnemyRobotHp.h"
98#include "rm_msgs/RadarWirelessEnemyProjectileAllowance.h"
99#include "rm_msgs/RadarWirelessEnemyCoinAndFieldStatus.h"
100#include "rm_msgs/RadarWirelessEnemyRobotBuff.h"
101#include "rm_msgs/RadarWirelessEnemyCallSign.h"
102#include <rm_msgs/PowerManagementSampleAndStatusData.h>
103#include <rm_msgs/PowerManagementSystemExceptionData.h>
104#include <rm_msgs/PowerManagementInitializationExceptionData.h>
105#include <rm_msgs/PowerManagementProcessStackOverflowData.h>
106#include <rm_msgs/PowerManagementUnknownExceptionData.h>
107
108namespace rm_referee
109{
111{
115 double cap_power;
116 bool is_online = false;
117};
118
119class Base
120{
121public:
122 serial::Serial serial_;
123
124 int client_id_ = 0; // recipient's id
125 int robot_id_ = 0; // recent robot's id
127 std::string robot_color_;
129
131 {
132 serial::Timeout timeout = serial::Timeout::simpleTimeout(50);
133 serial_.setPort("/dev/usbReferee");
134 serial_.setBaudrate(115200);
135 serial_.setTimeout(timeout);
136 if (serial_.isOpen())
137 return;
138 try
139 {
140 serial_.open();
141 }
142 catch (serial::IOException& e)
143 {
144 ROS_ERROR("Cannot open referee port");
145 }
146 }
147
148 // CRC check
149 uint8_t getCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length, unsigned char uc_crc_8)
150 {
151 unsigned char uc_index;
152 while (dw_length--)
153 {
154 uc_index = uc_crc_8 ^ (*pch_message++);
155 uc_crc_8 = rm_referee::kCrc8Table[uc_index];
156 }
157 return (uc_crc_8);
158 }
159
160 uint32_t verifyCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length)
161 {
162 unsigned char uc_expected;
163 if ((pch_message == nullptr) || (dw_length <= 2))
164 return 0;
165 uc_expected = getCRC8CheckSum(pch_message, dw_length - 1, rm_referee::kCrc8Init);
166 return (uc_expected == pch_message[dw_length - 1]);
167 }
168
169 void appendCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length)
170 {
171 unsigned char uc_crc;
172 if ((pch_message == nullptr) || (dw_length <= 2))
173 return;
174 uc_crc = getCRC8CheckSum((unsigned char*)pch_message, dw_length - 1, rm_referee::kCrc8Init);
175 pch_message[dw_length - 1] = uc_crc;
176 }
177
178 uint16_t getCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length, uint16_t w_crc)
179 {
180 uint8_t chData;
181 if (pch_message == nullptr)
182 return 0xFFFF;
183 while (dw_length--)
184 {
185 chData = *pch_message++;
186 (w_crc) = (static_cast<uint16_t>(w_crc) >> 8) ^
187 rm_referee::wCRC_table[(static_cast<uint16_t>(w_crc) ^ static_cast<uint16_t>(chData)) & 0x00ff];
188 }
189 return w_crc;
190 }
191
192 uint32_t verifyCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length)
193 {
194 uint16_t w_expected;
195 if ((pch_message == nullptr) || (dw_length <= 2))
196 return 0;
197 w_expected = getCRC16CheckSum(pch_message, dw_length - 2, rm_referee::kCrc16Init);
198 return ((w_expected & 0xff) == pch_message[dw_length - 2] &&
199 ((w_expected >> 8) & 0xff) == pch_message[dw_length - 1]);
200 }
201
202 void appendCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length)
203 {
204 uint16_t wCRC;
205 if ((pch_message == nullptr) || (dw_length <= 2))
206 return;
207 wCRC = getCRC16CheckSum(static_cast<uint8_t*>(pch_message), dw_length - 2, rm_referee::kCrc16Init);
208 pch_message[dw_length - 2] = static_cast<uint8_t>((wCRC & 0x00ff));
209 pch_message[dw_length - 1] = static_cast<uint8_t>(((wCRC >> 8) & 0x00ff));
210 }
211};
212} // namespace rm_referee
Definition data.h:120
serial::Serial serial_
Definition data.h:122
int capacity_recent_mode_
Definition data.h:126
int client_id_
Definition data.h:124
uint8_t getCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length, unsigned char uc_crc_8)
Definition data.h:149
std::string robot_color_
Definition data.h:127
void appendCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition data.h:169
void appendCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition data.h:202
uint32_t verifyCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition data.h:160
void initSerial()
Definition data.h:130
bool referee_data_is_online_
Definition data.h:128
int robot_id_
Definition data.h:125
uint16_t getCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length, uint16_t w_crc)
Definition data.h:178
int capacity_expect_mode_
Definition data.h:126
uint32_t verifyCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition data.h:192
Definition data.h:109
const uint8_t kCrc8Init
Definition protocol.h:847
const uint8_t kCrc8Table[256]
Definition protocol.h:848
const uint16_t kCrc16Init
Definition protocol.h:864
const uint16_t wCRC_table[256]
Definition protocol.h:865
Definition data.h:111
double chassis_power
Definition data.h:112
double limit_power
Definition data.h:113
double cap_power
Definition data.h:115
bool is_online
Definition data.h:116
double buffer_power
Definition data.h:114