Skip to content

Commit

Permalink
Merge pull request #219 from GuraMumei/master
Browse files Browse the repository at this point in the history
Update rm_referee for engineer, radar and sentry
  • Loading branch information
d0h0s authored Apr 17, 2024
2 parents 2202aab + 01f0129 commit 38a91c3
Show file tree
Hide file tree
Showing 10 changed files with 302 additions and 152 deletions.
25 changes: 14 additions & 11 deletions rm_referee/include/rm_referee/common/protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,8 @@ typedef enum
BLUE_STANDARD_3_CLIENT = 0x0167,
BLUE_STANDARD_4_CLIENT = 0x0168,
BLUE_STANDARD_5_CLIENT = 0x0169,
BLUE_AERIAL_CLIENT = 0x016A
BLUE_AERIAL_CLIENT = 0x016A,
REFEREE_SERVER = 0x8080
} ClientId;

typedef enum
Expand Down Expand Up @@ -386,16 +387,6 @@ typedef struct
uint16_t operate_launch_cmd_time;
} __packed DartClientCmd;

typedef struct
{
uint32_t sentry_info;
} __packed SentryInfo;

typedef struct
{
uint8_t radar_info;
} __packed RadarInfo;

/*********************** Interactive data between robots----0x0301 ********************/
typedef struct
{
Expand Down Expand Up @@ -511,6 +502,18 @@ typedef struct
uint8_t data;
} __packed InteractiveData;

typedef struct
{
InteractiveDataHeader header;
uint32_t sentry_info;
} __packed SentryInfo;

typedef struct
{
InteractiveDataHeader header;
uint8_t radar_info;
} __packed RadarInfo;

typedef struct
{
uint8_t data[30];
Expand Down
21 changes: 16 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 @@ -57,6 +56,9 @@ class RefereeBase
virtual void mapSentryCallback(const rm_msgs::MapSentryDataConstPtr& data);
virtual void sentryDeviateCallback(const rm_msgs::SentryDeviateConstPtr& data);
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 @@ -80,8 +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 All @@ -102,20 +106,27 @@ class RefereeBase
JointPositionTimeChangeUi *engineer_joint1_time_change_ui{}, *engineer_joint2_time_change_ui{},
*engineer_joint3_time_change_ui{};
TargetDistanceTimeChangeUi* target_distance_time_change_ui_{};
StringTriggerChangeUi *step_name_trigger_change_ui_{}, *servo_mode_trigger_change_ui_{},
*reversal_state_trigger_change_ui_{}, *stone_num_trigger_change_ui_{}, *joint_temperature_trigger_change_ui_{},
*drag_state_trigger_change_ui_{}, *gripper_state_trigger_change_ui_{};

FixedUi* fixed_ui_{};

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_;
std::deque<Graph> character_queue_;

ros::Time radar_interactive_data_last_send_;
ros::Time sentry_interactive_data_last_send_;
UiBase* interactive_data_sender_{};
ros::Time sentry_cmd_data_last_send_, radar_cmd_data_last_send_;

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
12 changes: 12 additions & 0 deletions rm_referee/include/rm_referee/ui/trigger_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -226,4 +226,16 @@ class CameraTriggerChangeUi : public TriggerChangeUi
std::string current_camera_{}, camera1_name_{}, camera2_name_{};
};

class StringTriggerChangeUi : public TriggerChangeUi
{
public:
explicit StringTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& name,
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: TriggerChangeUi(rpc_value, base, name, graph_queue, character_queue){};
void updateStringUiData(const std::string& data);

private:
void update() override;
std::string data_;
};
} // namespace rm_referee
24 changes: 19 additions & 5 deletions rm_referee/include/rm_referee/ui/ui_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,6 @@ 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 sendSerial(const ros::Time& time, int data_len);
Expand Down Expand Up @@ -74,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
85 changes: 44 additions & 41 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,47 +590,50 @@ 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:
base_.client_id_ = rm_referee::ClientId::RED_ENGINEER_CLIENT;
break;
case rm_referee::RobotId::RED_STANDARD_3:
base_.client_id_ = rm_referee::ClientId::RED_STANDARD_3_CLIENT;
break;
case rm_referee::RobotId::RED_STANDARD_4:
base_.client_id_ = rm_referee::ClientId::RED_STANDARD_4_CLIENT;
break;
case rm_referee::RobotId::RED_STANDARD_5:
base_.client_id_ = rm_referee::ClientId::RED_STANDARD_5_CLIENT;
break;
case rm_referee::RobotId::RED_AERIAL:
base_.client_id_ = rm_referee::ClientId::RED_AERIAL_CLIENT;
break;
}
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:
base_.client_id_ = rm_referee::ClientId::RED_STANDARD_3_CLIENT;
break;
case rm_referee::RobotId::RED_STANDARD_4:
base_.client_id_ = rm_referee::ClientId::RED_STANDARD_4_CLIENT;
break;
case rm_referee::RobotId::RED_STANDARD_5:
base_.client_id_ = rm_referee::ClientId::RED_STANDARD_5_CLIENT;
break;
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
Loading

0 comments on commit 38a91c3

Please sign in to comment.