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"
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/ChassisCmd.h>
65#include <rm_msgs/GameStatus.h>
66#include <rm_msgs/RfidStatus.h>
67#include <rm_msgs/EngineerUi.h>
68#include <rm_msgs/GameRobotHp.h>
69#include <rm_msgs/BalanceState.h>
70#include <rm_msgs/DartClientCmd.h>
71#include <rm_msgs/ActuatorState.h>
72#include <rm_msgs/MapSentryData.h>
73#include <rm_msgs/RadarMarkData.h>
74#include <rm_msgs/PowerHeatData.h>
75#include <rm_msgs/GimbalDesError.h>
76#include <rm_msgs/BulletAllowance.h>
77#include <rm_msgs/GameRobotStatus.h>
78#include <rm_msgs/ManualToReferee.h>
79#include <rm_msgs/ClientMapSendData.h>
80#include <rm_msgs/RobotsPositionData.h>
81#include <rm_msgs/DartInfo.h>
82#include <rm_msgs/StatusChangeRequest.h>
83#include <rm_msgs/ClientMapReceiveData.h>
84#include <rm_msgs/SupplyProjectileAction.h>
85#include <rm_msgs/IcraBuffDebuffZoneStatus.h>
86#include <rm_msgs/GameRobotPosData.h>
87#include "rm_msgs/SentryInfo.h"
88#include "rm_msgs/SentryCmd.h"
89#include "rm_msgs/RadarInfo.h"
90#include "rm_msgs/RadarCmd.h"
91#include "rm_msgs/Buff.h"
92#include "rm_msgs/TrackData.h"
93#include "rm_msgs/SentryAttackingTarget.h"
94#include "rm_msgs/RadarToSentry.h"
95#include "rm_msgs/RadarWirelessEnemyRobotPos.h"
96#include "rm_msgs/RadarWirelessEnemyRobotHp.h"
97#include "rm_msgs/RadarWirelessEnemyProjectileAllowance.h"
98#include "rm_msgs/RadarWirelessEnemyCoinAndFieldStatus.h"
99#include "rm_msgs/RadarWirelessEnemyRobotBuff.h"
100#include "rm_msgs/RadarWirelessEnemyCallSign.h"
101#include <rm_msgs/PowerManagementSampleAndStatusData.h>
102#include <rm_msgs/PowerManagementSystemExceptionData.h>
103#include <rm_msgs/PowerManagementInitializationExceptionData.h>
104#include <rm_msgs/PowerManagementProcessStackOverflowData.h>
105#include <rm_msgs/PowerManagementUnknownExceptionData.h>
131 serial::Timeout timeout = serial::Timeout::simpleTimeout(50);
132 serial_.setPort(
"/dev/usbReferee");
141 catch (serial::IOException& e)
143 ROS_ERROR(
"Cannot open referee port");
148 uint8_t
getCRC8CheckSum(
unsigned char* pch_message,
unsigned int dw_length,
unsigned char uc_crc_8)
150 unsigned char uc_index;
153 uc_index = uc_crc_8 ^ (*pch_message++);
161 unsigned char uc_expected;
162 if ((pch_message ==
nullptr) || (dw_length <= 2))
165 return (uc_expected == pch_message[dw_length - 1]);
170 unsigned char uc_crc;
171 if ((pch_message ==
nullptr) || (dw_length <= 2))
174 pch_message[dw_length - 1] = uc_crc;
180 if (pch_message ==
nullptr)
184 chData = *pch_message++;
185 (w_crc) = (
static_cast<uint16_t
>(w_crc) >> 8) ^
194 if ((pch_message ==
nullptr) || (dw_length <= 2))
197 return ((w_expected & 0xff) == pch_message[dw_length - 2] &&
198 ((w_expected >> 8) & 0xff) == pch_message[dw_length - 1]);
204 if ((pch_message ==
nullptr) || (dw_length <= 2))
207 pch_message[dw_length - 2] =
static_cast<uint8_t
>((wCRC & 0x00ff));
208 pch_message[dw_length - 1] =
static_cast<uint8_t
>(((wCRC >> 8) & 0x00ff));
serial::Serial serial_
Definition data.h:121
int capacity_recent_mode_
Definition data.h:125
int client_id_
Definition data.h:123
uint8_t getCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length, unsigned char uc_crc_8)
Definition data.h:148
std::string robot_color_
Definition data.h:126
void appendCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition data.h:168
void appendCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition data.h:201
uint32_t verifyCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition data.h:159
void initSerial()
Definition data.h:129
bool referee_data_is_online_
Definition data.h:127
int robot_id_
Definition data.h:124
uint16_t getCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length, uint16_t w_crc)
Definition data.h:177
int capacity_expect_mode_
Definition data.h:125
uint32_t verifyCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition data.h:191
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
double chassis_power
Definition data.h:111
double limit_power
Definition data.h:112
double cap_power
Definition data.h:114
bool is_online
Definition data.h:115
double buffer_power
Definition data.h:113