Skip to content

Commit 79e6a96

Browse files
Merge pull request #80 from ljq-lv/new_ui_test
Improve the Ui to reduce data transport
2 parents 3989abc + 54e4b06 commit 79e6a96

30 files changed

+1279
-1390
lines changed

rm_referee/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ include_directories(
6767
)
6868

6969
## Declare cpp executables
70-
FILE(GLOB ALL_SOURCES "src/*.cpp" "src/common/*.cpp" "src/referee/*.cpp")
70+
FILE(GLOB ALL_SOURCES "src/*.cpp" "src/common/*.cpp" "src/ui/*.cpp")
7171
add_executable(${PROJECT_NAME} ${ALL_SOURCES})
7272

7373
## Add dependencies to exported targets, like ROS msgs or srvs

rm_referee/include/rm_referee/common/data.h

Lines changed: 3 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -90,43 +90,12 @@ struct CapacityData
9090
class Base
9191
{
9292
public:
93-
// sub data
94-
uint8_t radar_data_;
95-
sensor_msgs::JointState joint_state_;
96-
geometry_msgs::Twist vel2d_cmd_data_;
97-
rm_msgs::DbusData dbus_data_;
98-
rm_msgs::StateCmd card_cmd_data_;
99-
rm_msgs::ShootCmd shoot_cmd_data_;
100-
rm_msgs::GimbalCmd gimbal_cmd_data_;
101-
rm_msgs::ChassisCmd chassis_cmd_data_;
102-
rm_msgs::ActuatorState actuator_state_;
103-
rm_msgs::EngineerCmd engineer_cmd_data_;
104-
rm_msgs::ManualToReferee manual_to_referee_data_;
105-
106-
// pub data
107-
rm_msgs::EventData event_data_;
108-
rm_msgs::ShootData shoot_data_;
109-
rm_msgs::RobotHurt robot_hurt_data_;
110-
rm_msgs::CapacityData capacity_data_;
111-
rm_msgs::RfidStatus rfid_status_data_;
112-
rm_msgs::DartStatus dart_status_data_;
113-
rm_msgs::GameStatus game_status_data_;
114-
rm_msgs::PowerHeatData power_heat_data_;
115-
rm_msgs::GameRobotHp game_robot_hp_data_;
116-
rm_referee::CapacityData capacity_data_ref_;
117-
rm_msgs::DartClientCmd dart_client_cmd_data_;
118-
rm_msgs::SuperCapacitor super_capacitor_data_;
119-
rm_msgs::BulletRemaining bullet_remaining_data_;
120-
rm_msgs::GameRobotStatus game_robot_status_data_;
121-
rm_msgs::DartRemainingTime dart_remaining_time_data_;
122-
rm_msgs::SupplyProjectileAction supply_projectile_action_data_;
123-
rm_msgs::IcraBuffDebuffZoneStatus icra_buff_debuff_zone_status_data_;
124-
12593
serial::Serial serial_;
94+
95+
int client_id_ = 0; // recipient's id
96+
int robot_id_ = 0; // recent robot's id
12697
std::string robot_color_;
12798
bool referee_data_is_online_ = false;
128-
int client_id_ = 0; // recipient's id
129-
int robot_id_ = 0; // recent robot's id
13099

131100
void initSerial()
132101
{

rm_referee/include/rm_referee/common/ui.h

Lines changed: 0 additions & 85 deletions
This file was deleted.

rm_referee/include/rm_referee/referee.h

Lines changed: 28 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -40,22 +40,22 @@
4040
#include <ros/ros.h>
4141

4242
#include "rm_referee/common/data.h"
43-
#include "rm_referee/referee/referee_base.h"
43+
#include "rm_referee/referee_base.h"
4444

4545
namespace rm_referee
4646
{
4747
class SuperCapacitor
4848
{
4949
public:
50-
explicit SuperCapacitor(rm_referee::CapacityData& data) : last_get_data_(ros::Time::now()), data_(data){};
50+
explicit SuperCapacitor() : last_get_data_time_(ros::Time::now()){};
5151
void read(const std::vector<uint8_t>& rx_buffer);
52-
ros::Time last_get_data_;
52+
ros::Time last_get_data_time_;
53+
rm_referee::CapacityData capacity_data_;
5354

5455
private:
5556
void dtpReceivedCallBack(unsigned char receive_byte);
5657
void receiveCallBack(unsigned char package_id, const unsigned char* data);
5758
static float int16ToFloat(unsigned short data0);
58-
rm_referee::CapacityData& data_;
5959
unsigned char receive_buffer_[1024] = { 0 };
6060
unsigned char ping_pong_buffer_[1024] = { 0 };
6161
unsigned int receive_buf_counter_ = 0;
@@ -64,54 +64,50 @@ class SuperCapacitor
6464
class Referee
6565
{
6666
public:
67-
Referee() : super_capacitor_(base_.capacity_data_ref_), last_get_(ros::Time::now())
67+
Referee(ros::NodeHandle& nh) : referee_ui_(nh, base_), last_get_data_time_(ros::Time::now())
6868
{
69-
base_.robot_hurt_data_.hurt_type = 0x09;
7069
// pub
71-
ros::NodeHandle root_nh;
72-
super_capacitor_pub_ = root_nh.advertise<rm_msgs::SuperCapacitor>("/super_capacitor", 1);
73-
game_robot_status_pub_ = root_nh.advertise<rm_msgs::GameRobotStatus>("/game_robot_status", 1);
74-
game_status_pub_ = root_nh.advertise<rm_msgs::GameStatus>("/game_status", 1);
75-
capacity_data_pub_ = root_nh.advertise<rm_msgs::CapacityData>("/capacity_data", 1);
76-
power_heat_data_pub_ = root_nh.advertise<rm_msgs::PowerHeatData>("/power_heat_data", 1);
77-
game_robot_hp_pub_ = root_nh.advertise<rm_msgs::GameRobotHp>("/game_robot_hp", 1);
78-
event_data_pub_ = root_nh.advertise<rm_msgs::EventData>("/event_data", 1);
79-
dart_status_pub_ = root_nh.advertise<rm_msgs::DartStatus>("/dart_status_data", 1);
70+
super_capacitor_pub_ = nh.advertise<rm_msgs::SuperCapacitor>("super_capacitor", 1);
71+
game_robot_status_pub_ = nh.advertise<rm_msgs::GameRobotStatus>("game_robot_status", 1);
72+
game_status_pub_ = nh.advertise<rm_msgs::GameStatus>("game_status", 1);
73+
capacity_data_pub_ = nh.advertise<rm_msgs::CapacityData>("capacity_data", 1);
74+
power_heat_data_pub_ = nh.advertise<rm_msgs::PowerHeatData>("power_heat_data", 1);
75+
game_robot_hp_pub_ = nh.advertise<rm_msgs::GameRobotHp>("game_robot_hp", 1);
76+
event_data_pub_ = nh.advertise<rm_msgs::EventData>("event_data", 1);
77+
dart_status_pub_ = nh.advertise<rm_msgs::DartStatus>("dart_status_data", 1);
8078
icra_buff_debuff_zone_status_pub_ =
81-
root_nh.advertise<rm_msgs::IcraBuffDebuffZoneStatus>("/icra_buff_debuff_zone_status_data", 1);
82-
supply_projectile_action_pub_ =
83-
root_nh.advertise<rm_msgs::SupplyProjectileAction>("/supply_projectile_action_data", 1);
84-
dart_remaining_time_pub_ = root_nh.advertise<rm_msgs::DartRemainingTime>("/dart_remaining_time_data", 1);
85-
robot_hurt_pub_ = root_nh.advertise<rm_msgs::RobotHurt>("/robot_hurt_data", 1);
86-
shoot_data_pub_ = root_nh.advertise<rm_msgs::ShootData>("/shoot_data", 1);
87-
bullet_remaining_pub_ = root_nh.advertise<rm_msgs::BulletRemaining>("/bullet_remaining_data", 1);
88-
rfid_status_pub_ = root_nh.advertise<rm_msgs::RfidStatus>("/rfid_status_data", 1);
89-
dart_client_cmd_pub_ = root_nh.advertise<rm_msgs::DartClientCmd>("/dart_client_cmd_data", 1);
79+
nh.advertise<rm_msgs::IcraBuffDebuffZoneStatus>("icra_buff_debuff_zone_status_data", 1);
80+
supply_projectile_action_pub_ = nh.advertise<rm_msgs::SupplyProjectileAction>("supply_projectile_action_data", 1);
81+
dart_remaining_time_pub_ = nh.advertise<rm_msgs::DartRemainingTime>("dart_remaining_time_data", 1);
82+
robot_hurt_pub_ = nh.advertise<rm_msgs::RobotHurt>("robot_hurt_data", 1);
83+
shoot_data_pub_ = nh.advertise<rm_msgs::ShootData>("shoot_data", 1);
84+
bullet_remaining_pub_ = nh.advertise<rm_msgs::BulletRemaining>("bullet_remaining_data", 1);
85+
rfid_status_pub_ = nh.advertise<rm_msgs::RfidStatus>("rfid_status_data", 1);
86+
dart_client_cmd_pub_ = nh.advertise<rm_msgs::DartClientCmd>("dart_client_cmd_data", 1);
9087
// initSerial
9188
base_.initSerial();
9289
};
9390
void read();
9491
void checkUiAdd()
9592
{
96-
if (referee_ui_->base_.dbus_data_.s_r == rm_msgs::DbusData::UP)
93+
if (referee_ui_.send_ui_flag_)
9794
{
98-
if (referee_ui_->add_ui_flag_)
95+
if (referee_ui_.add_ui_flag_)
9996
{
100-
referee_ui_->addUi();
97+
referee_ui_.addUi();
10198
ROS_INFO("Add ui");
102-
referee_ui_->add_ui_flag_ = false;
99+
referee_ui_.add_ui_flag_ = false;
103100
}
104101
}
105102
else
106-
referee_ui_->add_ui_flag_ = true;
103+
referee_ui_.add_ui_flag_ = true;
107104
}
108105
void clearRxBuffer()
109106
{
110107
rx_buffer_.clear();
111108
rx_len_ = 0;
112109
}
113110

114-
ros::Publisher referee_pub_;
115111
ros::Publisher super_capacitor_pub_;
116112
ros::Publisher game_robot_status_pub_;
117113
ros::Publisher game_status_pub_;
@@ -131,7 +127,7 @@ class Referee
131127

132128
Base base_;
133129
std::vector<uint8_t> rx_buffer_;
134-
rm_referee::RefereeBase* referee_ui_;
130+
rm_referee::RefereeBase referee_ui_;
135131
int rx_len_;
136132

137133
private:
@@ -140,7 +136,7 @@ class Referee
140136
void publishCapacityData();
141137

142138
SuperCapacitor super_capacitor_;
143-
ros::Time last_get_;
139+
ros::Time last_get_data_time_;
144140
const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
145141
const int k_unpack_buffer_length_ = 256;
146142
uint8_t unpack_buffer_[256]{};

rm_referee/include/rm_referee/referee/engineer_referee.h

Lines changed: 0 additions & 32 deletions
This file was deleted.

rm_referee/include/rm_referee/referee/hero_referee.h

Lines changed: 0 additions & 23 deletions
This file was deleted.

rm_referee/include/rm_referee/referee/radar_referee.h

Lines changed: 0 additions & 34 deletions
This file was deleted.

rm_referee/include/rm_referee/referee/robot_referee.h

Lines changed: 0 additions & 33 deletions
This file was deleted.

0 commit comments

Comments
 (0)