51 uint8_t temp_buffer[256] = { 0 };
59 for (
int k_i = 0; k_i <
rx_len_; ++k_i)
81 rm_referee::FrameHeader frame_header;
86 if (frame_header.data_length > 256)
88 ROS_INFO(
"discard possible wrong frames, data length: %d", frame_header.data_length);
94 cmd_id = (rx_data[6] << 8 | rx_data[5]);
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));
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;
115 rm_referee::GameResult game_result_ref;
116 memcpy(&game_result_ref, rx_data + 7,
sizeof(rm_referee::GameResult));
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));
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;
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));
151 dart_status_data.dart_belong = dart_status_ref.dart_belong;
152 dart_status_data.stage_remaining_time = dart_status_ref.stage_remaining_time;
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));
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;
193 rm_referee::EventData event_ref;
194 rm_msgs::EventData event_data;
195 memcpy(&event_ref, rx_data + 7,
sizeof(rm_referee::EventData));
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;
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));
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;
230 rm_referee::RefereeWarning referee_warning_ref;
231 memcpy(&referee_warning_ref, rx_data + 7,
sizeof(rm_referee::RefereeWarning));
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));
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;
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));
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;
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));
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;
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));
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;
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;
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;
327 rm_referee::AerialRobotEnergy aerial_robot_energy_ref;
328 memcpy(&aerial_robot_energy_ref, rx_data + 7,
sizeof(rm_referee::AerialRobotEnergy));
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));
337 robot_hurt_data.armor_id = robot_hurt_ref.armor_id;
338 robot_hurt_data.hurt_type = robot_hurt_ref.hurt_type;
348 rm_referee::ShootData shoot_data_ref;
349 rm_msgs::ShootData shoot_data;
351 memcpy(&shoot_data_ref, rx_data + 7,
sizeof(rm_referee::ShootData));
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;
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));
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;
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));
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;
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;
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));
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;
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));
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;
476 rm_referee::InteractiveData interactive_data_ref;
477 memcpy(&interactive_data_ref, rx_data + 7,
sizeof(rm_referee::InteractiveData));
480 rm_referee::BulletNumData bullet_num_data_ref;
481 memcpy(&bullet_num_data_ref, rx_data + 7,
sizeof(rm_referee::BulletNumData));
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;
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;
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));
516 rm_referee::CustomInfo custom_info;
517 memcpy(&custom_info, rx_data + 7,
sizeof(rm_referee::CustomInfo));
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));
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;
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;
547 rm_msgs::RadarInfo radar_info;
548 memcpy(&radar_info, rx_data + 7,
sizeof(rm_msgs::RadarInfo));
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]);
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);
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));
581 initialization_exception_pub_data.error_code = initialization_exception_ref.error_code;
582 initialization_exception_pub_data.string = initialization_exception_ref.string;
589 unsigned char* tmp_rx_data_ptr = rx_data + 7;
590 rm_msgs::PowerManagementSystemExceptionData system_exception_pub_data;
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];
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));
618 stack_overflow_pub_data.process_name = stack_overflow_ref.process_name;
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));
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;
638 ROS_WARN(
"Referee command ID %d not found.", cmd_id);