Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update referee and add new interactive data sender #235

Merged
merged 11 commits into from
Jul 19, 2024
1 change: 1 addition & 0 deletions rm_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ add_message_files(
SentryInfo.msg
RadarInfo.msg
Buff.msg
RadarToSentry.msg
PowerManagementSampleAndStatusData.msg
PowerManagementInitializationExceptionData.msg
PowerManagementProcessStackOverflowData.msg
Expand Down
15 changes: 12 additions & 3 deletions rm_msgs/msg/referee/ClientMapReceiveData.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,14 @@
uint16 target_robot_ID
float32 target_position_x
float32 target_position_y
uint16 hero_position_x
uint16 hero_position_y
uint16 engineer_position_x
uint16 engineer_position_y
uint16 infantry_3_position_x
uint16 infantry_3_position_y
uint16 infantry_4_position_x
uint16 infantry_4_position_y
uint16 infantry_5_position_x
uint16 infantry_5_position_y
uint16 sentry_position_x
uint16 sentry_position_y

time stamp
4 changes: 4 additions & 0 deletions rm_msgs/msg/referee/RadarToSentry.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
uint8 robot_ID
float32 position_x
float32 position_y
bool engineer_marked
1 change: 1 addition & 0 deletions rm_msgs/msg/referee/SentryInfo.msg
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
uint32 sentry_info
uint16 sentry_info_2
1 change: 1 addition & 0 deletions rm_referee/include/rm_referee/common/data.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@
#include "rm_msgs/Buff.h"
#include "rm_msgs/TrackData.h"
#include "rm_msgs/SentryAttackingTarget.h"
#include "rm_msgs/RadarToSentry.h"
#include <rm_msgs/PowerManagementSampleAndStatusData.h>
#include <rm_msgs/PowerManagementSystemExceptionData.h>
#include <rm_msgs/PowerManagementInitializationExceptionData.h>
Expand Down
35 changes: 29 additions & 6 deletions rm_referee/include/rm_referee/common/protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,8 +95,8 @@ typedef enum
SENTRY_CMD = 0x0120,
RADAR_CMD = 0x0121,
BULLET_NUM_SHARE_CMD = 0x0200, // send robot->aerial
SENTRY_TO_RADAR_CMD = 0x0201 // send sentry->radar
// send radar->sentry
SENTRY_TO_RADAR_CMD = 0x0201, // send sentry->radar
RADAR_TO_SENTRY_CMD = 0x0202 // send radar->sentry
} DataCmdId;

typedef enum
Expand Down Expand Up @@ -354,7 +354,11 @@ typedef struct

typedef struct
{
uint8_t power_rune_buff;
uint8_t recovery_buff;
uint8_t cooling_buff;
uint8_t defence_buff;
uint8_t vulnerability_buff;
uint16_t attack_buff;
} __packed Buff;

typedef struct
Expand Down Expand Up @@ -540,6 +544,7 @@ typedef struct
{
InteractiveDataHeader header;
uint32_t sentry_info;
uint16_t sentry_info_2;
} __packed SentryInfo;

typedef struct
Expand All @@ -564,9 +569,18 @@ typedef struct

typedef struct
{
uint16_t target_robot_ID;
float target_position_x;
float target_position_y;
uint16_t hero_position_x;
uint16_t hero_position_y;
uint16_t engineer_position_x;
uint16_t engineer_position_y;
uint16_t infantry_3_position_x;
uint16_t infantry_3_position_y;
uint16_t infantry_4_position_x;
uint16_t infantry_4_position_y;
uint16_t infantry_5_position_x;
uint16_t infantry_5_position_y;
uint16_t sentry_position_x;
uint16_t sentry_position_y;
} __packed ClientMapReceiveData;

typedef struct
Expand All @@ -577,6 +591,15 @@ typedef struct
float target_position_y;
} __packed SentryAttackingTargetData;

typedef struct
{
InteractiveDataHeader header_data;
uint8_t robot_ID;
float position_x;
float position_y;
bool engineer_marked;
} __packed RadarToSentryData;

typedef struct
{
int16_t mouse_x;
Expand Down
2 changes: 2 additions & 0 deletions rm_referee/include/rm_referee/referee.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ class Referee
sentry_info_pub_ = nh.advertise<rm_msgs::SentryInfo>("sentry_info", 1);
radar_info_pub_ = nh.advertise<rm_msgs::RadarInfo>("radar_info", 1);
sentry_to_radar_pub_ = nh.advertise<rm_msgs::SentryAttackingTarget>("sentry_target_to_radar", 1);
radar_to_sentry_pub_ = nh.advertise<rm_msgs::RadarToSentry>("radar_to_sentry", 1);

ros::NodeHandle power_management_nh = ros::NodeHandle(nh, "power_management");
power_management_sample_and_status_data_pub_ =
Expand Down Expand Up @@ -121,6 +122,7 @@ class Referee
ros::Publisher sentry_info_pub_;
ros::Publisher radar_info_pub_;
ros::Publisher client_map_send_data_pub_;
ros::Publisher radar_to_sentry_pub_;
ros::Publisher power_management_sample_and_status_data_pub_;
ros::Publisher power_management_initialization_exception_pub_;
ros::Publisher power_management_system_exception_data_;
Expand Down
8 changes: 5 additions & 3 deletions rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ class RefereeBase
virtual void sendSentryStateCallback(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);

// send ui
void sendSerialDataCallback();
Expand All @@ -87,8 +88,8 @@ class RefereeBase
ros::Subscriber balance_state_sub_;
ros::Subscriber radar_receive_sub_;
ros::Subscriber map_sentry_sub_;
ros::Subscriber sentry_to_radar_sub_;
ros::Subscriber radar_to_sentry_sub_;
ros::Subscriber sentry_to_referee_sub_;
ros::Subscriber radar_to_referee_sub_;
ros::Subscriber sentry_cmd_sub_;
ros::Subscriber radar_cmd_sub_;
ros::Subscriber sentry_state_sub_;
Expand Down Expand Up @@ -130,10 +131,11 @@ class RefereeBase
EngineerActionFlashUi* engineer_action_flash_ui_{};

InteractiveSender* interactive_data_sender_{};
CustomInfoSender* enemy_hero_state_sender_{};
// CustomInfoSender* enemy_hero_state_sender_{};
CustomInfoSender* sentry_state_sender_{};
BulletNumShare* bullet_num_share_{};
SentryToRadar* sentry_to_radar_{};
RadarToSentry* radar_to_sentry_{};

GroupUiBase* graph_queue_sender_{};
std::deque<Graph> graph_queue_;
Expand Down
20 changes: 17 additions & 3 deletions rm_referee/include/rm_referee/ui/interactive_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ class InteractiveSender : public UiBase
: 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 sendRadarInteractiveData(const rm_msgs::ClientMapReceiveData::ConstPtr& data);
void sendMapSentryData(const rm_referee::MapSentryData& data);
void sendSentryCmdData(const rm_msgs::SentryInfoConstPtr& data);
void sendRadarCmdData(const rm_msgs::RadarInfoConstPtr& data);
Expand Down Expand Up @@ -56,8 +56,22 @@ class SentryToRadar : public InteractiveSender
void updateSentryAttackingTargetData(const rm_msgs::SentryAttackingTargetConstPtr& data);
bool needSendInteractiveData() override;
void sendSentryToRadarData();
ros::Time last_get_data_time_;
float target_position_x_, target_position_y_, robot_id_;
int robot_id_;
float target_position_x_, target_position_y_;
};

class RadarToSentry : public InteractiveSender
{
public:
explicit RadarToSentry(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue = nullptr,
std::deque<Graph>* character_queue = nullptr)
: InteractiveSender(rpc_value, base, graph_queue, character_queue){};
void updateRadarToSentryData(const rm_msgs::RadarToSentryConstPtr& data);
bool needSendInteractiveData() override;
void sendRadarToSentryData();
int robot_id_;
float position_x_, position_y_;
bool engineer_marked_{ false }, has_new_data_{ false };
};

} // namespace rm_referee
29 changes: 18 additions & 11 deletions rm_referee/src/referee.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -307,7 +307,14 @@ int Referee::unpack(uint8_t* rx_data)
case rm_referee::RefereeCmdId::BUFF_CMD:
{
rm_referee::Buff referee_buff;
rm_msgs::Buff robot_buff;
memcpy(&referee_buff, rx_data + 7, sizeof(rm_referee::Buff));
robot_buff.attack_buff = referee_buff.attack_buff;
robot_buff.defence_buff = referee_buff.defence_buff;
robot_buff.vulnerability_buff = referee_buff.vulnerability_buff;
robot_buff.cooling_buff = referee_buff.cooling_buff;
robot_buff.recovery_buff = referee_buff.recovery_buff;
buff_pub_.publish(robot_buff);
break;
}
case rm_referee::RefereeCmdId::AERIAL_ROBOT_ENERGY_CMD:
Expand Down Expand Up @@ -460,7 +467,6 @@ int Referee::unpack(uint8_t* rx_data)
{
rm_referee::InteractiveData interactive_data_ref; // local variable temporarily before moving referee data
memcpy(&interactive_data_ref, rx_data + 7, sizeof(rm_referee::InteractiveData));
// TODO: case cmd_id
if (interactive_data_ref.header_data.data_cmd_id == rm_referee::DataCmdId::BULLET_NUM_SHARE_CMD)
{
rm_referee::BulletNumData bullet_num_data_ref;
Expand All @@ -477,23 +483,24 @@ int Referee::unpack(uint8_t* rx_data)
sentry_attacking_target_data_data.target_position_y = sentry_attacking_target_data_ref.target_position_y;
sentry_to_radar_pub_.publish(sentry_attacking_target_data_data);
}
else if (interactive_data_ref.header_data.data_cmd_id == rm_referee::DataCmdId::RADAR_TO_SENTRY_CMD)
{
rm_referee::RadarToSentryData radar_to_sentry_data_ref;
rm_msgs::RadarToSentry radar_to_sentry_data;
memcpy(&radar_to_sentry_data_ref, rx_data + 7, sizeof(rm_referee::RadarToSentryData));
radar_to_sentry_data.robot_ID = radar_to_sentry_data_ref.robot_ID;
radar_to_sentry_data.position_x = radar_to_sentry_data_ref.position_x;
radar_to_sentry_data.position_y = radar_to_sentry_data_ref.position_y;
radar_to_sentry_data.engineer_marked = radar_to_sentry_data_ref.engineer_marked;
radar_to_sentry_pub_.publish(radar_to_sentry_data);
}
break;
}
case rm_referee::CLIENT_MAP_CMD:
{
rm_referee::ClientMapReceiveData client_map_receive_ref;
rm_msgs::ClientMapReceiveData client_map_receive_data;
memcpy(&client_map_receive_ref, rx_data + 7, sizeof(rm_referee::ClientMapReceiveData));

if (client_map_receive_ref.target_robot_ID == base_.robot_id_)
{
client_map_receive_data.target_robot_ID = client_map_receive_ref.target_robot_ID;
client_map_receive_data.target_position_x = client_map_receive_ref.target_position_x;
client_map_receive_data.target_position_y = client_map_receive_ref.target_position_y;
client_map_receive_data.stamp = last_get_data_time_;

client_map_receive_pub_.publish(client_map_receive_data);
}
break;
}
case rm_referee::CUSTOM_INFO_CMD:
Expand Down
47 changes: 32 additions & 15 deletions rm_referee/src/referee_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,10 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
nh.subscribe<geometry_msgs::PoseStamped>("/mavros/vision_pose/pose", 1, &RefereeBase::dronePoseCallBack, this);
RefereeBase::shoot_cmd_sub_ = nh.subscribe<rm_msgs::ShootCmd>("/controllers/shooter_controller/command", 1,
&RefereeBase::shootCmdCallBack, this);
RefereeBase::sentry_to_radar_sub_ = nh.subscribe<rm_msgs::SentryAttackingTarget>(
RefereeBase::sentry_to_referee_sub_ = nh.subscribe<rm_msgs::SentryAttackingTarget>(
"/sentry_target_to_referee", 1, &RefereeBase::sentryAttackingTargetCallback, this);
RefereeBase::radar_to_referee_sub_ =
nh.subscribe<rm_msgs::RadarToSentry>("/radar_to_referee", 1, &RefereeBase::radarToRefereeCallBack, this);

XmlRpc::XmlRpcValue rpc_value;
send_ui_queue_delay_ = getParam(nh, "send_ui_queue_delay", 0.15);
Expand Down Expand Up @@ -155,14 +157,16 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
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 CustomInfoSender(rpc_value[i], base_);
// 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"] == "bullet_num_share")
bullet_num_share_ = new BulletNumShare(rpc_value[i], base_);
if (rpc_value[i]["name"] == "sentry_to_radar")
sentry_to_radar_ = new SentryToRadar(rpc_value[i], base_);
if (rpc_value[i]["name"] == "radar_to_sentry")
radar_to_sentry_ = new RadarToSentry(rpc_value[i], base_);
}
}

Expand Down Expand Up @@ -248,6 +252,22 @@ void RefereeBase::addUi()

void RefereeBase::sendSerialDataCallback()
{
if (bullet_num_share_ && bullet_num_share_->needSendInteractiveData())
{
bullet_num_share_->sendBulletData();
return;
}
if (sentry_to_radar_ && sentry_to_radar_->needSendInteractiveData())
{
sentry_to_radar_->sendSentryToRadarData();
return;
}
if (radar_to_sentry_ && radar_to_sentry_->needSendInteractiveData())
{
radar_to_sentry_->sendRadarToSentryData();
return;
}

if (graph_queue_.empty() && character_queue_.empty())
return;

Expand All @@ -268,12 +288,7 @@ void RefereeBase::sendSerialDataCallback()
while (character_queue_.size() > 8)
character_queue_.pop_front();
}
if (bullet_num_share_ && bullet_num_share_->needSendInteractiveData())
bullet_num_share_->sendBulletData();
else if (sentry_to_radar_ && sentry_to_radar_->needSendInteractiveData())
sentry_to_radar_->sendSentryToRadarData();
else
sendQueue();
sendQueue();
}
else
sendQueue();
Expand Down Expand Up @@ -508,15 +523,11 @@ void RefereeBase::sentryAttackingTargetCallback(const rm_msgs::SentryAttackingTa
}
void RefereeBase::radarReceiveCallback(const rm_msgs::ClientMapReceiveData::ConstPtr& data)
{
rm_referee::ClientMapReceiveData radar_receive_data;
radar_receive_data.target_position_x = data->target_position_x;
radar_receive_data.target_position_y = data->target_position_y;
radar_receive_data.target_robot_ID = data->target_robot_ID;
if (ros::Time::now() - radar_interactive_data_last_send_ <= ros::Duration(0.1))
if (ros::Time::now() - radar_interactive_data_last_send_ <= ros::Duration(0.2))
return;
else
{
interactive_data_sender_->sendRadarInteractiveData(radar_receive_data);
interactive_data_sender_->sendRadarInteractiveData(data);
radar_interactive_data_last_send_ = ros::Time::now();
}
}
Expand Down Expand Up @@ -595,4 +606,10 @@ void RefereeBase::updateBulletRemainData(const rm_referee::BulletNumData& data)
friend_bullets_time_change_group_ui_->updateBulletsData(data);
}

void RefereeBase::radarToRefereeCallBack(const rm_msgs::RadarToSentryConstPtr& data)
{
if (radar_to_sentry_)
radar_to_sentry_->updateRadarToSentryData(data);
}

} // namespace rm_referee
Loading
Loading