referee.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/5/17.
36 //
37 #pragma once
38 
39 #include <cstdint>
40 #include <ros/ros.h>
41 
42 #include "rm_referee/common/data.h"
44 
45 namespace rm_referee
46 {
47 class Referee
48 {
49 public:
51  {
52  ROS_INFO("New serial protocol loading.");
53  // pub
54  game_robot_status_pub_ = nh.advertise<rm_msgs::GameRobotStatus>("game_robot_status", 1);
55  game_status_pub_ = nh.advertise<rm_msgs::GameStatus>("game_status", 1);
56  power_heat_data_pub_ = nh.advertise<rm_msgs::PowerHeatData>("power_heat_data", 1);
57  game_robot_hp_pub_ = nh.advertise<rm_msgs::GameRobotHp>("game_robot_hp", 1);
58  buff_pub_ = nh.advertise<rm_msgs::Buff>("robot_buff", 1);
59  event_data_pub_ = nh.advertise<rm_msgs::EventData>("event_data", 1);
60  dart_status_pub_ = nh.advertise<rm_msgs::DartStatus>("dart_status_data", 1);
62  nh.advertise<rm_msgs::IcraBuffDebuffZoneStatus>("icra_buff_debuff_zone_status_data", 1);
63  supply_projectile_action_pub_ = nh.advertise<rm_msgs::SupplyProjectileAction>("supply_projectile_action_data", 1);
64  dart_info_pub_ = nh.advertise<rm_msgs::DartInfo>("dart_info_data", 1);
65  robot_hurt_pub_ = nh.advertise<rm_msgs::RobotHurt>("robot_hurt_data", 1);
66  shoot_data_pub_ = nh.advertise<rm_msgs::ShootData>("shoot_data", 1);
67  bullet_allowance_pub_ = nh.advertise<rm_msgs::BulletAllowance>("bullet_allowance_data", 1);
68  rfid_status_pub_ = nh.advertise<rm_msgs::RfidStatus>("rfid_status_data", 1);
69  dart_client_cmd_pub_ = nh.advertise<rm_msgs::DartClientCmd>("dart_client_cmd_data", 1);
70  client_map_receive_pub_ = nh.advertise<rm_msgs::ClientMapReceiveData>("client_map_receive", 1);
71  robots_position_pub_ = nh.advertise<rm_msgs::RobotsPositionData>("robot_position", 1);
72  radar_mark_pub_ = nh.advertise<rm_msgs::RadarMarkData>("radar_mark", 1);
73  client_map_send_data_pub_ = nh.advertise<rm_msgs::ClientMapSendData>("client_map_send_data", 1);
74  game_robot_pos_pub_ = nh.advertise<rm_msgs::GameRobotPosData>("game_robot_pos", 1);
75  sentry_info_pub_ = nh.advertise<rm_msgs::SentryInfo>("sentry_info", 1);
76  radar_info_pub_ = nh.advertise<rm_msgs::RadarInfo>("radar_info", 1);
77  sentry_to_radar_pub_ = nh.advertise<rm_msgs::SentryAttackingTarget>("sentry_target_to_radar", 1);
78  radar_to_sentry_pub_ = nh.advertise<rm_msgs::RadarToSentry>("radar_to_sentry", 1);
79 
80  ros::NodeHandle power_management_nh = ros::NodeHandle(nh, "power_management");
82  power_management_nh.advertise<rm_msgs::PowerManagementSampleAndStatusData>("sample_and_status", 1);
84  power_management_nh.advertise<rm_msgs::PowerManagementInitializationExceptionData>("initialization_exception",
85  1);
87  power_management_nh.advertise<rm_msgs::PowerManagementSystemExceptionData>("system_exception", 1);
89  power_management_nh.advertise<rm_msgs::PowerManagementProcessStackOverflowData>("stack_overflow", 1);
91  power_management_nh.advertise<rm_msgs::PowerManagementUnknownExceptionData>("unknown_exception", 1);
92  // initSerial
93  base_.initSerial();
94  };
95  void read();
96  void clearRxBuffer()
97  {
98  rx_buffer_.clear();
99  rx_len_ = 0;
100  }
101 
131 
132  Base base_;
133  std::vector<uint8_t> rx_buffer_;
135  int rx_len_;
136 
137 private:
138  int unpack(uint8_t* rx_data);
139  void getRobotInfo();
140  void publishCapacityData();
141 
143  const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
144  const int k_unpack_buffer_length_ = 256;
145  uint8_t unpack_buffer_[256]{};
146 };
147 
148 } // namespace rm_referee
rm_referee::Base
Definition: data.h:142
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
ros::Publisher
ros
ros.h
rm_referee::Referee::unpack
int unpack(uint8_t *rx_data)
Definition: referee.cpp:108
rm_referee::Referee::publishCapacityData
void publishCapacityData()
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::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::Referee::k_tail_length_
const int k_tail_length_
Definition: referee.h:205
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rm_referee::Referee::dart_status_pub_
ros::Publisher dart_status_pub_
Definition: referee.h:170
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::Referee::k_cmd_id_length_
const int k_cmd_id_length_
Definition: referee.h:205
rm_referee::Referee::sentry_to_radar_pub_
ros::Publisher sentry_to_radar_pub_
Definition: referee.h:168
rm_referee::Referee::game_robot_status_pub_
ros::Publisher game_robot_status_pub_
Definition: referee.h:164
rm_referee::Referee::shoot_data_pub_
ros::Publisher shoot_data_pub_
Definition: referee.h:176
rm_referee::Referee::bullet_allowance_pub_
ros::Publisher bullet_allowance_pub_
Definition: referee.h:177
rm_referee::Base::initSerial
void initSerial()
Definition: data.h:153
rm_referee::Referee::getRobotInfo
void getRobotInfo()
Definition: referee.cpp:680
referee_base.h
rm_referee::Referee::sentry_info_pub_
ros::Publisher sentry_info_pub_
Definition: referee.h:184
rm_referee::Referee::power_management_unknown_exception_pub_
ros::Publisher power_management_unknown_exception_pub_
Definition: referee.h:192
rm_referee::Referee::Referee
Referee(ros::NodeHandle &nh)
Definition: referee.h:112
rm_referee::Referee::read
void read()
Definition: referee.cpp:73
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::Referee::dart_info_pub_
ros::Publisher dart_info_pub_
Definition: referee.h:174
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::Referee::power_management_initialization_exception_pub_
ros::Publisher power_management_initialization_exception_pub_
Definition: referee.h:189
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
ros::Time
rm_referee::Referee::clearRxBuffer
void clearRxBuffer()
Definition: referee.h:158
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::RefereeBase
Definition: referee_base.h:19
data.h
rm_referee::Referee::power_management_process_stack_overflow_pub_
ros::Publisher power_management_process_stack_overflow_pub_
Definition: referee.h:191
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::Referee::client_map_receive_pub_
ros::Publisher client_map_receive_pub_
Definition: referee.h:180
rm_referee::Referee::buff_pub_
ros::Publisher buff_pub_
Definition: referee.h:171
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::Referee::supply_projectile_action_pub_
ros::Publisher supply_projectile_action_pub_
Definition: referee.h:173
rm_referee::Referee::radar_to_sentry_pub_
ros::Publisher radar_to_sentry_pub_
Definition: referee.h:187
ROS_INFO
#define ROS_INFO(...)
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::Referee::power_heat_data_pub_
ros::Publisher power_heat_data_pub_
Definition: referee.h:166
ros::NodeHandle
rm_referee::Referee::rfid_status_pub_
ros::Publisher rfid_status_pub_
Definition: referee.h:178


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