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

[pull] master from rm-controls:master #16

Merged
merged 16 commits into from
Jul 31, 2024
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: 2 additions & 0 deletions rm_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ add_message_files(
RadarInfo.msg
Buff.msg
RadarToSentry.msg
SentryCmd.msg
VisualizeStateData.msg
PowerManagementSampleAndStatusData.msg
PowerManagementInitializationExceptionData.msg
PowerManagementProcessStackOverflowData.msg
Expand Down
28 changes: 19 additions & 9 deletions rm_msgs/msg/referee/ClientMapSendData.msg
Original file line number Diff line number Diff line change
@@ -1,20 +1,30 @@
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
uint8 command_keyboard
uint8 target_robot_ID
uint8 cmd_source

time stamp
1 change: 1 addition & 0 deletions rm_msgs/msg/referee/SentryCmd.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
uint32 sentry_info
3 changes: 2 additions & 1 deletion rm_msgs/msg/referee/SentryInfo.msg
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
uint32 sentry_info
uint16 sentry_info_2
bool is_out_of_war
uint16 remaining_bullets_can_supply
1 change: 1 addition & 0 deletions rm_msgs/msg/referee/VisualizeStateData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
bool[] state
2 changes: 2 additions & 0 deletions rm_msgs/srv/SetLimitVel.srv
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
float32 limit_vel
float32 slide_window
---
float32 current_limit_vel
float32 current_slide_window
3 changes: 3 additions & 0 deletions rm_referee/include/rm_referee/common/data.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include "std_msgs/UInt32.h"
#include "rm_msgs/VisualizeStateData.h"

#include "rm_referee/common/protocol.h"

Expand Down Expand Up @@ -83,6 +85,7 @@
#include <rm_msgs/IcraBuffDebuffZoneStatus.h>
#include <rm_msgs/GameRobotPosData.h>
#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"
Expand Down
17 changes: 12 additions & 5 deletions rm_referee/include/rm_referee/common/protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -544,8 +544,7 @@ typedef struct
{
InteractiveDataHeader header;
uint32_t sentry_info;
uint16_t sentry_info_2;
} __packed SentryInfo;
} __packed SentryCmd;

typedef struct
{
Expand All @@ -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;
Expand Down
15 changes: 9 additions & 6 deletions rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -59,12 +58,14 @@ 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 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);
virtual void customizeDisplayCmdCallBack(const std_msgs::UInt32ConstPtr& data);
virtual void visualizeStateDataCallBack(const rm_msgs::VisualizeStateDataConstPtr& data);

// send ui
void sendSerialDataCallback();
Expand Down Expand Up @@ -95,6 +96,8 @@ class RefereeBase
ros::Subscriber sentry_state_sub_;
ros::Subscriber drone_pose_sub_;
ros::Subscriber shoot_cmd_sub_;
ros::Subscriber customize_display_cmd_sub_;
ros::Subscriber visualize_state_data_sub_;

ChassisTriggerChangeUi* chassis_trigger_change_ui_{};
ShooterTriggerChangeUi* shooter_trigger_change_ui_{};
Expand All @@ -121,18 +124,18 @@ class RefereeBase
DroneTowardsTimeChangeGroupUi* drone_towards_time_change_group_ui_{};
StringTriggerChangeUi *servo_mode_trigger_change_ui_{}, *stone_num_trigger_change_ui_{},
*joint_temperature_trigger_change_ui_{}, *gripper_state_trigger_change_ui_{};
VisualizeStateTriggerChangeUi* visualize_state_trigger_change_ui_{};

FixedUi* fixed_ui_{};

CoverFlashUi* cover_flash_ui_{};
SpinFlashUi* spin_flash_ui_{};
HeroHitFlashUi* hero_hit_flash_ui_{};
ExceedBulletSpeedFlashUi* exceed_bullet_speed_flash_ui_{};
EngineerActionFlashUi* engineer_action_flash_ui_{};
CustomizeDisplayFlashUi* customize_display_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_{};
Expand Down
34 changes: 27 additions & 7 deletions rm_referee/include/rm_referee/ui/flash_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,18 +33,19 @@ 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:
std::string graph_name_;
};

class EngineerActionFlashUi : public FlashGroupUi
class CustomizeDisplayFlashUi : public FlashGroupUi
{
public:
explicit EngineerActionFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashGroupUi(rpc_value, base, "engineer_action", graph_queue, character_queue)
explicit CustomizeDisplayFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashGroupUi(rpc_value, base, "customize_display", graph_queue, character_queue)
{
if (rpc_value.hasMember("data"))
{
Expand All @@ -56,7 +57,7 @@ class EngineerActionFlashUi : public FlashGroupUi
}
}
}
void updateEngineerUiCmdData(const rm_msgs::EngineerUi::ConstPtr data, const ros::Time& last_get_data_time);
void updateCmdData(const uint32_t& data);

private:
void display(const ros::Time& time) override;
Expand Down Expand Up @@ -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>* graph_queue,
std::deque<Graph>* 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<std::string, Graph*>("1", new Graph(rpc_value["config"], base_, id_++)));
graph_vector_.insert(std::pair<std::string, Graph*>("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);

Expand Down
4 changes: 2 additions & 2 deletions rm_referee/include/rm_referee/ui/interactive_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand All @@ -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
Expand Down
6 changes: 3 additions & 3 deletions rm_referee/include/rm_referee/ui/time_change_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -347,14 +347,14 @@ class FriendBulletsTimeChangeGroupUi : public TimeChangeGroupUi
graph_vector_.insert(std::pair<std::string, Graph*>("standard3", new Graph(rpc_value["config"], base_, id_++)));
graph_vector_.insert(std::pair<std::string, Graph*>("standard4", new Graph(rpc_value["config"], base_, id_++)));
graph_vector_.insert(std::pair<std::string, Graph*>("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);
}
}
Expand All @@ -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
23 changes: 23 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 @@ -252,4 +252,27 @@ class FrictionSpeedTriggerChangeUi : public TriggerChangeUi
double wheel_speed_;
};

class VisualizeStateTriggerChangeUi : public TriggerChangeGroupUi
{
public:
explicit VisualizeStateTriggerChangeUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, const std::string& name,
std::deque<Graph>* graph_queue, std::deque<Graph>* character_queue)
: TriggerChangeGroupUi(rpc_value, base, name, graph_queue, character_queue)
{
if (rpc_value.hasMember("data"))
{
XmlRpc::XmlRpcValue& data = rpc_value["data"];
for (int i = 0; i < static_cast<int>(rpc_value["data"].size()); i++)
{
graph_vector_.insert(
std::pair<std::string, Graph*>(std::to_string(i), new Graph(data[i]["config"], base_, id_++)));
}
}
};
void updateUiColor(const std::vector<bool>& data);

private:
void update() override;
};

} // namespace rm_referee
15 changes: 11 additions & 4 deletions rm_referee/src/referee.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -520,15 +519,17 @@ 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;
}
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;
}
Expand Down Expand Up @@ -684,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
Loading
Loading