Skip to content

Commit

Permalink
Update rm_referee sentry, optimize frame.
Browse files Browse the repository at this point in the history
  • Loading branch information
GuraMumei committed Apr 17, 2024
1 parent 7210d7a commit 95d8b63
Show file tree
Hide file tree
Showing 7 changed files with 150 additions and 111 deletions.
13 changes: 8 additions & 5 deletions rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,10 @@ class RefereeBase
virtual void robotHurtDataCallBack(const rm_msgs::RobotHurt& robot_hurt_data, const ros::Time& last_get_data_time);
virtual void bulletRemainDataCallBack(const rm_msgs::BulletAllowance& bullet_allowance,
const ros::Time& last_get_data_time);
virtual void updateHeroStateDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data,
const ros::Time& last_get_data_time);
virtual void interactiveDataCallBack(const rm_referee::InteractiveData& interactive_data,
const ros::Time& last_get_data_time);
virtual void eventDataCallBack(const rm_msgs::EventData& event_data, const ros::Time& last_get_data_time);
virtual void updateHeroHitDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data);

// sub call back
virtual void jointStateCallback(const sensor_msgs::JointState::ConstPtr& joint_state);
Expand All @@ -59,6 +58,7 @@ class RefereeBase
virtual void sendCurrentSentryCallback(const rm_msgs::CurrentSentryPosDataConstPtr& data);
virtual void sendSentryCmdCallback(const rm_msgs::SentryInfoConstPtr& data);
virtual void sendRadarCmdCallback(const rm_msgs::RadarInfoConstPtr& data);
virtual void sendSentryStateCallback(const std_msgs::StringConstPtr& data);

// send ui
void sendSerialDataCallback();
Expand All @@ -82,10 +82,10 @@ class RefereeBase
ros::Subscriber balance_state_sub_;
ros::Subscriber radar_receive_sub_;
ros::Subscriber map_sentry_sub_;
ros::Subscriber sentry_deviate_sub_;
ros::Subscriber radar_to_sentry_sub_;
ros::Subscriber sentry_cmd_sub_;
ros::Subscriber radar_cmd_sub_;
ros::Subscriber sentry_state_sub_;

ChassisTriggerChangeUi* chassis_trigger_change_ui_{};
ShooterTriggerChangeUi* shooter_trigger_change_ui_{};
Expand Down Expand Up @@ -114,7 +114,11 @@ class RefereeBase

CoverFlashUi* cover_flash_ui_{};
SpinFlashUi* spin_flash_ui_{};
HeroStateFlashUi* hero_state_flash_ui_{};
HeroHitFlashUi* hero_hit_flash_ui_{};

InteractiveSender* interactive_data_sender_{};
InteractiveSender* enemy_hero_state_sender_{};
InteractiveSender* sentry_state_sender_{};

GroupUiBase* graph_queue_sender_{};
std::deque<Graph> graph_queue_;
Expand All @@ -123,7 +127,6 @@ class RefereeBase
ros::Time radar_interactive_data_last_send_;
ros::Time sentry_interactive_data_last_send_;
ros::Time sentry_cmd_data_last_send_, radar_cmd_data_last_send_;
UiBase* interactive_data_sender_{};

Base& base_;
ros::Timer add_ui_timer_, send_serial_data_timer_;
Expand Down
20 changes: 9 additions & 11 deletions rm_referee/include/rm_referee/ui/flash_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,21 +49,19 @@ class SpinFlashUi : public FlashUi
uint8_t chassis_mode_;
};

class HeroStateFlashUi : public FlashUi
class HeroHitFlashUi : public FlashUi
{
public:
explicit HeroStateFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashUi(rpc_value, base, "hero_state", graph_queue, character_queue)
explicit HeroHitFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashUi(rpc_value, base, " hero_hit", graph_queue, character_queue)
{
ros::NodeHandle nh;
timer_ = nh.createTimer(ros::Duration(delay_), std::bind(&HeroStateFlashUi::delayDisplay, this), false, false);
};
void updateHeroStateData(const rm_msgs::GameRobotHp& data, const ros::Time& last_get_data_time);
}
void updateHittingConfig(const rm_msgs::GameRobotHp& msg);

private:
void delayDisplay();
ros::Timer timer_;
bool enemy_hero_die_{ false };
void display(const ros::Time& time) override;
bool hitted_;
rm_msgs::GameRobotHp last_hp_msg_;
};
} // namespace rm_referee
26 changes: 19 additions & 7 deletions rm_referee/include/rm_referee/ui/ui_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,14 +41,7 @@ class UiBase

void sendCharacter(const ros::Time& time, Graph* graph);
void sendSingleGraph(const ros::Time& time, Graph* graph);
void sendInteractiveData(int data_cmd_id, int receiver_id, unsigned char data);
void sendRadarInteractiveData(const rm_referee::ClientMapReceiveData& data);
void sendMapSentryData(const rm_referee::MapSentryData& data);
void sendCurrentSentryData(const rm_msgs::CurrentSentryPosDataConstPtr& data);
void sendCustomInfoData(std::wstring data);
void transferInt(const int data);
void sendSentryCmdData(const rm_msgs::SentryInfoConstPtr& data);
void sendRadarCmdData(const rm_msgs::RadarInfoConstPtr& data);

void sendSerial(const ros::Time& time, int data_len);
void clearTxBuffer();
Expand Down Expand Up @@ -76,6 +69,25 @@ class UiBase
const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
};

class InteractiveSender : public UiBase
{
public:
explicit InteractiveSender(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue = nullptr,
std::deque<Graph>* character_queue = nullptr)
: UiBase(rpc_value, base, graph_queue, character_queue){};

void sendInteractiveData(int data_cmd_id, int receiver_id, unsigned char data);
void sendRadarInteractiveData(const rm_referee::ClientMapReceiveData& data);
void sendMapSentryData(const rm_referee::MapSentryData& data);
void sendCurrentSentryData(const rm_msgs::CurrentSentryPosDataConstPtr& data);
void sendCustomInfoData(std::wstring data);
void sendSentryCmdData(const rm_msgs::SentryInfoConstPtr& data);
void sendRadarCmdData(const rm_msgs::RadarInfoConstPtr& data);

protected:
std::wstring last_custom_info_;
};

class GroupUiBase : public UiBase
{
public:
Expand Down
57 changes: 30 additions & 27 deletions rm_referee/src/referee.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ int Referee::unpack(uint8_t* rx_data)
game_robot_hp_data.stamp = last_get_data_time_;

referee_ui_.updateEnemyHeroState(game_robot_hp_data, last_get_data_time_);
referee_ui_.updateHeroStateDataCallBack(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;
}
Expand Down Expand Up @@ -590,32 +590,30 @@ int Referee::unpack(uint8_t* rx_data)
void Referee::getRobotInfo()
{
base_.robot_color_ = base_.robot_id_ >= 100 ? "blue" : "red";
if (base_.robot_id_ != rm_referee::RobotId::BLUE_SENTRY && base_.robot_id_ != rm_referee::RobotId::RED_SENTRY)
switch (base_.robot_id_)
{
switch (base_.robot_id_)
{
case rm_referee::RobotId::BLUE_HERO:
base_.client_id_ = rm_referee::ClientId::BLUE_HERO_CLIENT;
break;
case rm_referee::RobotId::BLUE_ENGINEER:
base_.client_id_ = rm_referee::ClientId::BLUE_ENGINEER_CLIENT;
break;
case rm_referee::RobotId::BLUE_STANDARD_3:
base_.client_id_ = rm_referee::ClientId::BLUE_STANDARD_3_CLIENT;
break;
case rm_referee::RobotId::BLUE_STANDARD_4:
base_.client_id_ = rm_referee::ClientId::BLUE_STANDARD_4_CLIENT;
break;
case rm_referee::RobotId::BLUE_STANDARD_5:
base_.client_id_ = rm_referee::ClientId::BLUE_STANDARD_5_CLIENT;
break;
case rm_referee::RobotId::BLUE_AERIAL:
base_.client_id_ = rm_referee::ClientId::BLUE_AERIAL_CLIENT;
break;
case rm_referee::RobotId::RED_HERO:
base_.client_id_ = rm_referee::ClientId::RED_HERO_CLIENT;
break;
case rm_referee::RobotId::RED_ENGINEER:
case rm_referee::RobotId::BLUE_HERO:
base_.client_id_ = rm_referee::ClientId::BLUE_HERO_CLIENT;
break;
case rm_referee::RobotId::BLUE_ENGINEER:
base_.client_id_ = rm_referee::ClientId::BLUE_ENGINEER_CLIENT;
break;
case rm_referee::RobotId::BLUE_STANDARD_3:
base_.client_id_ = rm_referee::ClientId::BLUE_STANDARD_3_CLIENT;
break;
case rm_referee::RobotId::BLUE_STANDARD_4:
base_.client_id_ = rm_referee::ClientId::BLUE_STANDARD_4_CLIENT;
break;
case rm_referee::RobotId::BLUE_STANDARD_5:
base_.client_id_ = rm_referee::ClientId::BLUE_STANDARD_5_CLIENT;
break;
case rm_referee::RobotId::BLUE_AERIAL:
base_.client_id_ = rm_referee::ClientId::BLUE_AERIAL_CLIENT;
break;
case rm_referee::RobotId::RED_HERO:
base_.client_id_ = rm_referee::ClientId::RED_HERO_CLIENT;
break;
case rm_referee::RobotId::RED_ENGINEER:
base_.client_id_ = rm_referee::ClientId::RED_ENGINEER_CLIENT;
break;
case rm_referee::RobotId::RED_STANDARD_3:
Expand All @@ -630,7 +628,12 @@ void Referee::getRobotInfo()
case rm_referee::RobotId::RED_AERIAL:
base_.client_id_ = rm_referee::ClientId::RED_AERIAL_CLIENT;
break;
}
case rm_referee::RobotId::BLUE_SENTRY:
base_.client_id_ = rm_referee::ClientId::BLUE_AERIAL_CLIENT;
break;
case rm_referee::RobotId::RED_SENTRY:
base_.client_id_ = rm_referee::ClientId::RED_AERIAL_CLIENT;
break;
}
}
} // namespace rm_referee
69 changes: 44 additions & 25 deletions rm_referee/src/referee_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
//

#include "rm_referee/referee_base.h"
#include <codecvt>

namespace rm_referee
{
Expand Down Expand Up @@ -35,20 +36,20 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
nh.subscribe<rm_msgs::MapSentryData>("/map_sentry_data", 10, &RefereeBase::mapSentryCallback, this);
RefereeBase::radar_receive_sub_ =
nh.subscribe<rm_msgs::ClientMapReceiveData>("/rm_radar", 10, &RefereeBase::radarReceiveCallback, this);
RefereeBase::sentry_deviate_sub_ =
nh.subscribe<rm_msgs::SentryDeviate>("/deviate", 10, &RefereeBase::sentryDeviateCallback, this);
RefereeBase::radar_to_sentry_sub_ = nh.subscribe<rm_msgs::CurrentSentryPosData>(
"/radar_to_sentry", 10, &RefereeBase::sendCurrentSentryCallback, this);
RefereeBase::sentry_cmd_sub_ =
nh.subscribe<rm_msgs::SentryInfo>("/sentry_cmd", 1, &RefereeBase::sendSentryCmdCallback, this);
RefereeBase::radar_cmd_sub_ =
nh.subscribe<rm_msgs::RadarInfo>("/radar_cmd", 1, &RefereeBase::sendRadarCmdCallback, this);
RefereeBase::sentry_state_sub_ =
nh.subscribe<std_msgs::String>("/sentry_state", 1, &RefereeBase::sendSentryStateCallback, this);

XmlRpc::XmlRpcValue rpc_value;
send_ui_queue_delay_ = getParam(nh, "send_ui_queue_delay", 0.15);
add_ui_frequency_ = getParam(nh, "add_ui_frequency", 5);
add_ui_max_times_ = getParam(nh, "add_ui_max_times", 10);
interactive_data_sender_ = new UiBase(rpc_value, base_);
interactive_data_sender_ = new InteractiveSender(rpc_value, base_);
if (nh.hasParam("ui"))
{
ros::NodeHandle ui_nh(nh, "ui");
Expand Down Expand Up @@ -134,8 +135,19 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
cover_flash_ui_ = new CoverFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "spin")
spin_flash_ui_ = new SpinFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "hero_state")
hero_state_flash_ui_ = new HeroStateFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "hero_hit")
hero_hit_flash_ui_ = new HeroHitFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
}
}
if (nh.hasParam("interactive_data"))
{
nh.getParam("interactive_data", rpc_value);
for (int i = 0; i < rpc_value.size(); i++)
{
if (rpc_value[i]["name"] == "enemy_hero_state")
enemy_hero_state_sender_ = new InteractiveSender(rpc_value[i], base_);
if (rpc_value[i]["name"] == "sentry_state")
sentry_state_sender_ = new InteractiveSender(rpc_value[i], base_);
}
}

Expand Down Expand Up @@ -289,31 +301,31 @@ void RefereeBase::robotStatusDataCallBack(const rm_msgs::GameRobotStatus& data,
void RefereeBase::updateEnemyHeroState(const rm_msgs::GameRobotHp& game_robot_hp_data,
const ros::Time& last_get_data_time)
{
std::wstring data;
if (base_.robot_id_ < 100 && base_.robot_id_ != RED_SENTRY)
{
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 && base_.robot_id_ != BLUE_SENTRY)
if (enemy_hero_state_sender_)
{
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"敌方英雄死亡";
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);
}
else
return;
interactive_data_sender_->sendCustomInfoData(data);
}

void RefereeBase::updateHeroStateDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data,
const ros::Time& last_get_data_time)
void RefereeBase::updateHeroHitDataCallBack(const rm_msgs::GameRobotHp& game_robot_hp_data)
{
if (hero_state_flash_ui_)
hero_state_flash_ui_->updateHeroStateData(game_robot_hp_data, last_get_data_time);
if (hero_hit_flash_ui_)
hero_hit_flash_ui_->updateHittingConfig(game_robot_hp_data);
}
void RefereeBase::gameStatusDataCallBack(const rm_msgs::GameStatus& data, const ros::Time& last_get_data_time)
{
Expand Down Expand Up @@ -514,4 +526,11 @@ void RefereeBase::sendRadarCmdCallback(const rm_msgs::RadarInfoConstPtr& data)
}
}

void RefereeBase::sendSentryStateCallback(const std_msgs::StringConstPtr& data)
{
std::wstring_convert<std::codecvt_utf8<wchar_t>> converter;
if (sentry_state_sender_)
sentry_state_sender_->sendCustomInfoData(converter.from_bytes(data->data));
}

} // namespace rm_referee
Loading

0 comments on commit 95d8b63

Please sign in to comment.