Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
rm_referee::Referee Class Reference

#include <referee.h>

Public Member Functions

void clearRxBuffer ()
 
void read ()
 
 Referee (ros::NodeHandle &nh)
 

Public Attributes

Base base_
 
ros::Publisher buff_pub_
 
ros::Publisher bullet_allowance_pub_
 
ros::Publisher client_map_receive_pub_
 
ros::Publisher client_map_send_data_pub_
 
ros::Publisher dart_client_cmd_pub_
 
ros::Publisher dart_info_pub_
 
ros::Publisher dart_status_pub_
 
ros::Publisher event_data_pub_
 
ros::Publisher game_robot_hp_pub_
 
ros::Publisher game_robot_pos_pub_
 
ros::Publisher game_robot_status_pub_
 
ros::Publisher game_status_pub_
 
ros::Publisher icra_buff_debuff_zone_status_pub_
 
ros::Publisher power_heat_data_pub_
 
ros::Publisher power_management_initialization_exception_pub_
 
ros::Publisher power_management_process_stack_overflow_pub_
 
ros::Publisher power_management_sample_and_status_data_pub_
 
ros::Publisher power_management_system_exception_data_
 
ros::Publisher power_management_unknown_exception_pub_
 
ros::Publisher radar_info_pub_
 
ros::Publisher radar_mark_pub_
 
ros::Publisher radar_to_sentry_pub_
 
rm_referee::RefereeBase referee_ui_
 
ros::Publisher rfid_status_pub_
 
ros::Publisher robot_hurt_pub_
 
ros::Publisher robots_position_pub_
 
std::vector< uint8_t > rx_buffer_
 
int rx_len_
 
ros::Publisher sentry_info_pub_
 
ros::Publisher sentry_to_radar_pub_
 
ros::Publisher shoot_data_pub_
 
ros::Publisher supply_projectile_action_pub_
 

Private Member Functions

void getRobotInfo ()
 
void publishCapacityData ()
 
int unpack (uint8_t *rx_data)
 

Private Attributes

const int k_cmd_id_length_ = 2
 
const int k_frame_length_ = 128
 
const int k_header_length_ = 5
 
const int k_tail_length_ = 2
 
const int k_unpack_buffer_length_ = 256
 
ros::Time last_get_data_time_
 
uint8_t unpack_buffer_ [256] {}
 

Detailed Description

Definition at line 78 of file referee.h.

Constructor & Destructor Documentation

◆ Referee()

rm_referee::Referee::Referee ( ros::NodeHandle nh)
inline

Definition at line 112 of file referee.h.

Member Function Documentation

◆ clearRxBuffer()

void rm_referee::Referee::clearRxBuffer ( )
inline

Definition at line 158 of file referee.h.

◆ getRobotInfo()

void rm_referee::Referee::getRobotInfo ( )
private

Definition at line 680 of file referee.cpp.

◆ publishCapacityData()

void rm_referee::Referee::publishCapacityData ( )
private

◆ read()

void rm_referee::Referee::read ( )

Definition at line 73 of file referee.cpp.

◆ unpack()

int rm_referee::Referee::unpack ( uint8_t *  rx_data)
private

Definition at line 108 of file referee.cpp.

Member Data Documentation

◆ base_

Base rm_referee::Referee::base_

Definition at line 194 of file referee.h.

◆ buff_pub_

ros::Publisher rm_referee::Referee::buff_pub_

Definition at line 171 of file referee.h.

◆ bullet_allowance_pub_

ros::Publisher rm_referee::Referee::bullet_allowance_pub_

Definition at line 177 of file referee.h.

◆ client_map_receive_pub_

ros::Publisher rm_referee::Referee::client_map_receive_pub_

Definition at line 180 of file referee.h.

◆ client_map_send_data_pub_

ros::Publisher rm_referee::Referee::client_map_send_data_pub_

Definition at line 186 of file referee.h.

◆ dart_client_cmd_pub_

ros::Publisher rm_referee::Referee::dart_client_cmd_pub_

Definition at line 179 of file referee.h.

◆ dart_info_pub_

ros::Publisher rm_referee::Referee::dart_info_pub_

Definition at line 174 of file referee.h.

◆ dart_status_pub_

ros::Publisher rm_referee::Referee::dart_status_pub_

Definition at line 170 of file referee.h.

◆ event_data_pub_

ros::Publisher rm_referee::Referee::event_data_pub_

Definition at line 169 of file referee.h.

◆ game_robot_hp_pub_

ros::Publisher rm_referee::Referee::game_robot_hp_pub_

Definition at line 167 of file referee.h.

◆ game_robot_pos_pub_

ros::Publisher rm_referee::Referee::game_robot_pos_pub_

Definition at line 183 of file referee.h.

◆ game_robot_status_pub_

ros::Publisher rm_referee::Referee::game_robot_status_pub_

Definition at line 164 of file referee.h.

◆ game_status_pub_

ros::Publisher rm_referee::Referee::game_status_pub_

Definition at line 165 of file referee.h.

◆ icra_buff_debuff_zone_status_pub_

ros::Publisher rm_referee::Referee::icra_buff_debuff_zone_status_pub_

Definition at line 172 of file referee.h.

◆ k_cmd_id_length_

const int rm_referee::Referee::k_cmd_id_length_ = 2
private

Definition at line 205 of file referee.h.

◆ k_frame_length_

const int rm_referee::Referee::k_frame_length_ = 128
private

Definition at line 205 of file referee.h.

◆ k_header_length_

const int rm_referee::Referee::k_header_length_ = 5
private

Definition at line 205 of file referee.h.

◆ k_tail_length_

const int rm_referee::Referee::k_tail_length_ = 2
private

Definition at line 205 of file referee.h.

◆ k_unpack_buffer_length_

const int rm_referee::Referee::k_unpack_buffer_length_ = 256
private

Definition at line 206 of file referee.h.

◆ last_get_data_time_

ros::Time rm_referee::Referee::last_get_data_time_
private

Definition at line 204 of file referee.h.

◆ power_heat_data_pub_

ros::Publisher rm_referee::Referee::power_heat_data_pub_

Definition at line 166 of file referee.h.

◆ power_management_initialization_exception_pub_

ros::Publisher rm_referee::Referee::power_management_initialization_exception_pub_

Definition at line 189 of file referee.h.

◆ power_management_process_stack_overflow_pub_

ros::Publisher rm_referee::Referee::power_management_process_stack_overflow_pub_

Definition at line 191 of file referee.h.

◆ power_management_sample_and_status_data_pub_

ros::Publisher rm_referee::Referee::power_management_sample_and_status_data_pub_

Definition at line 188 of file referee.h.

◆ power_management_system_exception_data_

ros::Publisher rm_referee::Referee::power_management_system_exception_data_

Definition at line 190 of file referee.h.

◆ power_management_unknown_exception_pub_

ros::Publisher rm_referee::Referee::power_management_unknown_exception_pub_

Definition at line 192 of file referee.h.

◆ radar_info_pub_

ros::Publisher rm_referee::Referee::radar_info_pub_

Definition at line 185 of file referee.h.

◆ radar_mark_pub_

ros::Publisher rm_referee::Referee::radar_mark_pub_

Definition at line 182 of file referee.h.

◆ radar_to_sentry_pub_

ros::Publisher rm_referee::Referee::radar_to_sentry_pub_

Definition at line 187 of file referee.h.

◆ referee_ui_

rm_referee::RefereeBase rm_referee::Referee::referee_ui_

Definition at line 196 of file referee.h.

◆ rfid_status_pub_

ros::Publisher rm_referee::Referee::rfid_status_pub_

Definition at line 178 of file referee.h.

◆ robot_hurt_pub_

ros::Publisher rm_referee::Referee::robot_hurt_pub_

Definition at line 175 of file referee.h.

◆ robots_position_pub_

ros::Publisher rm_referee::Referee::robots_position_pub_

Definition at line 181 of file referee.h.

◆ rx_buffer_

std::vector<uint8_t> rm_referee::Referee::rx_buffer_

Definition at line 195 of file referee.h.

◆ rx_len_

int rm_referee::Referee::rx_len_

Definition at line 197 of file referee.h.

◆ sentry_info_pub_

ros::Publisher rm_referee::Referee::sentry_info_pub_

Definition at line 184 of file referee.h.

◆ sentry_to_radar_pub_

ros::Publisher rm_referee::Referee::sentry_to_radar_pub_

Definition at line 168 of file referee.h.

◆ shoot_data_pub_

ros::Publisher rm_referee::Referee::shoot_data_pub_

Definition at line 176 of file referee.h.

◆ supply_projectile_action_pub_

ros::Publisher rm_referee::Referee::supply_projectile_action_pub_

Definition at line 173 of file referee.h.

◆ unpack_buffer_

uint8_t rm_referee::Referee::unpack_buffer_[256] {}
private

Definition at line 207 of file referee.h.


The documentation for this class was generated from the following files:


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