referee.cpp
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/5/17.
36 //
37 #include "rm_referee/referee.h"
38 
39 namespace rm_referee
40 {
41 // read data from referee
42 void Referee::read()
43 {
44  if (base_.serial_.available())
45  {
46  rx_len_ = static_cast<int>(base_.serial_.available());
48  }
49  else
50  return;
51  uint8_t temp_buffer[256] = { 0 };
52  int frame_len;
56  {
57  for (int k_i = 0; k_i < k_unpack_buffer_length_ - rx_len_; ++k_i)
58  temp_buffer[k_i] = unpack_buffer_[k_i + rx_len_];
59  for (int k_i = 0; k_i < rx_len_; ++k_i)
60  temp_buffer[k_i + k_unpack_buffer_length_ - rx_len_] = rx_buffer_[k_i];
61  for (int k_i = 0; k_i < k_unpack_buffer_length_; ++k_i)
62  unpack_buffer_[k_i] = temp_buffer[k_i];
63  }
64  for (int k_i = 0; k_i < k_unpack_buffer_length_ - k_frame_length_; ++k_i)
65  {
66  if (unpack_buffer_[k_i] == 0xA5)
67  {
68  frame_len = unpack(&unpack_buffer_[k_i]);
69  if (frame_len != -1)
70  k_i += frame_len;
71  }
72  }
74  clearRxBuffer();
75 }
76 
77 int Referee::unpack(uint8_t* rx_data)
78 {
79  uint16_t cmd_id;
80  int frame_len;
81  rm_referee::FrameHeader frame_header;
82 
83  memcpy(&frame_header, rx_data, k_header_length_);
84  if (static_cast<bool>(base_.verifyCRC8CheckSum(rx_data, k_header_length_)))
85  {
86  if (frame_header.data_length > 256) // temporary and inaccurate value
87  {
88  ROS_INFO("discard possible wrong frames, data length: %d", frame_header.data_length);
89  return 0;
90  }
91  frame_len = frame_header.data_length + k_header_length_ + k_cmd_id_length_ + k_tail_length_;
92  if (base_.verifyCRC16CheckSum(rx_data, frame_len) == 1)
93  {
94  cmd_id = (rx_data[6] << 8 | rx_data[5]);
95  switch (cmd_id)
96  {
98  {
99  rm_referee::GameStatus game_status_ref;
100  rm_msgs::GameStatus game_status_data;
101  memcpy(&game_status_ref, rx_data + 7, sizeof(rm_referee::GameStatus));
102 
103  game_status_data.game_type = game_status_ref.game_type;
104  game_status_data.game_progress = game_status_ref.game_progress;
105  game_status_data.stage_remain_time = game_status_ref.stage_remain_time;
106  game_status_data.sync_time_stamp = game_status_ref.sync_time_stamp;
107  game_status_data.stamp = last_get_data_time_;
108 
110  game_status_pub_.publish(game_status_data);
111  break;
112  }
114  {
115  rm_referee::GameResult game_result_ref;
116  memcpy(&game_result_ref, rx_data + 7, sizeof(rm_referee::GameResult));
117  break;
118  }
120  {
121  rm_referee::GameRobotHp game_robot_hp_ref;
122  rm_msgs::GameRobotHp game_robot_hp_data;
123  memcpy(&game_robot_hp_ref, rx_data + 7, sizeof(rm_referee::GameRobotHp));
124 
125  game_robot_hp_data.blue_1_robot_hp = game_robot_hp_ref.blue_1_robot_hp;
126  game_robot_hp_data.blue_2_robot_hp = game_robot_hp_ref.blue_2_robot_hp;
127  game_robot_hp_data.blue_3_robot_hp = game_robot_hp_ref.blue_3_robot_hp;
128  game_robot_hp_data.blue_4_robot_hp = game_robot_hp_ref.blue_4_robot_hp;
129  game_robot_hp_data.blue_7_robot_hp = game_robot_hp_ref.blue_7_robot_hp;
130  game_robot_hp_data.blue_outpost_hp = game_robot_hp_ref.blue_outpost_hp;
131  game_robot_hp_data.blue_base_hp = game_robot_hp_ref.blue_base_hp;
132  game_robot_hp_data.red_1_robot_hp = game_robot_hp_ref.red_1_robot_hp;
133  game_robot_hp_data.red_2_robot_hp = game_robot_hp_ref.red_2_robot_hp;
134  game_robot_hp_data.red_3_robot_hp = game_robot_hp_ref.red_3_robot_hp;
135  game_robot_hp_data.red_4_robot_hp = game_robot_hp_ref.red_4_robot_hp;
136  game_robot_hp_data.red_7_robot_hp = game_robot_hp_ref.red_7_robot_hp;
137  game_robot_hp_data.red_outpost_hp = game_robot_hp_ref.red_outpost_hp;
138  game_robot_hp_data.red_base_hp = game_robot_hp_ref.red_base_hp;
139  game_robot_hp_data.stamp = last_get_data_time_;
140 
141  referee_ui_.updateHeroHitDataCallBack(game_robot_hp_data);
142  game_robot_hp_pub_.publish(game_robot_hp_data);
143  break;
144  }
146  {
147  rm_referee::DartStatus dart_status_ref;
148  rm_msgs::DartStatus dart_status_data;
149  memcpy(&dart_status_ref, rx_data + 7, sizeof(rm_referee::DartStatus));
150 
151  dart_status_data.dart_belong = dart_status_ref.dart_belong;
152  dart_status_data.stage_remaining_time = dart_status_ref.stage_remaining_time;
153  dart_status_data.stamp = last_get_data_time_;
154 
155  dart_status_pub_.publish(dart_status_data);
156  break;
157  }
159  {
160  rm_referee::IcraBuffDebuffZoneStatus icra_buff_debuff_zone_status_ref;
161  rm_msgs::IcraBuffDebuffZoneStatus icra_buff_debuff_zone_status_data;
162  memcpy(&icra_buff_debuff_zone_status_ref, rx_data + 7, sizeof(rm_referee::IcraBuffDebuffZoneStatus));
163 
164  icra_buff_debuff_zone_status_data.blue_1_bullet_left = icra_buff_debuff_zone_status_ref.blue_1_bullet_left;
165  icra_buff_debuff_zone_status_data.blue_2_bullet_left = icra_buff_debuff_zone_status_ref.blue_2_bullet_left;
166  icra_buff_debuff_zone_status_data.red_1_bullet_left = icra_buff_debuff_zone_status_ref.red_1_bullet_left;
167  icra_buff_debuff_zone_status_data.red_2_bullet_left = icra_buff_debuff_zone_status_ref.red_2_bullet_left;
168  icra_buff_debuff_zone_status_data.f_1_zone_buff_debuff_status =
169  icra_buff_debuff_zone_status_ref.f_1_zone_buff_debuff_status;
170  icra_buff_debuff_zone_status_data.f_1_zone_status = icra_buff_debuff_zone_status_ref.f_1_zone_status;
171  icra_buff_debuff_zone_status_data.f_2_zone_buff_debuff_status =
172  icra_buff_debuff_zone_status_ref.f_2_zone_buff_debuff_status;
173  icra_buff_debuff_zone_status_data.f_2_zone_status = icra_buff_debuff_zone_status_ref.f_2_zone_status;
174  icra_buff_debuff_zone_status_data.f_3_zone_buff_debuff_status =
175  icra_buff_debuff_zone_status_ref.f_3_zone_buff_debuff_status;
176  icra_buff_debuff_zone_status_data.f_3_zone_status = icra_buff_debuff_zone_status_ref.f_3_zone_status;
177  icra_buff_debuff_zone_status_data.f_4_zone_buff_debuff_status =
178  icra_buff_debuff_zone_status_ref.f_4_zone_buff_debuff_status;
179  icra_buff_debuff_zone_status_data.f_4_zone_status = icra_buff_debuff_zone_status_ref.f_4_zone_status;
180  icra_buff_debuff_zone_status_data.f_5_zone_buff_debuff_status =
181  icra_buff_debuff_zone_status_ref.f_5_zone_buff_debuff_status;
182  icra_buff_debuff_zone_status_data.f_5_zone_status = icra_buff_debuff_zone_status_ref.f_5_zone_status;
183  icra_buff_debuff_zone_status_data.f_6_zone_buff_debuff_status =
184  icra_buff_debuff_zone_status_ref.f_6_zone_buff_debuff_status;
185  icra_buff_debuff_zone_status_data.f_6_zone_status = icra_buff_debuff_zone_status_ref.f_6_zone_status;
186  icra_buff_debuff_zone_status_data.stamp = last_get_data_time_;
187 
188  icra_buff_debuff_zone_status_pub_.publish(icra_buff_debuff_zone_status_data);
189  break;
190  }
192  {
193  rm_referee::EventData event_ref;
194  rm_msgs::EventData event_data;
195  memcpy(&event_ref, rx_data + 7, sizeof(rm_referee::EventData));
196 
197  event_data.overlapping_supply_station_state = event_ref.overlapping_supply_station_state;
198  event_data.nan_overlapping_supply_station_state = event_ref.nan_overlapping_supply_station_state;
199  event_data.supplier_zone_state = event_ref.supplier_zone_state;
200  event_data.small_power_rune_state = event_ref.small_power_rune_state;
201  event_data.large_power_rune_state = event_ref.small_power_rune_state;
202  event_data.central_elevated_ground_state = event_ref.central_elevated_ground_state;
203  event_data.trapezoidal_elevated_ground_state = event_ref.trapezoidal_elevated_ground_state;
204  event_data.be_hit_time = event_ref.be_hit_time;
205  event_data.be_hit_target = event_ref.be_hit_target;
206  event_data.central_point_state = event_ref.central_point_state;
207  event_data.stamp = last_get_data_time_;
208 
209  event_data_pub_.publish(event_data);
210  break;
211  }
213  {
214  rm_referee::SupplyProjectileAction supply_projectile_action_ref;
215  rm_msgs::SupplyProjectileAction supply_projectile_action_data;
216  memcpy(&supply_projectile_action_ref, rx_data + 7, sizeof(rm_referee::SupplyProjectileAction));
217 
218  supply_projectile_action_data.reserved = supply_projectile_action_ref.reserved;
219  supply_projectile_action_data.supply_projectile_num = supply_projectile_action_ref.supply_projectile_num;
220  supply_projectile_action_data.supply_projectile_step = supply_projectile_action_ref.supply_projectile_step;
221  supply_projectile_action_data.supply_robot_id = supply_projectile_action_ref.supply_robot_id;
222  supply_projectile_action_data.stamp = last_get_data_time_;
223 
224  referee_ui_.supplyBulletDataCallBack(supply_projectile_action_data);
225  supply_projectile_action_pub_.publish(supply_projectile_action_data);
226  break;
227  }
229  {
230  rm_referee::RefereeWarning referee_warning_ref;
231  memcpy(&referee_warning_ref, rx_data + 7, sizeof(rm_referee::RefereeWarning));
232  break;
233  }
235  {
236  rm_referee::DartInfo dart_info_ref;
237  rm_msgs::DartInfo dart_info_data;
238  memcpy(&dart_info_ref, rx_data + 7, sizeof(rm_referee::DartInfo));
239 
240  dart_info_data.dart_remaining_time = dart_info_ref.dart_remaining_time;
241  dart_info_data.dart_last_aim_state = dart_info_ref.dart_last_aim_state;
242  dart_info_data.enemy_total_hit_received = dart_info_ref.enemy_total_hit_received;
243  dart_info_data.dart_current_target = dart_info_ref.dart_current_target;
244  dart_info_data.stamp = last_get_data_time_;
245 
246  dart_info_pub_.publish(dart_info_data);
247  break;
248  }
250  {
251  rm_referee::GameRobotStatus game_robot_status_ref;
252  rm_msgs::GameRobotStatus game_robot_status_data;
253  memcpy(&game_robot_status_ref, rx_data + 7, sizeof(rm_referee::GameRobotStatus));
254 
255  game_robot_status_data.remain_hp = game_robot_status_ref.remain_hp;
256  game_robot_status_data.robot_level = game_robot_status_ref.robot_level;
257  game_robot_status_data.max_hp = game_robot_status_ref.max_hp;
258  game_robot_status_data.shooter_cooling_limit = game_robot_status_ref.shooter_cooling_limit;
259  game_robot_status_data.shooter_cooling_rate = game_robot_status_ref.shooter_cooling_rate;
260  game_robot_status_data.chassis_power_limit = game_robot_status_ref.chassis_power_limit;
261  game_robot_status_data.mains_power_chassis_output = game_robot_status_ref.mains_power_chassis_output;
262  game_robot_status_data.mains_power_gimbal_output = game_robot_status_ref.mains_power_gimbal_output;
263  game_robot_status_data.mains_power_shooter_output = game_robot_status_ref.mains_power_shooter_output;
264  game_robot_status_data.robot_id = game_robot_status_ref.robot_id;
265  base_.robot_id_ = game_robot_status_ref.robot_id;
266  game_robot_status_data.stamp = last_get_data_time_;
267 
269  game_robot_status_pub_.publish(game_robot_status_data);
270  break;
271  }
273  {
274  rm_referee::PowerHeatData power_heat_ref;
275  rm_msgs::PowerHeatData power_heat_data;
276  memcpy(&power_heat_ref, rx_data + 7, sizeof(rm_referee::PowerHeatData));
277 
278  power_heat_data.chassis_power_buffer = power_heat_ref.chassis_power_buffer;
279  power_heat_data.shooter_id_1_17_mm_cooling_heat = power_heat_ref.shooter_id_1_17_mm_cooling_heat;
280  power_heat_data.shooter_id_2_17_mm_cooling_heat = power_heat_ref.shooter_id_2_17_mm_cooling_heat;
281  power_heat_data.shooter_id_1_42_mm_cooling_heat = power_heat_ref.shooter_id_1_42_mm_cooling_heat;
282 
283  power_heat_data.stamp = last_get_data_time_;
284 
285  power_heat_data_pub_.publish(power_heat_data);
286  break;
287  }
289  {
290  rm_referee::GameRobotPos game_robot_pos_ref;
291  rm_msgs::GameRobotPosData game_robot_pos_data;
292  memcpy(&game_robot_pos_ref, rx_data + 7, sizeof(rm_referee::GameRobotPos));
293 
294  game_robot_pos_data.x = game_robot_pos_ref.x;
295  game_robot_pos_data.y = game_robot_pos_ref.y;
296  game_robot_pos_data.yaw = game_robot_pos_ref.yaw;
297  game_robot_pos_pub_.publish(game_robot_pos_data);
298  break;
299  }
301  {
302  rm_referee::Buff referee_buff;
303  rm_msgs::Buff robot_buff;
304  memcpy(&referee_buff, rx_data + 7, sizeof(rm_referee::Buff));
305  robot_buff.attack_buff = referee_buff.attack_buff;
306  robot_buff.defence_buff = referee_buff.defence_buff;
307  robot_buff.vulnerability_buff = referee_buff.vulnerability_buff;
308  robot_buff.cooling_buff = referee_buff.cooling_buff;
309  robot_buff.recovery_buff = referee_buff.recovery_buff;
310 
311  if (referee_buff.remaining_energy & 0x1E)
312  robot_buff.remaining_energy = 50;
313  else if (referee_buff.remaining_energy & 0x1C)
314  robot_buff.remaining_energy = 30;
315  else if (referee_buff.remaining_energy & 0x18)
316  robot_buff.remaining_energy = 15;
317  else if (referee_buff.remaining_energy & 0x10)
318  robot_buff.remaining_energy = 5;
319  else if (referee_buff.remaining_energy & 0x00)
320  robot_buff.remaining_energy = 1;
321 
322  buff_pub_.publish(robot_buff);
323  break;
324  }
326  {
327  rm_referee::AerialRobotEnergy aerial_robot_energy_ref;
328  memcpy(&aerial_robot_energy_ref, rx_data + 7, sizeof(rm_referee::AerialRobotEnergy));
329  break;
330  }
332  {
333  rm_referee::RobotHurt robot_hurt_ref;
334  rm_msgs::RobotHurt robot_hurt_data;
335  memcpy(&robot_hurt_ref, rx_data + 7, sizeof(rm_referee::RobotHurt));
336 
337  robot_hurt_data.armor_id = robot_hurt_ref.armor_id;
338  robot_hurt_data.hurt_type = robot_hurt_ref.hurt_type;
339  robot_hurt_data.stamp = last_get_data_time_;
340 
342 
343  robot_hurt_pub_.publish(robot_hurt_data);
344  break;
345  }
347  {
348  rm_referee::ShootData shoot_data_ref;
349  rm_msgs::ShootData shoot_data;
350 
351  memcpy(&shoot_data_ref, rx_data + 7, sizeof(rm_referee::ShootData));
352 
353  shoot_data.bullet_freq = shoot_data_ref.bullet_freq;
354  shoot_data.bullet_speed = shoot_data_ref.bullet_speed;
355  shoot_data.bullet_type = shoot_data_ref.bullet_type;
356  shoot_data.shooter_id = shoot_data_ref.shooter_id;
357  shoot_data.stamp = last_get_data_time_;
358 
360  shoot_data_pub_.publish(shoot_data);
361  break;
362  }
364  {
365  rm_referee::BulletAllowance bullet_allowance_ref;
366  rm_msgs::BulletAllowance bullet_allowance_data;
367  memcpy(&bullet_allowance_ref, rx_data + 7, sizeof(rm_referee::BulletAllowance));
368 
369  bullet_allowance_data.bullet_allowance_num_17_mm = bullet_allowance_ref.bullet_allowance_num_17_mm;
370  bullet_allowance_data.bullet_allowance_num_42_mm = bullet_allowance_ref.bullet_allowance_num_42_mm;
371  bullet_allowance_data.coin_remaining_num = bullet_allowance_ref.coin_remaining_num;
372  bullet_allowance_data.stamp = last_get_data_time_;
374 
375  bullet_allowance_pub_.publish(bullet_allowance_data);
376  break;
377  }
379  {
380  rm_referee::RfidStatus rfid_status_ref;
381  rm_msgs::RfidStatus rfid_status_data;
382  memcpy(&rfid_status_ref, rx_data + 7, sizeof(rm_referee::RfidStatus));
383 
384  rfid_status_data.base_buff_point_state = rfid_status_ref.base_buff_point_state;
385  rfid_status_data.own_central_elevated_ground_state = rfid_status_ref.own_central_elevated_ground_state;
386  rfid_status_data.enemy_central_elevated_ground_state = rfid_status_ref.enemy_central_elevated_ground_state;
387  rfid_status_data.own_trapezoidal_elevated_ground_state =
388  rfid_status_ref.own_trapezoidal_elevated_ground_state;
389  rfid_status_data.enemy_trapezoidal_elevated_ground_state =
390  rfid_status_ref.enemy_trapezoidal_elevated_ground_state;
391  rfid_status_data.forward_own_terrain_span_buff_point_state =
392  rfid_status_ref.forward_own_terrain_span_buff_point_state;
393  rfid_status_data.behind_own_terrain_span_buff_point_state =
394  rfid_status_ref.behind_own_terrain_span_buff_point_state;
395  rfid_status_data.forward_enemy_terrain_span_buff_point_state =
396  rfid_status_ref.forward_enemy_terrain_span_buff_point_state;
397  rfid_status_data.behind_enemy_terrain_span_buff_point_state =
398  rfid_status_ref.behind_enemy_terrain_span_buff_point_state;
399  rfid_status_data.below_central_own_terrain_span_buff_point_state =
400  rfid_status_ref.below_central_own_terrain_span_buff_point_state;
401  rfid_status_data.upper_central_own_terrain_span_buff_point_state =
402  rfid_status_ref.upper_central_own_terrain_span_buff_point_state;
403  rfid_status_data.below_central_enemy_terrain_span_buff_point_state =
404  rfid_status_ref.below_central_enemy_terrain_span_buff_point_state;
405  rfid_status_data.upper_central_enemy_terrain_span_buff_point_state =
406  rfid_status_ref.upper_central_enemy_terrain_span_buff_point_state;
407  rfid_status_data.below_road_own_terrain_span_buff_point_state =
408  rfid_status_ref.below_road_own_terrain_span_buff_point_state;
409  rfid_status_data.upper_road_own_terrain_span_buff_point_state =
410  rfid_status_ref.upper_road_own_terrain_span_buff_point_state;
411  rfid_status_data.below_road_enemy_terrain_span_buff_point_state =
412  rfid_status_ref.below_road_enemy_terrain_span_buff_point_state;
413  rfid_status_data.upper_road_enemy_terrain_span_buff_point_state =
414  rfid_status_ref.upper_road_enemy_terrain_span_buff_point_state;
415  rfid_status_data.own_fort_buff_point = rfid_status_ref.own_fort_buff_point;
416  rfid_status_data.own_outpost_buff_point = rfid_status_ref.own_outpost_buff_point;
417  rfid_status_data.nan_overlapping_supplier_zone = rfid_status_ref.nan_overlapping_supplier_zone;
418  rfid_status_data.overlapping_supplier_zone = rfid_status_ref.overlapping_supplier_zone;
419  rfid_status_data.own_large_resource_island_point = rfid_status_ref.own_large_resource_island_point;
420  rfid_status_data.enemy_large_resource_island_point = rfid_status_ref.enemy_large_resource_island_point;
421  rfid_status_data.central_buff_point = rfid_status_ref.central_buff_point;
422  rfid_status_data.stamp = last_get_data_time_;
423 
424  rfid_status_pub_.publish(rfid_status_data);
425  break;
426  }
428  {
429  rm_referee::DartClientCmd dart_client_cmd_ref;
430  rm_msgs::DartClientCmd dart_client_cmd_data;
431  memcpy(&dart_client_cmd_ref, rx_data + 7, sizeof(rm_referee::DartClientCmd));
432  dart_client_cmd_data.dart_launch_opening_status = dart_client_cmd_ref.dart_launch_opening_status;
433  dart_client_cmd_data.target_change_time = dart_client_cmd_ref.target_change_time;
434  dart_client_cmd_data.latest_launch_cmd_time = dart_client_cmd_ref.latest_launch_cmd_time;
435  dart_client_cmd_data.stamp = last_get_data_time_;
436 
437  dart_client_cmd_pub_.publish(dart_client_cmd_data);
438  break;
439  }
441  {
442  rm_referee::RobotsPositionData robots_position_ref;
443  rm_msgs::RobotsPositionData robots_position_data;
444  memcpy(&robots_position_ref, rx_data + 7, sizeof(rm_referee::RobotsPositionData));
445 
446  robots_position_data.engineer_x = robots_position_ref.engineer_x;
447  robots_position_data.engineer_y = robots_position_ref.engineer_y;
448  robots_position_data.hero_x = robots_position_ref.hero_x;
449  robots_position_data.hero_y = robots_position_ref.hero_y;
450  robots_position_data.standard_3_x = robots_position_ref.standard_3_x;
451  robots_position_data.standard_3_y = robots_position_ref.standard_3_y;
452  robots_position_data.standard_4_x = robots_position_ref.standard_4_x;
453  robots_position_data.standard_4_y = robots_position_ref.standard_4_y;
454  robots_position_data.stamp = last_get_data_time_;
455 
456  robots_position_pub_.publish(robots_position_data);
457  break;
458  }
460  {
461  rm_referee::RadarMarkData radar_mark_ref;
462  rm_msgs::RadarMarkData radar_mark_data;
463  memcpy(&radar_mark_ref, rx_data + 7, sizeof(rm_referee::RadarMarkData));
464 
465  radar_mark_data.mark_engineer_progress = radar_mark_ref.mark_engineer_progress;
466  radar_mark_data.mark_hero_progress = radar_mark_ref.mark_hero_progress;
467  radar_mark_data.mark_sentry_progress = radar_mark_ref.mark_sentry_progress;
468  radar_mark_data.mark_standard_3_progress = radar_mark_ref.mark_standard_3_progress;
469  radar_mark_data.mark_standard_4_progress = radar_mark_ref.mark_standard_4_progress;
470  radar_mark_data.stamp = last_get_data_time_;
471 
472  radar_mark_pub_.publish(radar_mark_data);
473  }
475  {
476  rm_referee::InteractiveData interactive_data_ref; // local variable temporarily before moving referee data
477  memcpy(&interactive_data_ref, rx_data + 7, sizeof(rm_referee::InteractiveData));
478  if (interactive_data_ref.header_data.data_cmd_id == rm_referee::DataCmdId::BULLET_NUM_SHARE_CMD)
479  {
480  rm_referee::BulletNumData bullet_num_data_ref;
481  memcpy(&bullet_num_data_ref, rx_data + 7, sizeof(rm_referee::BulletNumData));
482  referee_ui_.updateBulletRemainData(bullet_num_data_ref);
483  }
484  else if (interactive_data_ref.header_data.data_cmd_id == rm_referee::DataCmdId::SENTRY_TO_RADAR_CMD)
485  {
486  rm_referee::SentryAttackingTargetData sentry_attacking_target_data_ref;
487  rm_msgs::SentryAttackingTarget sentry_attacking_target_data_data;
488  memcpy(&sentry_attacking_target_data_ref, rx_data + 7, sizeof(rm_referee::SentryAttackingTargetData));
489  sentry_attacking_target_data_data.target_robot_ID = sentry_attacking_target_data_ref.target_robot_ID;
490  sentry_attacking_target_data_data.target_position_x = sentry_attacking_target_data_ref.target_position_x;
491  sentry_attacking_target_data_data.target_position_y = sentry_attacking_target_data_ref.target_position_y;
492  sentry_to_radar_pub_.publish(sentry_attacking_target_data_data);
493  }
494  else if (interactive_data_ref.header_data.data_cmd_id == rm_referee::DataCmdId::RADAR_TO_SENTRY_CMD)
495  {
496  rm_referee::RadarToSentryData radar_to_sentry_data_ref;
497  rm_msgs::RadarToSentry radar_to_sentry_data;
498  memcpy(&radar_to_sentry_data_ref, rx_data + 7, sizeof(rm_referee::RadarToSentryData));
499  radar_to_sentry_data.robot_ID = radar_to_sentry_data_ref.robot_ID;
500  radar_to_sentry_data.position_x = radar_to_sentry_data_ref.position_x;
501  radar_to_sentry_data.position_y = radar_to_sentry_data_ref.position_y;
502  radar_to_sentry_data.engineer_marked = radar_to_sentry_data_ref.engineer_marked;
503  radar_to_sentry_pub_.publish(radar_to_sentry_data);
504  }
505  break;
506  }
508  {
509  rm_referee::ClientMapReceiveData client_map_receive_ref;
510  rm_msgs::ClientMapReceiveData client_map_receive_data;
511  memcpy(&client_map_receive_ref, rx_data + 7, sizeof(rm_referee::ClientMapReceiveData));
512  break;
513  }
515  {
516  rm_referee::CustomInfo custom_info;
517  memcpy(&custom_info, rx_data + 7, sizeof(rm_referee::CustomInfo));
518  break;
519  }
521  {
522  rm_referee::ClientMapSendData client_map_send_data_ref;
523  rm_msgs::ClientMapSendData client_map_send_data;
524  memcpy(&client_map_send_data_ref, rx_data + 7, sizeof(rm_referee::ClientMapSendData));
525 
526  client_map_send_data.target_position_x = client_map_send_data_ref.target_position_x;
527  client_map_send_data.target_position_y = client_map_send_data_ref.target_position_y;
528  client_map_send_data.command_keyboard = client_map_send_data_ref.command_keyboard;
529  client_map_send_data.target_robot_ID = client_map_send_data_ref.target_robot_ID;
530  client_map_send_data.cmd_source = client_map_send_data_ref.cmd_source;
531  client_map_send_data_pub_.publish(client_map_send_data);
532  break;
533  }
535  {
536  rm_referee::SentryInfo sentry_info_ref;
537  rm_msgs::SentryInfo sentry_info;
538  memcpy(&sentry_info_ref, rx_data + 7, sizeof(rm_referee::SentryInfo));
539  sentry_info.sentry_info = sentry_info_ref.sentry_info;
540  sentry_info.is_out_of_war = sentry_info_ref.is_out_of_war;
541  sentry_info.remaining_bullets_can_supply = sentry_info_ref.remaining_bullets_can_supply;
542  sentry_info_pub_.publish(sentry_info);
543  break;
544  }
546  {
547  rm_msgs::RadarInfo radar_info;
548  memcpy(&radar_info, rx_data + 7, sizeof(rm_msgs::RadarInfo));
549  radar_info_pub_.publish(radar_info);
550  break;
551  }
553  {
554  rm_msgs::PowerManagementSampleAndStatusData sample_and_status_pub_data;
555  uint8_t data[sizeof(rm_referee::PowerManagementSampleAndStatusData)];
556  memcpy(&data, rx_data + 7, sizeof(rm_referee::PowerManagementSampleAndStatusData));
557  sample_and_status_pub_data.chassis_power = (static_cast<uint16_t>((data[0] << 8) | data[1]) / 100.);
558  sample_and_status_pub_data.cap_error_flag = (static_cast<uint16_t>((data[2] << 8) | data[3]) / 100.);
559  sample_and_status_pub_data.cap_received_msg = (static_cast<uint16_t>((data[4] << 8) | data[5]) / 100.);
560  sample_and_status_pub_data.capacity_remain_charge =
561  (static_cast<uint16_t>((data[6] << 8) | data[7]) / 10000.);
562  sample_and_status_pub_data.capacity_discharge_power = static_cast<uint8_t>(data[8]);
563  sample_and_status_pub_data.state_machine_running_state = base_.capacity_recent_mode_ =
564  static_cast<uint8_t>(data[9] >> 4);
565  sample_and_status_pub_data.power_management_protection_info = static_cast<uint8_t>((data[9] >> 2) & 0x03);
566  sample_and_status_pub_data.power_management_topology = static_cast<uint8_t>(data[9] & 0x03);
567  sample_and_status_pub_data.stamp = last_get_data_time_;
568 
569  referee_ui_.capacityDataCallBack(sample_and_status_pub_data, last_get_data_time_);
570 
571  power_management_sample_and_status_data_pub_.publish(sample_and_status_pub_data);
572  break;
573  }
575  {
576  rm_referee::PowerManagementInitializationExceptionData initialization_exception_ref;
577  rm_msgs::PowerManagementInitializationExceptionData initialization_exception_pub_data;
578  memcpy(&initialization_exception_ref, rx_data + 7,
579  sizeof(rm_referee::PowerManagementInitializationExceptionData));
580 
581  initialization_exception_pub_data.error_code = initialization_exception_ref.error_code;
582  initialization_exception_pub_data.string = initialization_exception_ref.string;
583  initialization_exception_pub_data.stamp = last_get_data_time_;
584  power_management_initialization_exception_pub_.publish(initialization_exception_pub_data);
585  break;
586  }
588  {
589  unsigned char* tmp_rx_data_ptr = rx_data + 7;
590  rm_msgs::PowerManagementSystemExceptionData system_exception_pub_data;
591 
592  system_exception_pub_data.r0 =
593  tmp_rx_data_ptr[0] << 24 | tmp_rx_data_ptr[1] << 16 | tmp_rx_data_ptr[2] << 8 | tmp_rx_data_ptr[3];
594  system_exception_pub_data.r1 =
595  tmp_rx_data_ptr[4] << 24 | tmp_rx_data_ptr[5] << 16 | tmp_rx_data_ptr[6] << 8 | tmp_rx_data_ptr[7];
596  system_exception_pub_data.r2 =
597  tmp_rx_data_ptr[8] << 24 | tmp_rx_data_ptr[9] << 16 | tmp_rx_data_ptr[10] << 8 | tmp_rx_data_ptr[11];
598  system_exception_pub_data.r3 =
599  tmp_rx_data_ptr[12] << 24 | tmp_rx_data_ptr[13] << 16 | tmp_rx_data_ptr[14] << 8 | tmp_rx_data_ptr[15];
600  system_exception_pub_data.r12 =
601  tmp_rx_data_ptr[16] << 24 | tmp_rx_data_ptr[17] << 16 | tmp_rx_data_ptr[18] << 8 | tmp_rx_data_ptr[19];
602  system_exception_pub_data.LR =
603  tmp_rx_data_ptr[20] << 24 | tmp_rx_data_ptr[21] << 16 | tmp_rx_data_ptr[22] << 8 | tmp_rx_data_ptr[23];
604  system_exception_pub_data.PC =
605  tmp_rx_data_ptr[24] << 24 | tmp_rx_data_ptr[25] << 16 | tmp_rx_data_ptr[26] << 8 | tmp_rx_data_ptr[27];
606  system_exception_pub_data.PSR =
607  tmp_rx_data_ptr[28] << 24 | tmp_rx_data_ptr[29] << 16 | tmp_rx_data_ptr[30] << 8 | tmp_rx_data_ptr[31];
608  system_exception_pub_data.stamp = last_get_data_time_;
609  power_management_system_exception_data_.publish(system_exception_pub_data);
610  break;
611  }
613  {
614  rm_referee::PowerManagementProcessStackOverflowData stack_overflow_ref;
615  rm_msgs::PowerManagementProcessStackOverflowData stack_overflow_pub_data;
616  memcpy(&stack_overflow_ref, rx_data + 7, sizeof(rm_referee::PowerManagementProcessStackOverflowData));
617 
618  stack_overflow_pub_data.process_name = stack_overflow_ref.process_name;
619  stack_overflow_pub_data.stamp = last_get_data_time_;
620  power_management_process_stack_overflow_pub_.publish(stack_overflow_pub_data);
621  }
623  {
624  rm_referee::PowerManagementUnknownExceptionData unknown_exception_ref;
625  rm_msgs::PowerManagementUnknownExceptionData unknown_exception_pub_data;
626  memcpy(&unknown_exception_ref, rx_data + 7, sizeof(rm_referee::PowerManagementUnknownExceptionData));
627 
628  unknown_exception_pub_data.abnormal_reset_reason = unknown_exception_ref.abnormal_reset_reason;
629  unknown_exception_pub_data.power_management_before_reset_topology =
630  unknown_exception_ref.power_management_before_reset_topology;
631  unknown_exception_pub_data.state_machine_before_reset_mode =
632  unknown_exception_ref.state_machine_before_reset_mode;
633  unknown_exception_pub_data.stamp = last_get_data_time_;
634  power_management_unknown_exception_pub_.publish(unknown_exception_pub_data);
635  break;
636  }
637  default:
638  ROS_WARN("Referee command ID %d not found.", cmd_id);
639  break;
640  }
643  return frame_len;
644  }
645  }
646  return -1;
647 }
648 
650 {
651  base_.robot_color_ = base_.robot_id_ >= 100 ? "blue" : "red";
652  switch (base_.robot_id_)
653  {
656  break;
659  break;
662  break;
665  break;
668  break;
671  break;
674  break;
677  break;
680  break;
683  break;
686  break;
689  break;
692  break;
695  break;
698  break;
701  break;
702  }
703 }
704 } // namespace rm_referee
serial::Serial::read
std::string read(size_t size=1)
rm_referee::Base::robot_id_
int robot_id_
Definition: data.h:148
rm_referee::ROBOT_POS_CMD
@ ROBOT_POS_CMD
Definition: protocol.h:58
rm_referee::ROBOTS_POS_CMD
@ ROBOTS_POS_CMD
Definition: protocol.h:66
rm_referee::BLUE_ENGINEER
@ BLUE_ENGINEER
Definition: protocol.h:116
rm_referee::BLUE_AERIAL_CLIENT
@ BLUE_AERIAL_CLIENT
Definition: protocol.h:140
rm_referee::Referee::unpack_buffer_
uint8_t unpack_buffer_[256]
Definition: referee.h:207
rm_referee::Referee::k_header_length_
const int k_header_length_
Definition: referee.h:205
rm_referee
Definition: data.h:100
rm_referee::RED_STANDARD_3_CLIENT
@ RED_STANDARD_3_CLIENT
Definition: protocol.h:131
rm_referee::TARGET_POS_CMD
@ TARGET_POS_CMD
Definition: protocol.h:72
rm_referee::RADAR_MARK_CMD
@ RADAR_MARK_CMD
Definition: protocol.h:67
rm_referee::SENTRY_INFO_CMD
@ SENTRY_INFO_CMD
Definition: protocol.h:68
rm_referee::DART_STATUS_CMD
@ DART_STATUS_CMD
Definition: protocol.h:50
rm_referee::AERIAL_ROBOT_ENERGY_CMD
@ AERIAL_ROBOT_ENERGY_CMD
Definition: protocol.h:60
rm_referee::ROBOT_HURT_CMD
@ ROBOT_HURT_CMD
Definition: protocol.h:61
rm_referee::CLIENT_MAP_CMD
@ CLIENT_MAP_CMD
Definition: protocol.h:74
rm_referee::FIELD_EVENTS_CMD
@ FIELD_EVENTS_CMD
Definition: protocol.h:52
rm_referee::Base::client_id_
int client_id_
Definition: data.h:147
rm_referee::Base::capacity_recent_mode_
int capacity_recent_mode_
Definition: data.h:149
rm_referee::Referee::unpack
int unpack(uint8_t *rx_data)
Definition: referee.cpp:108
rm_referee::GAME_STATUS_CMD
@ GAME_STATUS_CMD
Definition: protocol.h:47
rm_referee::RED_AERIAL_CLIENT
@ RED_AERIAL_CLIENT
Definition: protocol.h:134
rm_referee::BLUE_STANDARD_4
@ BLUE_STANDARD_4
Definition: protocol.h:118
rm_referee::POWER_MANAGEMENT_UNKNOWN_EXCEPTION_CMD
@ POWER_MANAGEMENT_UNKNOWN_EXCEPTION_CMD
Definition: protocol.h:83
rm_referee::POWER_MANAGEMENT_SAMPLE_AND_STATUS_DATA_CMD
@ POWER_MANAGEMENT_SAMPLE_AND_STATUS_DATA_CMD
Definition: protocol.h:79
rm_referee::Base::robot_color_
std::string robot_color_
Definition: data.h:150
rm_referee::Referee::icra_buff_debuff_zone_status_pub_
ros::Publisher icra_buff_debuff_zone_status_pub_
Definition: referee.h:172
rm_referee::Referee::power_management_system_exception_data_
ros::Publisher power_management_system_exception_data_
Definition: referee.h:190
rm_referee::REFEREE_WARNING_CMD
@ REFEREE_WARNING_CMD
Definition: protocol.h:54
rm_referee::SUPPLY_PROJECTILE_ACTION_CMD
@ SUPPLY_PROJECTILE_ACTION_CMD
Definition: protocol.h:53
rm_referee::SENTRY_TO_RADAR_CMD
@ SENTRY_TO_RADAR_CMD
Definition: protocol.h:99
rm_referee::RefereeBase::updateShootDataDataCallBack
virtual void updateShootDataDataCallBack(const rm_msgs::ShootData &msg)
Definition: referee_base.cpp:589
rm_referee::Referee::client_map_send_data_pub_
ros::Publisher client_map_send_data_pub_
Definition: referee.h:186
rm_referee::Referee::event_data_pub_
ros::Publisher event_data_pub_
Definition: referee.h:169
rm_referee::BLUE_HERO
@ BLUE_HERO
Definition: protocol.h:115
rm_referee::Referee::k_tail_length_
const int k_tail_length_
Definition: referee.h:205
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rm_referee::Referee::dart_status_pub_
ros::Publisher dart_status_pub_
Definition: referee.h:170
rm_referee::RefereeBase::updateHeroHitDataCallBack
virtual void updateHeroHitDataCallBack(const rm_msgs::GameRobotHp &game_robot_hp_data)
Definition: referee_base.cpp:362
rm_referee::RefereeBase::robotHurtDataCallBack
virtual void robotHurtDataCallBack(const rm_msgs::RobotHurt &robot_hurt_data, const ros::Time &last_get_data_time)
Definition: referee_base.cpp:381
rm_referee::ROBOT_RFID_STATUS_CMD
@ ROBOT_RFID_STATUS_CMD
Definition: protocol.h:64
rm_referee::Referee::game_robot_hp_pub_
ros::Publisher game_robot_hp_pub_
Definition: referee.h:167
rm_referee::Referee::last_get_data_time_
ros::Time last_get_data_time_
Definition: referee.h:204
rm_referee::BLUE_STANDARD_3_CLIENT
@ BLUE_STANDARD_3_CLIENT
Definition: protocol.h:137
rm_referee::RED_ENGINEER_CLIENT
@ RED_ENGINEER_CLIENT
Definition: protocol.h:130
rm_referee::Referee::k_cmd_id_length_
const int k_cmd_id_length_
Definition: referee.h:205
rm_referee::BLUE_ENGINEER_CLIENT
@ BLUE_ENGINEER_CLIENT
Definition: protocol.h:136
rm_referee::RED_ENGINEER
@ RED_ENGINEER
Definition: protocol.h:106
rm_referee::Referee::sentry_to_radar_pub_
ros::Publisher sentry_to_radar_pub_
Definition: referee.h:168
rm_referee::BLUE_STANDARD_5
@ BLUE_STANDARD_5
Definition: protocol.h:119
rm_referee::RADAR_TO_SENTRY_CMD
@ RADAR_TO_SENTRY_CMD
Definition: protocol.h:100
rm_referee::RED_STANDARD_5
@ RED_STANDARD_5
Definition: protocol.h:109
rm_referee::Referee::game_robot_status_pub_
ros::Publisher game_robot_status_pub_
Definition: referee.h:164
rm_referee::BLUE_SENTRY
@ BLUE_SENTRY
Definition: protocol.h:121
rm_referee::DART_INFO_CMD
@ DART_INFO_CMD
Definition: protocol.h:55
rm_referee::GAME_RESULT_CMD
@ GAME_RESULT_CMD
Definition: protocol.h:48
rm_referee::ICRA_ZONE_STATUS_CMD
@ ICRA_ZONE_STATUS_CMD
Definition: protocol.h:51
rm_referee::Base::referee_data_is_online_
bool referee_data_is_online_
Definition: data.h:151
rm_referee::BULLET_REMAINING_CMD
@ BULLET_REMAINING_CMD
Definition: protocol.h:63
rm_referee::RED_AERIAL
@ RED_AERIAL
Definition: protocol.h:110
rm_referee::Referee::shoot_data_pub_
ros::Publisher shoot_data_pub_
Definition: referee.h:176
rm_referee::RED_HERO_CLIENT
@ RED_HERO_CLIENT
Definition: protocol.h:129
rm_referee::RED_HERO
@ RED_HERO
Definition: protocol.h:105
rm_referee::Referee::bullet_allowance_pub_
ros::Publisher bullet_allowance_pub_
Definition: referee.h:177
rm_referee::BUFF_CMD
@ BUFF_CMD
Definition: protocol.h:59
rm_referee::Referee::getRobotInfo
void getRobotInfo()
Definition: referee.cpp:680
rm_referee::POWER_MANAGEMENT_SYSTEM_EXCEPTION_CMD
@ POWER_MANAGEMENT_SYSTEM_EXCEPTION_CMD
Definition: protocol.h:81
rm_referee::BLUE_AERIAL
@ BLUE_AERIAL
Definition: protocol.h:120
rm_referee::SHOOT_DATA_CMD
@ SHOOT_DATA_CMD
Definition: protocol.h:62
rm_referee::Referee::sentry_info_pub_
ros::Publisher sentry_info_pub_
Definition: referee.h:184
rm_referee::CUSTOM_TO_ROBOT_CMD
@ CUSTOM_TO_ROBOT_CMD
Definition: protocol.h:77
rm_referee::RED_RADAR
@ RED_RADAR
Definition: protocol.h:112
rm_referee::POWER_MANAGEMENT_PROCESS_STACK_OVERFLOW_CMD
@ POWER_MANAGEMENT_PROCESS_STACK_OVERFLOW_CMD
Definition: protocol.h:82
rm_referee::BLUE_STANDARD_3
@ BLUE_STANDARD_3
Definition: protocol.h:117
rm_referee::Referee::power_management_unknown_exception_pub_
ros::Publisher power_management_unknown_exception_pub_
Definition: referee.h:192
ROS_WARN
#define ROS_WARN(...)
rm_referee::BLUE_STANDARD_4_CLIENT
@ BLUE_STANDARD_4_CLIENT
Definition: protocol.h:138
rm_referee::Referee::read
void read()
Definition: referee.cpp:73
rm_referee::INTERACTIVE_DATA_CMD
@ INTERACTIVE_DATA_CMD
Definition: protocol.h:70
rm_referee::RefereeBase::bulletRemainDataCallBack
virtual void bulletRemainDataCallBack(const rm_msgs::BulletAllowance &bullet_allowance, const ros::Time &last_get_data_time)
Definition: referee_base.cpp:384
rm_referee::ROBOT_STATUS_CMD
@ ROBOT_STATUS_CMD
Definition: protocol.h:56
rm_referee::Referee::referee_ui_
rm_referee::RefereeBase referee_ui_
Definition: referee.h:196
rm_referee::Referee::robots_position_pub_
ros::Publisher robots_position_pub_
Definition: referee.h:181
rm_referee::RED_STANDARD_4_CLIENT
@ RED_STANDARD_4_CLIENT
Definition: protocol.h:132
rm_referee::Referee::dart_info_pub_
ros::Publisher dart_info_pub_
Definition: referee.h:174
rm_referee::POWER_HEAT_DATA_CMD
@ POWER_HEAT_DATA_CMD
Definition: protocol.h:57
rm_referee::RED_SENTRY
@ RED_SENTRY
Definition: protocol.h:111
rm_referee::Referee::radar_mark_pub_
ros::Publisher radar_mark_pub_
Definition: referee.h:182
rm_referee::Referee::rx_len_
int rx_len_
Definition: referee.h:197
rm_referee::POWER_MANAGEMENT_INITIALIZATION_EXCEPTION_CMD
@ POWER_MANAGEMENT_INITIALIZATION_EXCEPTION_CMD
Definition: protocol.h:80
rm_referee::BLUE_STANDARD_5_CLIENT
@ BLUE_STANDARD_5_CLIENT
Definition: protocol.h:139
rm_referee::RED_STANDARD_4
@ RED_STANDARD_4
Definition: protocol.h:108
rm_referee::Referee::power_management_initialization_exception_pub_
ros::Publisher power_management_initialization_exception_pub_
Definition: referee.h:189
rm_referee::RefereeBase::supplyBulletDataCallBack
virtual void supplyBulletDataCallBack(const rm_msgs::SupplyProjectileAction &data)
Definition: referee_base.cpp:579
rm_referee::Referee::k_unpack_buffer_length_
const int k_unpack_buffer_length_
Definition: referee.h:206
rm_referee::Referee::base_
Base base_
Definition: referee.h:194
rm_referee::RefereeBase::capacityDataCallBack
virtual void capacityDataCallBack(const rm_msgs::PowerManagementSampleAndStatusData &data, ros::Time &last_get_data_time)
Definition: referee_base.cpp:370
rm_referee::Referee::clearRxBuffer
void clearRxBuffer()
Definition: referee.h:158
rm_referee::RED_STANDARD_3
@ RED_STANDARD_3
Definition: protocol.h:107
rm_referee::Base::verifyCRC16CheckSum
uint32_t verifyCRC16CheckSum(uint8_t *pch_message, uint32_t dw_length)
Definition: data.h:215
rm_referee::Referee::power_management_sample_and_status_data_pub_
ros::Publisher power_management_sample_and_status_data_pub_
Definition: referee.h:188
rm_referee::Base::verifyCRC8CheckSum
uint32_t verifyCRC8CheckSum(unsigned char *pch_message, unsigned int dw_length)
Definition: data.h:183
rm_referee::RED_STANDARD_5_CLIENT
@ RED_STANDARD_5_CLIENT
Definition: protocol.h:133
serial::Serial::available
size_t available()
rm_referee::Referee::power_management_process_stack_overflow_pub_
ros::Publisher power_management_process_stack_overflow_pub_
Definition: referee.h:191
rm_referee::GAME_ROBOT_HP_CMD
@ GAME_ROBOT_HP_CMD
Definition: protocol.h:49
rm_referee::Referee::k_frame_length_
const int k_frame_length_
Definition: referee.h:205
rm_referee::Referee::robot_hurt_pub_
ros::Publisher robot_hurt_pub_
Definition: referee.h:175
rm_referee::RefereeBase::robotStatusDataCallBack
virtual void robotStatusDataCallBack(const rm_msgs::GameRobotStatus &game_robot_status_data, const ros::Time &last_get_data_time)
Definition: referee_base.cpp:356
rm_referee::Referee::buff_pub_
ros::Publisher buff_pub_
Definition: referee.h:171
rm_referee::DART_CLIENT_CMD
@ DART_CLIENT_CMD
Definition: protocol.h:65
rm_referee::Referee::game_status_pub_
ros::Publisher game_status_pub_
Definition: referee.h:165
rm_referee::Referee::radar_info_pub_
ros::Publisher radar_info_pub_
Definition: referee.h:185
rm_referee::Referee::rx_buffer_
std::vector< uint8_t > rx_buffer_
Definition: referee.h:195
rm_referee::Base::serial_
serial::Serial serial_
Definition: data.h:145
rm_referee::Referee::supply_projectile_action_pub_
ros::Publisher supply_projectile_action_pub_
Definition: referee.h:173
referee.h
rm_referee::Referee::radar_to_sentry_pub_
ros::Publisher radar_to_sentry_pub_
Definition: referee.h:187
ROS_INFO
#define ROS_INFO(...)
rm_referee::RADAR_INFO_CMD
@ RADAR_INFO_CMD
Definition: protocol.h:69
ros::Duration
rm_referee::BLUE_HERO_CLIENT
@ BLUE_HERO_CLIENT
Definition: protocol.h:135
rm_referee::Referee::game_robot_pos_pub_
ros::Publisher game_robot_pos_pub_
Definition: referee.h:183
rm_referee::Referee::dart_client_cmd_pub_
ros::Publisher dart_client_cmd_pub_
Definition: referee.h:179
rm_referee::RefereeBase::updateBulletRemainData
virtual void updateBulletRemainData(const rm_referee::BulletNumData &data)
Definition: referee_base.cpp:601
rm_referee::BULLET_NUM_SHARE_CMD
@ BULLET_NUM_SHARE_CMD
Definition: protocol.h:98
rm_referee::Referee::power_heat_data_pub_
ros::Publisher power_heat_data_pub_
Definition: referee.h:166
rm_referee::RefereeBase::gameStatusDataCallBack
virtual void gameStatusDataCallBack(const rm_msgs::GameStatus &game_status_data, const ros::Time &last_get_data_time)
Definition: referee_base.cpp:367
rm_referee::Referee::rfid_status_pub_
ros::Publisher rfid_status_pub_
Definition: referee.h:178
ros::Time::now
static Time now()
rm_referee::BLUE_RADAR
@ BLUE_RADAR
Definition: protocol.h:122


rm_referee
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:49