Skip to content

Commit

Permalink
Merge pull request #80 from ljq-lv/new_ui_test
Browse files Browse the repository at this point in the history
Improve the Ui to reduce data transport
  • Loading branch information
ye-luo-xi-tui authored Nov 24, 2022
2 parents 3989abc + 54e4b06 commit 79e6a96
Show file tree
Hide file tree
Showing 30 changed files with 1,279 additions and 1,390 deletions.
2 changes: 1 addition & 1 deletion rm_referee/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ include_directories(
)

## Declare cpp executables
FILE(GLOB ALL_SOURCES "src/*.cpp" "src/common/*.cpp" "src/referee/*.cpp")
FILE(GLOB ALL_SOURCES "src/*.cpp" "src/common/*.cpp" "src/ui/*.cpp")
add_executable(${PROJECT_NAME} ${ALL_SOURCES})

## Add dependencies to exported targets, like ROS msgs or srvs
Expand Down
37 changes: 3 additions & 34 deletions rm_referee/include/rm_referee/common/data.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,43 +90,12 @@ struct CapacityData
class Base
{
public:
// sub data
uint8_t radar_data_;
sensor_msgs::JointState joint_state_;
geometry_msgs::Twist vel2d_cmd_data_;
rm_msgs::DbusData dbus_data_;
rm_msgs::StateCmd card_cmd_data_;
rm_msgs::ShootCmd shoot_cmd_data_;
rm_msgs::GimbalCmd gimbal_cmd_data_;
rm_msgs::ChassisCmd chassis_cmd_data_;
rm_msgs::ActuatorState actuator_state_;
rm_msgs::EngineerCmd engineer_cmd_data_;
rm_msgs::ManualToReferee manual_to_referee_data_;

// pub data
rm_msgs::EventData event_data_;
rm_msgs::ShootData shoot_data_;
rm_msgs::RobotHurt robot_hurt_data_;
rm_msgs::CapacityData capacity_data_;
rm_msgs::RfidStatus rfid_status_data_;
rm_msgs::DartStatus dart_status_data_;
rm_msgs::GameStatus game_status_data_;
rm_msgs::PowerHeatData power_heat_data_;
rm_msgs::GameRobotHp game_robot_hp_data_;
rm_referee::CapacityData capacity_data_ref_;
rm_msgs::DartClientCmd dart_client_cmd_data_;
rm_msgs::SuperCapacitor super_capacitor_data_;
rm_msgs::BulletRemaining bullet_remaining_data_;
rm_msgs::GameRobotStatus game_robot_status_data_;
rm_msgs::DartRemainingTime dart_remaining_time_data_;
rm_msgs::SupplyProjectileAction supply_projectile_action_data_;
rm_msgs::IcraBuffDebuffZoneStatus icra_buff_debuff_zone_status_data_;

serial::Serial serial_;

int client_id_ = 0; // recipient's id
int robot_id_ = 0; // recent robot's id
std::string robot_color_;
bool referee_data_is_online_ = false;
int client_id_ = 0; // recipient's id
int robot_id_ = 0; // recent robot's id

void initSerial()
{
Expand Down
85 changes: 0 additions & 85 deletions rm_referee/include/rm_referee/common/ui.h

This file was deleted.

60 changes: 28 additions & 32 deletions rm_referee/include/rm_referee/referee.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,22 +40,22 @@
#include <ros/ros.h>

#include "rm_referee/common/data.h"
#include "rm_referee/referee/referee_base.h"
#include "rm_referee/referee_base.h"

namespace rm_referee
{
class SuperCapacitor
{
public:
explicit SuperCapacitor(rm_referee::CapacityData& data) : last_get_data_(ros::Time::now()), data_(data){};
explicit SuperCapacitor() : last_get_data_time_(ros::Time::now()){};
void read(const std::vector<uint8_t>& rx_buffer);
ros::Time last_get_data_;
ros::Time last_get_data_time_;
rm_referee::CapacityData capacity_data_;

private:
void dtpReceivedCallBack(unsigned char receive_byte);
void receiveCallBack(unsigned char package_id, const unsigned char* data);
static float int16ToFloat(unsigned short data0);
rm_referee::CapacityData& data_;
unsigned char receive_buffer_[1024] = { 0 };
unsigned char ping_pong_buffer_[1024] = { 0 };
unsigned int receive_buf_counter_ = 0;
Expand All @@ -64,54 +64,50 @@ class SuperCapacitor
class Referee
{
public:
Referee() : super_capacitor_(base_.capacity_data_ref_), last_get_(ros::Time::now())
Referee(ros::NodeHandle& nh) : referee_ui_(nh, base_), last_get_data_time_(ros::Time::now())
{
base_.robot_hurt_data_.hurt_type = 0x09;
// pub
ros::NodeHandle root_nh;
super_capacitor_pub_ = root_nh.advertise<rm_msgs::SuperCapacitor>("/super_capacitor", 1);
game_robot_status_pub_ = root_nh.advertise<rm_msgs::GameRobotStatus>("/game_robot_status", 1);
game_status_pub_ = root_nh.advertise<rm_msgs::GameStatus>("/game_status", 1);
capacity_data_pub_ = root_nh.advertise<rm_msgs::CapacityData>("/capacity_data", 1);
power_heat_data_pub_ = root_nh.advertise<rm_msgs::PowerHeatData>("/power_heat_data", 1);
game_robot_hp_pub_ = root_nh.advertise<rm_msgs::GameRobotHp>("/game_robot_hp", 1);
event_data_pub_ = root_nh.advertise<rm_msgs::EventData>("/event_data", 1);
dart_status_pub_ = root_nh.advertise<rm_msgs::DartStatus>("/dart_status_data", 1);
super_capacitor_pub_ = nh.advertise<rm_msgs::SuperCapacitor>("super_capacitor", 1);
game_robot_status_pub_ = nh.advertise<rm_msgs::GameRobotStatus>("game_robot_status", 1);
game_status_pub_ = nh.advertise<rm_msgs::GameStatus>("game_status", 1);
capacity_data_pub_ = nh.advertise<rm_msgs::CapacityData>("capacity_data", 1);
power_heat_data_pub_ = nh.advertise<rm_msgs::PowerHeatData>("power_heat_data", 1);
game_robot_hp_pub_ = nh.advertise<rm_msgs::GameRobotHp>("game_robot_hp", 1);
event_data_pub_ = nh.advertise<rm_msgs::EventData>("event_data", 1);
dart_status_pub_ = nh.advertise<rm_msgs::DartStatus>("dart_status_data", 1);
icra_buff_debuff_zone_status_pub_ =
root_nh.advertise<rm_msgs::IcraBuffDebuffZoneStatus>("/icra_buff_debuff_zone_status_data", 1);
supply_projectile_action_pub_ =
root_nh.advertise<rm_msgs::SupplyProjectileAction>("/supply_projectile_action_data", 1);
dart_remaining_time_pub_ = root_nh.advertise<rm_msgs::DartRemainingTime>("/dart_remaining_time_data", 1);
robot_hurt_pub_ = root_nh.advertise<rm_msgs::RobotHurt>("/robot_hurt_data", 1);
shoot_data_pub_ = root_nh.advertise<rm_msgs::ShootData>("/shoot_data", 1);
bullet_remaining_pub_ = root_nh.advertise<rm_msgs::BulletRemaining>("/bullet_remaining_data", 1);
rfid_status_pub_ = root_nh.advertise<rm_msgs::RfidStatus>("/rfid_status_data", 1);
dart_client_cmd_pub_ = root_nh.advertise<rm_msgs::DartClientCmd>("/dart_client_cmd_data", 1);
nh.advertise<rm_msgs::IcraBuffDebuffZoneStatus>("icra_buff_debuff_zone_status_data", 1);
supply_projectile_action_pub_ = nh.advertise<rm_msgs::SupplyProjectileAction>("supply_projectile_action_data", 1);
dart_remaining_time_pub_ = nh.advertise<rm_msgs::DartRemainingTime>("dart_remaining_time_data", 1);
robot_hurt_pub_ = nh.advertise<rm_msgs::RobotHurt>("robot_hurt_data", 1);
shoot_data_pub_ = nh.advertise<rm_msgs::ShootData>("shoot_data", 1);
bullet_remaining_pub_ = nh.advertise<rm_msgs::BulletRemaining>("bullet_remaining_data", 1);
rfid_status_pub_ = nh.advertise<rm_msgs::RfidStatus>("rfid_status_data", 1);
dart_client_cmd_pub_ = nh.advertise<rm_msgs::DartClientCmd>("dart_client_cmd_data", 1);
// initSerial
base_.initSerial();
};
void read();
void checkUiAdd()
{
if (referee_ui_->base_.dbus_data_.s_r == rm_msgs::DbusData::UP)
if (referee_ui_.send_ui_flag_)
{
if (referee_ui_->add_ui_flag_)
if (referee_ui_.add_ui_flag_)
{
referee_ui_->addUi();
referee_ui_.addUi();
ROS_INFO("Add ui");
referee_ui_->add_ui_flag_ = false;
referee_ui_.add_ui_flag_ = false;
}
}
else
referee_ui_->add_ui_flag_ = true;
referee_ui_.add_ui_flag_ = true;
}
void clearRxBuffer()
{
rx_buffer_.clear();
rx_len_ = 0;
}

ros::Publisher referee_pub_;
ros::Publisher super_capacitor_pub_;
ros::Publisher game_robot_status_pub_;
ros::Publisher game_status_pub_;
Expand All @@ -131,7 +127,7 @@ class Referee

Base base_;
std::vector<uint8_t> rx_buffer_;
rm_referee::RefereeBase* referee_ui_;
rm_referee::RefereeBase referee_ui_;
int rx_len_;

private:
Expand All @@ -140,7 +136,7 @@ class Referee
void publishCapacityData();

SuperCapacitor super_capacitor_;
ros::Time last_get_;
ros::Time last_get_data_time_;
const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
const int k_unpack_buffer_length_ = 256;
uint8_t unpack_buffer_[256]{};
Expand Down
32 changes: 0 additions & 32 deletions rm_referee/include/rm_referee/referee/engineer_referee.h

This file was deleted.

23 changes: 0 additions & 23 deletions rm_referee/include/rm_referee/referee/hero_referee.h

This file was deleted.

34 changes: 0 additions & 34 deletions rm_referee/include/rm_referee/referee/radar_referee.h

This file was deleted.

33 changes: 0 additions & 33 deletions rm_referee/include/rm_referee/referee/robot_referee.h

This file was deleted.

Loading

0 comments on commit 79e6a96

Please sign in to comment.