From 4a75d6850a81103a17439520bd3886cbd0de295b Mon Sep 17 00:00:00 2001 From: Guramumei <1421887449@qq.com> Date: Tue, 23 Jul 2024 20:40:27 +0800 Subject: [PATCH 1/6] Update referee. --- rm_msgs/CMakeLists.txt | 1 + rm_msgs/msg/referee/ClientMapSendData.msg | 26 ++++++++++++++----- rm_msgs/msg/referee/SentryCmd.msg | 2 ++ rm_msgs/msg/referee/SentryInfo.msg | 3 ++- rm_referee/include/rm_referee/common/data.h | 1 + .../include/rm_referee/common/protocol.h | 11 ++++++-- rm_referee/include/rm_referee/referee_base.h | 2 +- .../include/rm_referee/ui/interactive_data.h | 2 +- rm_referee/src/referee.cpp | 6 ++++- rm_referee/src/referee_base.cpp | 4 +-- rm_referee/src/ui/interactive_data.cpp | 7 +++-- 11 files changed, 46 insertions(+), 19 deletions(-) create mode 100644 rm_msgs/msg/referee/SentryCmd.msg diff --git a/rm_msgs/CMakeLists.txt b/rm_msgs/CMakeLists.txt index c37a445a..45f5bc28 100644 --- a/rm_msgs/CMakeLists.txt +++ b/rm_msgs/CMakeLists.txt @@ -85,6 +85,7 @@ add_message_files( RadarInfo.msg Buff.msg RadarToSentry.msg + SentryCmd.msg PowerManagementSampleAndStatusData.msg PowerManagementInitializationExceptionData.msg PowerManagementProcessStackOverflowData.msg diff --git a/rm_msgs/msg/referee/ClientMapSendData.msg b/rm_msgs/msg/referee/ClientMapSendData.msg index dab68248..95c530d7 100644 --- a/rm_msgs/msg/referee/ClientMapSendData.msg +++ b/rm_msgs/msg/referee/ClientMapSendData.msg @@ -1,15 +1,27 @@ -uint8 KEY_A = 65 +uint8 KEY_Q = 81 +uint8 KEY_W = 87 uint8 KEY_E = 69 +uint8 KEY_R = 82 +uint8 KEY_T = 84 +uint8 KEY_Y = 89 +uint8 KEY_U = 85 +uint8 KEY_O = 79 + +uint8 KEY_A = 65 +uint8 KEY_S = 83 +uint8 KEY_D = 68 +uint8 KEY_F = 70 +uint8 KEY_G = 71 uint8 KEY_H = 72 +uint8 KEY_J = 74 uint8 KEY_K = 75 uint8 KEY_L = 76 -uint8 KEY_N = 78 -uint8 KEY_O = 79 -uint8 KEY_Q = 81 -uint8 KEY_R = 82 -uint8 KEY_W = 87 -uint8 KEY_U = 85 +uint8 KEY_Z = 90 +uint8 KEY_X = 88 +uint8 KEY_C = 67 +uint8 KEY_V = 86 +uint8 KEY_N = 78 float32 target_position_x float32 target_position_y diff --git a/rm_msgs/msg/referee/SentryCmd.msg b/rm_msgs/msg/referee/SentryCmd.msg new file mode 100644 index 00000000..0584c26f --- /dev/null +++ b/rm_msgs/msg/referee/SentryCmd.msg @@ -0,0 +1,2 @@ +uint32 sentry_info + diff --git a/rm_msgs/msg/referee/SentryInfo.msg b/rm_msgs/msg/referee/SentryInfo.msg index af5a4377..f9319cbe 100644 --- a/rm_msgs/msg/referee/SentryInfo.msg +++ b/rm_msgs/msg/referee/SentryInfo.msg @@ -1,2 +1,3 @@ uint32 sentry_info -uint16 sentry_info_2 +bool is_out_of_war +uint16 remaining_bullets_can_supply diff --git a/rm_referee/include/rm_referee/common/data.h b/rm_referee/include/rm_referee/common/data.h index 632bd286..3fce648e 100644 --- a/rm_referee/include/rm_referee/common/data.h +++ b/rm_referee/include/rm_referee/common/data.h @@ -83,6 +83,7 @@ #include #include #include "rm_msgs/SentryInfo.h" +#include "rm_msgs/SentryCmd.h" #include "rm_msgs/RadarInfo.h" #include "rm_msgs/Buff.h" #include "rm_msgs/TrackData.h" diff --git a/rm_referee/include/rm_referee/common/protocol.h b/rm_referee/include/rm_referee/common/protocol.h index 5027749d..c21a3af2 100644 --- a/rm_referee/include/rm_referee/common/protocol.h +++ b/rm_referee/include/rm_referee/common/protocol.h @@ -544,8 +544,7 @@ typedef struct { InteractiveDataHeader header; uint32_t sentry_info; - uint16_t sentry_info_2; -} __packed SentryInfo; +} __packed SentryCmd; typedef struct { @@ -558,6 +557,14 @@ typedef struct uint8_t data[30]; } __packed CustomControllerData; +typedef struct +{ + uint32_t sentry_info; + uint16_t is_out_of_war : 1; + uint16_t remaining_bullets_can_supply : 11; + uint16_t reverse: 4; +} __packed SentryInfo; + typedef struct { float target_position_x; diff --git a/rm_referee/include/rm_referee/referee_base.h b/rm_referee/include/rm_referee/referee_base.h index 2d3b89f9..2030e5df 100644 --- a/rm_referee/include/rm_referee/referee_base.h +++ b/rm_referee/include/rm_referee/referee_base.h @@ -59,7 +59,7 @@ class RefereeBase virtual void radarReceiveCallback(const rm_msgs::ClientMapReceiveData::ConstPtr& data); virtual void mapSentryCallback(const rm_msgs::MapSentryDataConstPtr& data); virtual void sentryAttackingTargetCallback(const rm_msgs::SentryAttackingTargetConstPtr& data); - virtual void sendSentryCmdCallback(const rm_msgs::SentryInfoConstPtr& data); + virtual void sendSentryCmdCallback(const rm_msgs::SentryCmdConstPtr& data); virtual void sendRadarCmdCallback(const rm_msgs::RadarInfoConstPtr& data); virtual void sendSentryStateCallback(const std_msgs::StringConstPtr& data); virtual void dronePoseCallBack(const geometry_msgs::PoseStampedConstPtr& data); diff --git a/rm_referee/include/rm_referee/ui/interactive_data.h b/rm_referee/include/rm_referee/ui/interactive_data.h index 1a548406..be7ed8c0 100644 --- a/rm_referee/include/rm_referee/ui/interactive_data.h +++ b/rm_referee/include/rm_referee/ui/interactive_data.h @@ -18,7 +18,7 @@ class InteractiveSender : public UiBase void sendInteractiveData(int data_cmd_id, int receiver_id, unsigned char data); void sendRadarInteractiveData(const rm_msgs::ClientMapReceiveData::ConstPtr& data); void sendMapSentryData(const rm_referee::MapSentryData& data); - void sendSentryCmdData(const rm_msgs::SentryInfoConstPtr& data); + void sendSentryCmdData(const rm_msgs::SentryCmdConstPtr& data); void sendRadarCmdData(const rm_msgs::RadarInfoConstPtr& data); virtual bool needSendInteractiveData(); ros::Time last_send_time_; diff --git a/rm_referee/src/referee.cpp b/rm_referee/src/referee.cpp index b181a12e..be1d9238 100644 --- a/rm_referee/src/referee.cpp +++ b/rm_referee/src/referee.cpp @@ -527,8 +527,12 @@ int Referee::unpack(uint8_t* rx_data) } case rm_referee::SENTRY_INFO_CMD: { + rm_referee::SentryInfo sentry_info_ref; rm_msgs::SentryInfo sentry_info; - memcpy(&sentry_info, rx_data + 7, sizeof(rm_msgs::SentryInfo)); + memcpy(&sentry_info_ref, rx_data + 7, sizeof(rm_referee::SentryInfo)); + sentry_info.sentry_info = sentry_info_ref.sentry_info; + sentry_info.is_out_of_war = sentry_info_ref.is_out_of_war; + sentry_info.remaining_bullets_can_supply = sentry_info_ref.remaining_bullets_can_supply; sentry_info_pub_.publish(sentry_info); break; } diff --git a/rm_referee/src/referee_base.cpp b/rm_referee/src/referee_base.cpp index 96ff5800..45e94aaf 100644 --- a/rm_referee/src/referee_base.cpp +++ b/rm_referee/src/referee_base.cpp @@ -37,7 +37,7 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh) RefereeBase::radar_receive_sub_ = nh.subscribe("/rm_radar", 10, &RefereeBase::radarReceiveCallback, this); RefereeBase::sentry_cmd_sub_ = - nh.subscribe("/sentry_cmd", 1, &RefereeBase::sendSentryCmdCallback, this); + nh.subscribe("/sentry_cmd", 1, &RefereeBase::sendSentryCmdCallback, this); RefereeBase::radar_cmd_sub_ = nh.subscribe("/radar_cmd", 1, &RefereeBase::sendRadarCmdCallback, this); RefereeBase::sentry_state_sub_ = @@ -550,7 +550,7 @@ void RefereeBase::mapSentryCallback(const rm_msgs::MapSentryDataConstPtr& data) sentry_interactive_data_last_send_ = ros::Time::now(); } } -void RefereeBase::sendSentryCmdCallback(const rm_msgs::SentryInfoConstPtr& data) +void RefereeBase::sendSentryCmdCallback(const rm_msgs::SentryCmdConstPtr& data) { if (ros::Time::now() - sentry_cmd_data_last_send_ <= ros::Duration(0.15)) return; diff --git a/rm_referee/src/ui/interactive_data.cpp b/rm_referee/src/ui/interactive_data.cpp index 083edd26..d73f6152 100644 --- a/rm_referee/src/ui/interactive_data.cpp +++ b/rm_referee/src/ui/interactive_data.cpp @@ -123,16 +123,15 @@ void InteractiveSender::sendRadarInteractiveData(const rm_msgs::ClientMapReceive clearTxBuffer(); } -void InteractiveSender::sendSentryCmdData(const rm_msgs::SentryInfoConstPtr& data) +void InteractiveSender::sendSentryCmdData(const rm_msgs::SentryCmdConstPtr& data) { int data_len; - rm_referee::SentryInfo tx_data; - data_len = static_cast(sizeof(rm_referee::SentryInfo)); + rm_referee::SentryCmd tx_data; + data_len = static_cast(sizeof(rm_referee::SentryCmd)); tx_data.header.sender_id = base_.robot_id_; tx_data.header.receiver_id = REFEREE_SERVER; tx_data.sentry_info = data->sentry_info; - tx_data.sentry_info_2 = data->sentry_info_2; tx_data.header.data_cmd_id = rm_referee::DataCmdId::SENTRY_CMD; pack(tx_buffer_, reinterpret_cast(&tx_data), rm_referee::RefereeCmdId::INTERACTIVE_DATA_CMD, data_len); sendSerial(ros::Time::now(), data_len); From f5e56c358e5065c1e37b502be518fe0f62e2d805 Mon Sep 17 00:00:00 2001 From: Guramumei <1421887449@qq.com> Date: Sun, 28 Jul 2024 19:27:20 +0800 Subject: [PATCH 2/6] Update referee. --- rm_referee/include/rm_referee/common/protocol.h | 6 +++--- rm_referee/include/rm_referee/ui/interactive_data.h | 2 +- rm_referee/src/referee.cpp | 2 -- rm_referee/src/ui/interactive_data.cpp | 4 +++- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/rm_referee/include/rm_referee/common/protocol.h b/rm_referee/include/rm_referee/common/protocol.h index c21a3af2..21597e37 100644 --- a/rm_referee/include/rm_referee/common/protocol.h +++ b/rm_referee/include/rm_referee/common/protocol.h @@ -69,8 +69,8 @@ typedef enum RADAR_INFO_CMD = 0x020E, INTERACTIVE_DATA_CMD = 0x0301, CUSTOM_CONTROLLER_CMD = 0x0302, // controller - TARGET_POS_CMD = 0x0303, // send aerial->server - ROBOT_COMMAND_CMD = 0x0304, // controller + TARGET_POS_CMD = 0x0303, + ROBOT_COMMAND_CMD = 0x0304, // controller CLIENT_MAP_CMD = 0x0305, CUSTOM_CLIENT_CMD = 0x0306, // controller MAP_SENTRY_CMD = 0x0307, // send sentry->aerial @@ -293,7 +293,7 @@ typedef struct uint8_t ring_elevated_ground_state : 2; uint8_t r3_state : 2; uint8_t r4_state : 2; - uint8_t base_shield_value : 7; + uint16_t base_shield_value : 7; uint16_t be_hit_time : 9; uint8_t be_hit_target : 2; uint8_t central_point_state : 2; diff --git a/rm_referee/include/rm_referee/ui/interactive_data.h b/rm_referee/include/rm_referee/ui/interactive_data.h index be7ed8c0..6c3d6729 100644 --- a/rm_referee/include/rm_referee/ui/interactive_data.h +++ b/rm_referee/include/rm_referee/ui/interactive_data.h @@ -44,7 +44,7 @@ class BulletNumShare : public InteractiveSender : InteractiveSender(rpc_value, base, graph_queue, character_queue){}; void sendBulletData(); void updateBulletRemainData(const rm_msgs::BulletAllowance& data); - int bullet_42_mm_num_, bullet_17_mm_num_, count_receive_time_; + int bullet_42_mm_num_, bullet_17_mm_num_, count_receive_time_{ 0 }; }; class SentryToRadar : public InteractiveSender diff --git a/rm_referee/src/referee.cpp b/rm_referee/src/referee.cpp index be1d9238..034ce909 100644 --- a/rm_referee/src/referee.cpp +++ b/rm_referee/src/referee.cpp @@ -520,8 +520,6 @@ int Referee::unpack(uint8_t* rx_data) client_map_send_data.command_keyboard = client_map_send_data_ref.command_keyboard; client_map_send_data.target_robot_ID = client_map_send_data_ref.target_robot_ID; client_map_send_data.cmd_source = client_map_send_data_ref.cmd_source; - client_map_send_data.stamp = last_get_data_time_; - client_map_send_data_pub_.publish(client_map_send_data); break; } diff --git a/rm_referee/src/ui/interactive_data.cpp b/rm_referee/src/ui/interactive_data.cpp index d73f6152..a706d7b1 100644 --- a/rm_referee/src/ui/interactive_data.cpp +++ b/rm_referee/src/ui/interactive_data.cpp @@ -159,7 +159,9 @@ void BulletNumShare::sendBulletData() receiver_id = RED_HERO; else receiver_id = BLUE_HERO; - receiver_id += (4 - (count_receive_time_ % 3)); + if (count_receive_time_ % 5 == 1) + count_receive_time_++; + receiver_id += count_receive_time_ % 5; uint8_t tx_data[sizeof(BulletNumData)] = { 0 }; auto bullet_num_data = (BulletNumData*)tx_data; From 138cb44ffcd286a2e2398b37535c71ab2784eb34 Mon Sep 17 00:00:00 2001 From: Guramumei <1421887449@qq.com> Date: Sun, 28 Jul 2024 19:27:38 +0800 Subject: [PATCH 3/6] Update rm_msgs. --- rm_msgs/msg/referee/ClientMapSendData.msg | 2 -- 1 file changed, 2 deletions(-) diff --git a/rm_msgs/msg/referee/ClientMapSendData.msg b/rm_msgs/msg/referee/ClientMapSendData.msg index 95c530d7..991c4c9a 100644 --- a/rm_msgs/msg/referee/ClientMapSendData.msg +++ b/rm_msgs/msg/referee/ClientMapSendData.msg @@ -28,5 +28,3 @@ float32 target_position_y uint8 command_keyboard uint8 target_robot_ID uint8 cmd_source - -time stamp From 7858905128d06f18285b9984060718f2f2669851 Mon Sep 17 00:00:00 2001 From: Guramumei <1421887449@qq.com> Date: Mon, 29 Jul 2024 20:54:04 +0800 Subject: [PATCH 4/6] Update referee, optimize hero hit ui. --- rm_referee/include/rm_referee/referee_base.h | 6 +- rm_referee/include/rm_referee/ui/flash_ui.h | 24 ++++++- .../include/rm_referee/ui/time_change_ui.h | 6 +- rm_referee/src/referee.cpp | 7 +- rm_referee/src/referee_base.cpp | 39 ++--------- rm_referee/src/ui/flash_ui.cpp | 64 ++++++++++++++++++- rm_referee/src/ui/time_change_ui.cpp | 1 + 7 files changed, 102 insertions(+), 45 deletions(-) diff --git a/rm_referee/include/rm_referee/referee_base.h b/rm_referee/include/rm_referee/referee_base.h index 2030e5df..0bd6f1c3 100644 --- a/rm_referee/include/rm_referee/referee_base.h +++ b/rm_referee/include/rm_referee/referee_base.h @@ -25,7 +25,6 @@ class RefereeBase // unpack call back virtual void robotStatusDataCallBack(const rm_msgs::GameRobotStatus& game_robot_status_data, const ros::Time& last_get_data_time); - virtual void updateEnemyHeroState(const rm_msgs::GameRobotHp& game_robot_hp_data, const ros::Time& last_get_data_time); virtual void gameStatusDataCallBack(const rm_msgs::GameStatus& game_status_data, const ros::Time& last_get_data_time); virtual void capacityDataCallBack(const rm_msgs::PowerManagementSampleAndStatusData& data, ros::Time& last_get_data_time); @@ -61,7 +60,7 @@ class RefereeBase virtual void sentryAttackingTargetCallback(const rm_msgs::SentryAttackingTargetConstPtr& data); virtual void sendSentryCmdCallback(const rm_msgs::SentryCmdConstPtr& data); virtual void sendRadarCmdCallback(const rm_msgs::RadarInfoConstPtr& data); - virtual void sendSentryStateCallback(const std_msgs::StringConstPtr& data); + virtual void sendCustomInfoCallback(const std_msgs::StringConstPtr& data); virtual void dronePoseCallBack(const geometry_msgs::PoseStampedConstPtr& data); virtual void shootCmdCallBack(const rm_msgs::ShootCmdConstPtr& data); virtual void radarToRefereeCallBack(const rm_msgs::RadarToSentryConstPtr& data); @@ -131,8 +130,7 @@ class RefereeBase EngineerActionFlashUi* engineer_action_flash_ui_{}; InteractiveSender* interactive_data_sender_{}; - // CustomInfoSender* enemy_hero_state_sender_{}; - CustomInfoSender* sentry_state_sender_{}; + CustomInfoSender* custom_info_sender{}; BulletNumShare* bullet_num_share_{}; SentryToRadar* sentry_to_radar_{}; RadarToSentry* radar_to_sentry_{}; diff --git a/rm_referee/include/rm_referee/ui/flash_ui.h b/rm_referee/include/rm_referee/ui/flash_ui.h index ce3937f1..34f5a7dc 100644 --- a/rm_referee/include/rm_referee/ui/flash_ui.h +++ b/rm_referee/include/rm_referee/ui/flash_ui.h @@ -33,6 +33,7 @@ class FlashGroupUi : public GroupUiBase } virtual void display(const ros::Time& time){}; virtual void updateConfig(){}; + void updateFlashUiForQueue(const ros::Time& time, bool state, bool once); void updateFlashUiForQueue(const ros::Time& time, bool state, bool once, Graph* graph); protected: @@ -90,13 +91,32 @@ class SpinFlashUi : public FlashUi uint8_t chassis_mode_; }; -class HeroHitFlashUi : public FlashUi +class HeroHitFlashUi : public FlashGroupUi { public: explicit HeroHitFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque* graph_queue, std::deque* character_queue) - : FlashUi(rpc_value, base, " hero_hit", graph_queue, character_queue) + : FlashGroupUi(rpc_value, base, " hero_hit", graph_queue, character_queue) { + graph_vector_.insert(std::pair("1", new Graph(rpc_value["config"], base_, id_++))); + graph_vector_.insert(std::pair("2", new Graph(rpc_value["config"], base_, id_++))); + for (auto it : graph_vector_) + { + if (it.first == "1") + { + it.second->setStartX(960 + 50); + it.second->setStartY(540 + 50); + it.second->setEndX(960 - 50); + it.second->setEndY(540 - 50); + } + else if (it.first == "2") + { + it.second->setStartX(960 - 50); + it.second->setStartY(540 + 50); + it.second->setEndX(960 + 50); + it.second->setEndY(540 - 50); + } + } } void updateHittingConfig(const rm_msgs::GameRobotHp& msg); diff --git a/rm_referee/include/rm_referee/ui/time_change_ui.h b/rm_referee/include/rm_referee/ui/time_change_ui.h index 7211515a..e662af6d 100644 --- a/rm_referee/include/rm_referee/ui/time_change_ui.h +++ b/rm_referee/include/rm_referee/ui/time_change_ui.h @@ -347,14 +347,14 @@ class FriendBulletsTimeChangeGroupUi : public TimeChangeGroupUi graph_vector_.insert(std::pair("standard3", new Graph(rpc_value["config"], base_, id_++))); graph_vector_.insert(std::pair("standard4", new Graph(rpc_value["config"], base_, id_++))); graph_vector_.insert(std::pair("standard5", new Graph(rpc_value["config"], base_, id_++))); - int ui_start_y; + int ui_start_y = 0; for (auto it = graph_vector_.begin(); it != graph_vector_.end(); ++it) { if (it == graph_vector_.begin()) ui_start_y = it->second->getConfig().start_y; else { - ui_start_y += 40; + ui_start_y -= 40; it->second->setStartY(ui_start_y); } } @@ -363,7 +363,7 @@ class FriendBulletsTimeChangeGroupUi : public TimeChangeGroupUi private: void updateConfig() override; - int hero_bullets_, standard3_bullets_, standard4_bullets_, standard5_bullets_; + int hero_bullets_{ 1 }, standard3_bullets_{ 3 }, standard4_bullets_{ 4 }, standard5_bullets_{ 5 }; }; } // namespace rm_referee diff --git a/rm_referee/src/referee.cpp b/rm_referee/src/referee.cpp index 034ce909..6fdd5984 100644 --- a/rm_referee/src/referee.cpp +++ b/rm_referee/src/referee.cpp @@ -140,7 +140,6 @@ int Referee::unpack(uint8_t* rx_data) game_robot_hp_data.red_base_hp = game_robot_hp_ref.red_base_hp; game_robot_hp_data.stamp = last_get_data_time_; - referee_ui_.updateEnemyHeroState(game_robot_hp_data, last_get_data_time_); referee_ui_.updateHeroHitDataCallBack(game_robot_hp_data); game_robot_hp_pub_.publish(game_robot_hp_data); break; @@ -686,6 +685,12 @@ void Referee::getRobotInfo() case rm_referee::RobotId::RED_SENTRY: base_.client_id_ = rm_referee::ClientId::RED_AERIAL_CLIENT; break; + case rm_referee::RobotId::RED_RADAR: + base_.client_id_ = rm_referee::ClientId::RED_AERIAL_CLIENT; + break; + case rm_referee::RobotId::BLUE_RADAR: + base_.client_id_ = rm_referee::ClientId::BLUE_AERIAL_CLIENT; + break; } } } // namespace rm_referee diff --git a/rm_referee/src/referee_base.cpp b/rm_referee/src/referee_base.cpp index 45e94aaf..b8969e93 100644 --- a/rm_referee/src/referee_base.cpp +++ b/rm_referee/src/referee_base.cpp @@ -41,7 +41,7 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh) RefereeBase::radar_cmd_sub_ = nh.subscribe("/radar_cmd", 1, &RefereeBase::sendRadarCmdCallback, this); RefereeBase::sentry_state_sub_ = - nh.subscribe("/sentry_state", 1, &RefereeBase::sendSentryStateCallback, this); + nh.subscribe("/custom_info", 1, &RefereeBase::sendCustomInfoCallback, this); RefereeBase::drone_pose_sub_ = nh.subscribe("/mavros/vision_pose/pose", 1, &RefereeBase::dronePoseCallBack, this); RefereeBase::shoot_cmd_sub_ = nh.subscribe("/controllers/shooter_controller/command", 1, @@ -159,8 +159,8 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh) { // if (rpc_value[i]["name"] == "enemy_hero_state") // enemy_hero_state_sender_ = new CustomInfoSender(rpc_value[i], base_); - if (rpc_value[i]["name"] == "sentry_state") - sentry_state_sender_ = new CustomInfoSender(rpc_value[i], base_); + if (rpc_value[i]["name"] == "custom_info") + custom_info_sender = new CustomInfoSender(rpc_value[i], base_); if (rpc_value[i]["name"] == "bullet_num_share") bullet_num_share_ = new BulletNumShare(rpc_value[i], base_); if (rpc_value[i]["name"] == "sentry_to_radar") @@ -341,29 +341,6 @@ void RefereeBase::robotStatusDataCallBack(const rm_msgs::GameRobotStatus& data, if (fixed_ui_ && !is_adding_) fixed_ui_->updateForQueue(); } -void RefereeBase::updateEnemyHeroState(const rm_msgs::GameRobotHp& game_robot_hp_data, - const ros::Time& last_get_data_time) -{ - // if (enemy_hero_state_sender_) - // { - // std::wstring data; - // if (base_.robot_id_ < 100) - // { - // if (game_robot_hp_data.blue_1_robot_hp > 0) - // data = L"敌方英雄存活:" + std::to_wstring(game_robot_hp_data.blue_1_robot_hp); - // else - // data = L"敌方英雄死亡"; - // } - // else if (base_.robot_id_ >= 100) - // { - // if (game_robot_hp_data.red_1_robot_hp > 0) - // data = L"敌方英雄存活:" + std::to_wstring(game_robot_hp_data.red_1_robot_hp); - // else - // data = L"敌方英雄死亡"; - // } - // enemy_hero_state_sender_->sendCustomInfoData(data); - // } -} void RefereeBase::updateHeroHitDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data) { @@ -470,10 +447,6 @@ void RefereeBase::cardCmdDataCallback(const rm_msgs::StateCmd::ConstPtr& data) } void RefereeBase::engineerUiDataCallback(const rm_msgs::EngineerUi::ConstPtr& data) { - /*if (progress_time_change_ui_ && !is_adding_) - progress_time_change_ui_->updateEngineerUiData(data, ros::Time::now());*/ - /* if (drag_state_trigger_change_ui_ && !is_adding_) - drag_state_trigger_change_ui_->updateStringUiData(data->drag_state);*/ if (gripper_state_trigger_change_ui_ && !is_adding_) gripper_state_trigger_change_ui_->updateStringUiData(data->gripper_state); if (stone_num_trigger_change_ui_ && !is_adding_) @@ -571,11 +544,11 @@ void RefereeBase::sendRadarCmdCallback(const rm_msgs::RadarInfoConstPtr& data) } } -void RefereeBase::sendSentryStateCallback(const std_msgs::StringConstPtr& data) +void RefereeBase::sendCustomInfoCallback(const std_msgs::StringConstPtr& data) { std::wstring_convert> converter; - if (sentry_state_sender_) - sentry_state_sender_->sendCustomInfoData(converter.from_bytes(data->data)); + if (custom_info_sender) + custom_info_sender->sendCustomInfoData(converter.from_bytes(data->data)); } void RefereeBase::supplyBulletDataCallBack(const rm_msgs::SupplyProjectileAction& data) diff --git a/rm_referee/src/ui/flash_ui.cpp b/rm_referee/src/ui/flash_ui.cpp index d31f39a5..b61f4753 100644 --- a/rm_referee/src/ui/flash_ui.cpp +++ b/rm_referee/src/ui/flash_ui.cpp @@ -35,6 +35,66 @@ void FlashUi::updateFlashUiForQueue(const ros::Time& time, bool state, bool once UiBase::updateForQueue(); } +void FlashGroupUi::updateFlashUiForQueue(const ros::Time& time, bool state, bool once) +{ + if (once) + { + if (state) + { + for (auto graph : graph_vector_) + graph.second->setOperation(rm_referee::GraphOperation::ADD); + for (auto character : character_vector_) + character.second->setOperation(rm_referee::GraphOperation::ADD); + } + else + { + for (auto graph : graph_vector_) + graph.second->setOperation(rm_referee::GraphOperation::DELETE); + for (auto character : character_vector_) + character.second->setOperation(rm_referee::GraphOperation::DELETE); + } + } + else if (time - last_send_ > delay_) + { + ROS_INFO("%f %.3f", last_send_.toSec(), delay_.toSec()); + if (state) + { + for (auto graph : graph_vector_) + graph.second->setOperation(rm_referee::GraphOperation::ADD); + for (auto character : character_vector_) + character.second->setOperation(rm_referee::GraphOperation::ADD); + } + else + { + for (auto graph : graph_vector_) + graph.second->setOperation(rm_referee::GraphOperation::DELETE); + for (auto character : character_vector_) + character.second->setOperation(rm_referee::GraphOperation::DELETE); + } + } + + bool is_repeat = true; + for (auto it : graph_vector_) + if (!it.second->isRepeated()) + is_repeat = false; + for (auto it : character_vector_) + if (!it.second->isRepeated()) + is_repeat = false; + if (is_repeat) + return; + + for (auto it : graph_vector_) + it.second->updateLastConfig(); + for (auto it : character_vector_) + it.second->updateLastConfig(); + + last_send_ = time; + for (auto it : character_vector_) + character_queue_->push_back(*it.second); + for (auto it : graph_vector_) + graph_queue_->push_back(*it.second); +} + void FlashGroupUi::updateFlashUiForQueue(const ros::Time& time, bool state, bool once, Graph* graph) { if (once) @@ -126,9 +186,9 @@ void HeroHitFlashUi::updateHittingConfig(const rm_msgs::GameRobotHp& msg) void HeroHitFlashUi::display(const ros::Time& time) { if (hitted_) - FlashUi::updateFlashUiForQueue(time, true, true); + FlashGroupUi::updateFlashUiForQueue(time, true, true); else - FlashUi::updateFlashUiForQueue(time, false, false); + FlashGroupUi::updateFlashUiForQueue(time, false, false); } void ExceedBulletSpeedFlashUi::display(const ros::Time& time) diff --git a/rm_referee/src/ui/time_change_ui.cpp b/rm_referee/src/ui/time_change_ui.cpp index 7b07d9aa..9df99502 100644 --- a/rm_referee/src/ui/time_change_ui.cpp +++ b/rm_referee/src/ui/time_change_ui.cpp @@ -482,4 +482,5 @@ void FriendBulletsTimeChangeGroupUi::updateConfig() it.second->setIntNum(standard5_bullets_); } } + } // namespace rm_referee From 5d6887e617f04328ef10ad651566ca70af751018 Mon Sep 17 00:00:00 2001 From: Guramumei <1421887449@qq.com> Date: Mon, 29 Jul 2024 21:27:35 +0800 Subject: [PATCH 5/6] Update format. --- rm_referee/include/rm_referee/common/protocol.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rm_referee/include/rm_referee/common/protocol.h b/rm_referee/include/rm_referee/common/protocol.h index 21597e37..c9bb9f8c 100644 --- a/rm_referee/include/rm_referee/common/protocol.h +++ b/rm_referee/include/rm_referee/common/protocol.h @@ -562,7 +562,7 @@ typedef struct uint32_t sentry_info; uint16_t is_out_of_war : 1; uint16_t remaining_bullets_can_supply : 11; - uint16_t reverse: 4; + uint16_t reverse : 4; } __packed SentryInfo; typedef struct From 8a98917d51a5b6b7a1dc00c035289f9bb1496d39 Mon Sep 17 00:00:00 2001 From: Guramumei <1421887449@qq.com> Date: Mon, 29 Jul 2024 21:39:02 +0800 Subject: [PATCH 6/6] Update format. --- rm_msgs/msg/referee/SentryCmd.msg | 1 - 1 file changed, 1 deletion(-) diff --git a/rm_msgs/msg/referee/SentryCmd.msg b/rm_msgs/msg/referee/SentryCmd.msg index 0584c26f..5295edf2 100644 --- a/rm_msgs/msg/referee/SentryCmd.msg +++ b/rm_msgs/msg/referee/SentryCmd.msg @@ -1,2 +1 @@ uint32 sentry_info -