Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rm_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ add_message_files(
DartStatus.msg
IcraBuffDebuffZoneStatus.msg
SupplyProjectileAction.msg
DartRemainingTime.msg
DartInfo.msg
RobotHurt.msg
SentryAttackingTarget.msg
ShootData.msg
Expand Down
1 change: 1 addition & 0 deletions rm_msgs/msg/referee/Buff.msg
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@ uint8 cooling_buff
uint8 defence_buff
uint8 vulnerability_buff
uint16 attack_buff
uint8 remaining_energy
6 changes: 6 additions & 0 deletions rm_msgs/msg/referee/DartInfo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
uint8 dart_remaining_time
uint8 dart_last_aim_state
uint8 enemy_total_hit_received
uint8 dart_current_target

time stamp
4 changes: 0 additions & 4 deletions rm_msgs/msg/referee/DartRemainingTime.msg

This file was deleted.

11 changes: 4 additions & 7 deletions rm_msgs/msg/referee/EventData.msg
Original file line number Diff line number Diff line change
@@ -1,13 +1,10 @@
bool forward_supply_station_state
bool inside_supply_station_state
bool overlapping_supply_station_state
bool nan_overlapping_supply_station_state
bool supplier_zone_state
bool power_rune_activation_point_state
bool small_power_rune_state
bool large_power_rune_state
uint8 ring_elevated_ground_state
uint8 r3_state
uint8 r4_state
uint8 base_shield_value
uint8 central_elevated_ground_state
uint8 trapezoidal_elevated_ground_state
uint16 be_hit_time
uint8 be_hit_target
uint8 central_point_state
Expand Down
2 changes: 0 additions & 2 deletions rm_msgs/msg/referee/GameRobotHp.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,13 @@ uint16 red_1_robot_hp
uint16 red_2_robot_hp
uint16 red_3_robot_hp
uint16 red_4_robot_hp
uint16 red_5_robot_hp
uint16 red_7_robot_hp
uint16 red_outpost_hp
uint16 red_base_hp
uint16 blue_1_robot_hp
uint16 blue_2_robot_hp
uint16 blue_3_robot_hp
uint16 blue_4_robot_hp
uint16 blue_5_robot_hp
uint16 blue_7_robot_hp
uint16 blue_outpost_hp
uint16 blue_base_hp
Expand Down
3 changes: 0 additions & 3 deletions rm_msgs/msg/referee/PowerHeatData.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,3 @@
float32 chassis_volt
float32 chassis_current
float32 chassis_power
uint16 chassis_power_buffer
uint16 shooter_id_1_17_mm_cooling_heat
uint16 shooter_id_2_17_mm_cooling_heat
Expand Down
11 changes: 5 additions & 6 deletions rm_msgs/msg/referee/RadarMarkData.msg
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
uint8 mark_hero_progress
uint8 mark_engineer_progress
uint8 mark_standard_3_progress
uint8 mark_standard_4_progress
uint8 mark_standard_5_progress
uint8 mark_sentry_progress
bool mark_hero_progress
bool mark_engineer_progress
bool mark_standard_3_progress
bool mark_standard_4_progress
bool mark_sentry_progress

time stamp
34 changes: 19 additions & 15 deletions rm_msgs/msg/referee/RfidStatus.msg
Original file line number Diff line number Diff line change
@@ -1,23 +1,27 @@
bool base_buff_point_state
bool own_ring_elevated_ground_state
bool enemy_ring_elevated_ground_state
bool own_r3_state
bool enemy_r3_state
bool own_r4_state
bool enemy_r4_state
bool power_rune_activation_point_state
bool forward_own_launch_ramp_buff_point_state
bool behind_own_launch_ramp_buff_point_state
bool forward_enemy_launch_ramp_buff_point_state
bool behind_enemy_launch_ramp_buff_point_state
bool own_central_elevated_ground_state
bool enemy_central_elevated_ground_state
bool own_trapezoidal_elevated_ground_state
bool enemy_trapezoidal_elevated_ground_state
bool forward_own_terrain_span_buff_point_state
bool behind_own_terrain_span_buff_point_state
bool forward_enemy_terrain_span_buff_point_state
bool behind_enemy_terrain_span_buff_point_state
bool below_central_own_terrain_span_buff_point_state
bool upper_central_own_terrain_span_buff_point_state
bool below_central_enemy_terrain_span_buff_point_state
bool upper_central_enemy_terrain_span_buff_point_state
bool below_road_own_terrain_span_buff_point_state
bool upper_road_own_terrain_span_buff_point_state
bool below_road_enemy_terrain_span_buff_point_state
bool upper_road_enemy_terrain_span_buff_point_state
bool own_fort_buff_point
bool own_outpost_buff_point
bool own_side_restoration_zone
bool own_sentry_patrol_zones
bool enemy_sentry_patrol_zones
bool nan_overlapping_supplier_zone
bool overlapping_supplier_zone
bool own_large_resource_island_point
bool enemy_large_resource_island_point
bool own_exchange_zone
bool central_buff_point
uint32 reverse

time stamp
2 changes: 0 additions & 2 deletions rm_msgs/msg/referee/RobotsPositionData.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,5 @@ float32 standard_3_x
float32 standard_3_y
float32 standard_4_x
float32 standard_4_y
float32 standard_5_x
float32 standard_5_y

time stamp
2 changes: 1 addition & 1 deletion rm_referee/include/rm_referee/common/data.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@
#include <rm_msgs/ManualToReferee.h>
#include <rm_msgs/ClientMapSendData.h>
#include <rm_msgs/RobotsPositionData.h>
#include <rm_msgs/DartRemainingTime.h>
#include <rm_msgs/DartInfo.h>
#include <rm_msgs/StatusChangeRequest.h>
#include <rm_msgs/ClientMapReceiveData.h>
#include <rm_msgs/SupplyProjectileAction.h>
Expand Down
85 changes: 46 additions & 39 deletions rm_referee/include/rm_referee/common/protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ typedef enum
FIELD_EVENTS_CMD = 0x0101,
SUPPLY_PROJECTILE_ACTION_CMD = 0x0102,
REFEREE_WARNING_CMD = 0x0104,
DART_REMAINING_CMD = 0x0105,
DART_INFO_CMD = 0x0105,
ROBOT_STATUS_CMD = 0x0201,
POWER_HEAT_DATA_CMD = 0x0202,
ROBOT_POS_CMD = 0x0203,
Expand All @@ -74,7 +74,8 @@ typedef enum
CLIENT_MAP_CMD = 0x0305,
CUSTOM_CLIENT_CMD = 0x0306, // controller
MAP_SENTRY_CMD = 0x0307, // send sentry->aerial
CUSTOM_INFO_CMD = 0x0308,
CUSTOM_TO_ROBOT_CMD = 0x0308,
ROBOT_TO_CUSTOM_CMD = 0x0309,
POWER_MANAGEMENT_SAMPLE_AND_STATUS_DATA_CMD = 0X8301,
POWER_MANAGEMENT_INITIALIZATION_EXCEPTION_CMD = 0X8302,
POWER_MANAGEMENT_SYSTEM_EXCEPTION_CMD = 0X8303,
Expand Down Expand Up @@ -242,15 +243,15 @@ typedef struct
uint16_t red_2_robot_hp;
uint16_t red_3_robot_hp;
uint16_t red_4_robot_hp;
uint16_t red_5_robot_hp;
uint16_t reserved_1;
uint16_t red_7_robot_hp;
uint16_t red_outpost_hp;
uint16_t red_base_hp;
uint16_t blue_1_robot_hp;
uint16_t blue_2_robot_hp;
uint16_t blue_3_robot_hp;
uint16_t blue_4_robot_hp;
uint16_t blue_5_robot_hp;
uint16_t reserved_2;
uint16_t blue_7_robot_hp;
uint16_t blue_outpost_hp;
uint16_t blue_base_hp;
Expand Down Expand Up @@ -284,19 +285,17 @@ typedef struct

typedef struct
{
uint8_t forward_supply_station_state : 1;
uint8_t inside_supply_station_state : 1;
uint8_t overlapping_supply_station_state : 1;
uint8_t nan_overlapping_supply_station_state : 1;
uint8_t supplier_zone_state : 1;
uint8_t power_rune_activation_point_state : 1;
uint8_t small_power_rune_state : 1;
uint8_t large_power_rune_state : 1;
uint8_t ring_elevated_ground_state : 2;
uint8_t r3_state : 2;
uint8_t r4_state : 2;
uint16_t base_shield_value : 7;
uint8_t central_elevated_ground_state : 2;
uint8_t trapezoidal_elevated_ground_state : 2;
uint16_t be_hit_time : 9;
uint8_t be_hit_target : 2;
uint8_t central_point_state : 2;
uint16_t reserved : 9;
} __packed EventData;

typedef struct
Expand All @@ -317,8 +316,11 @@ typedef struct
typedef struct
{
uint8_t dart_remaining_time;
uint8_t dart_aim_state;
} __packed DartRemainingTime;
uint8_t dart_last_aim_state : 3;
uint8_t enemy_total_hit_received : 3;
uint8_t dart_current_target : 3;
uint8_t reserved;
} __packed DartInfo;

typedef struct
{
Expand All @@ -336,9 +338,9 @@ typedef struct

typedef struct
{
uint16_t chassis_volt;
uint16_t chassis_current;
float chassis_power;
uint16_t reserved_1;
uint16_t reserved_2;
float reserved_3;
uint16_t chassis_power_buffer;
uint16_t shooter_id_1_17_mm_cooling_heat;
uint16_t shooter_id_2_17_mm_cooling_heat;
Expand All @@ -359,6 +361,7 @@ typedef struct
uint8_t defence_buff;
uint8_t vulnerability_buff;
uint16_t attack_buff;
uint8_t remaining_energy;
} __packed Buff;

typedef struct
Expand Down Expand Up @@ -390,26 +393,31 @@ typedef struct
typedef struct
{
uint8_t base_buff_point_state : 1;
uint8_t own_ring_elevated_ground_state : 1;
uint8_t enemy_ring_elevated_ground_state : 1;
uint8_t own_r3_state : 1;
uint8_t enemy_r3_state : 1;
uint8_t own_r4_state : 1;
uint8_t enemy_r4_state : 1;
uint8_t power_rune_activation_point_state : 1;
uint8_t forward_own_launch_ramp_buff_point_state : 1;
uint8_t behind_own_launch_ramp_buff_point_state : 1;
uint8_t forward_enemy_launch_ramp_buff_point_state : 1;
uint8_t behind_enemy_launch_ramp_buff_point_state : 1;
uint8_t own_central_elevated_ground_state : 1;
uint8_t enemy_central_elevated_ground_state : 1;
uint8_t own_trapezoidal_elevated_ground_state : 1;
uint8_t enemy_trapezoidal_elevated_ground_state : 1;
uint8_t forward_own_terrain_span_buff_point_state : 1;
uint8_t behind_own_terrain_span_buff_point_state : 1;
uint8_t forward_enemy_terrain_span_buff_point_state : 1;
uint8_t behind_enemy_terrain_span_buff_point_state : 1;
uint8_t below_central_own_terrain_span_buff_point_state : 1;
uint8_t upper_central_own_terrain_span_buff_point_state : 1;
uint8_t below_central_enemy_terrain_span_buff_point_state : 1;
uint8_t upper_central_enemy_terrain_span_buff_point_state : 1;
uint8_t below_road_own_terrain_span_buff_point_state : 1;
uint8_t upper_road_own_terrain_span_buff_point_state : 1;
uint8_t below_road_enemy_terrain_span_buff_point_state : 1;
uint8_t upper_road_enemy_terrain_span_buff_point_state : 1;
uint8_t own_fort_buff_point : 1;
uint8_t own_outpost_buff_point : 1;
uint8_t own_side_restoration_zone : 1;
uint8_t own_sentry_patrol_zones : 1;
uint8_t enemy_sentry_patrol_zones : 1;
uint8_t nan_overlapping_supplier_zone : 1;
uint8_t overlapping_supplier_zone : 1;
uint8_t own_large_resource_island_point : 1;
uint8_t enemy_large_resource_island_point : 1;
uint8_t own_exchange_zone : 1;
uint8_t central_buff_point : 1;
uint32_t reverse : 12;
uint32_t reversed : 8;
} __packed RfidStatus;

typedef struct
Expand Down Expand Up @@ -489,18 +497,17 @@ typedef struct
float standard_3_y;
float standard_4_x;
float standard_4_y;
float standard_5_x;
float standard_5_y;
float reserved_1;
float reserved_2;
} __packed RobotsPositionData;

typedef struct
{
uint8_t mark_hero_progress;
uint8_t mark_engineer_progress;
uint8_t mark_standard_3_progress;
uint8_t mark_standard_4_progress;
uint8_t mark_standard_5_progress;
uint8_t mark_sentry_progress;
uint8_t mark_hero_progress : 1;
uint8_t mark_engineer_progress : 1;
uint8_t mark_standard_3_progress : 1;
uint8_t mark_standard_4_progress : 1;
uint8_t mark_sentry_progress : 1;
} __packed RadarMarkData;

typedef struct
Expand Down
4 changes: 2 additions & 2 deletions rm_referee/include/rm_referee/referee.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class Referee
icra_buff_debuff_zone_status_pub_ =
nh.advertise<rm_msgs::IcraBuffDebuffZoneStatus>("icra_buff_debuff_zone_status_data", 1);
supply_projectile_action_pub_ = nh.advertise<rm_msgs::SupplyProjectileAction>("supply_projectile_action_data", 1);
dart_remaining_time_pub_ = nh.advertise<rm_msgs::DartRemainingTime>("dart_remaining_time_data", 1);
dart_info_pub_ = nh.advertise<rm_msgs::DartInfo>("dart_info_data", 1);
robot_hurt_pub_ = nh.advertise<rm_msgs::RobotHurt>("robot_hurt_data", 1);
shoot_data_pub_ = nh.advertise<rm_msgs::ShootData>("shoot_data", 1);
bullet_allowance_pub_ = nh.advertise<rm_msgs::BulletAllowance>("bullet_allowance_data", 1);
Expand Down Expand Up @@ -109,7 +109,7 @@ class Referee
ros::Publisher buff_pub_;
ros::Publisher icra_buff_debuff_zone_status_pub_;
ros::Publisher supply_projectile_action_pub_;
ros::Publisher dart_remaining_time_pub_;
ros::Publisher dart_info_pub_;
ros::Publisher robot_hurt_pub_;
ros::Publisher shoot_data_pub_;
ros::Publisher bullet_allowance_pub_;
Expand Down
Loading
Loading