Skip to content
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
4 changes: 4 additions & 0 deletions rm_common/include/rm_common/decision/command_sender.h
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,10 @@ class ChassisCommandSender : public TimeStampCommandSenderBase<rm_msgs::ChassisC
{
msg_.follow_vel_des = follow_vel_des;
}
void setWirelessState(bool state)
{
msg_.wireless_state = state;
}
void sendChassisCommand(const ros::Time& time, bool is_gyro)
{
power_limit_->setLimitPower(msg_, is_gyro);
Expand Down
1 change: 1 addition & 0 deletions rm_msgs/msg/ChassisCmd.msg
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,5 @@ float64 power_limit
float64 follow_vel_des
string follow_source_frame
string command_source_frame
bool wireless_state
time stamp
1 change: 1 addition & 0 deletions rm_referee/include/rm_referee/referee_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,7 @@ class RefereeBase
CoverFlashUi* cover_flash_ui_{};
SpinFlashUi* spin_flash_ui_{};
DeployFlashUi* deploy_flash_ui_{};
WirelessFlashUi* wireless_flash_ui_{};
HeroHitFlashUi* hero_hit_flash_ui_{};
ExceedBulletSpeedFlashUi* exceed_bullet_speed_flash_ui_{};
CustomizeDisplayFlashUi* customize_display_flash_ui_{};
Expand Down
13 changes: 13 additions & 0 deletions rm_referee/include/rm_referee/ui/flash_ui.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,19 @@ class DeployFlashUi : public FlashUi
double angular_z_{ 0. };
};

class WirelessFlashUi : public FlashUi
{
public:
explicit WirelessFlashUi(XmlRpc::XmlRpcValue& rpc_value, Base& base, std::deque<Graph>* graph_queue,
std::deque<Graph>* character_queue)
: FlashUi(rpc_value, base, "wireless", graph_queue, character_queue){};
void updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr& data, const ros::Time& last_get_data_time);

private:
void display(const ros::Time& time) override;
bool wireless_state_;
};

class HeroHitFlashUi : public FlashGroupUi
{
public:
Expand Down
4 changes: 4 additions & 0 deletions rm_referee/src/referee_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,8 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
spin_flash_ui_ = new SpinFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "deploy")
deploy_flash_ui_ = new DeployFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "wireless")
wireless_flash_ui_ = new WirelessFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "hero_hit")
hero_hit_flash_ui_ = new HeroHitFlashUi(rpc_value[i], base_, &graph_queue_, &character_queue_);
if (rpc_value[i]["name"] == "exceed_bullet_speed")
Expand Down Expand Up @@ -457,6 +459,8 @@ void RefereeBase::chassisCmdDataCallback(const rm_msgs::ChassisCmd::ConstPtr& da
spin_flash_ui_->updateChassisCmdData(data, ros::Time::now());
if (deploy_flash_ui_ && !is_adding_)
deploy_flash_ui_->updateChassisCmdData(data, ros::Time::now());
if (wireless_flash_ui_ && !is_adding_)
wireless_flash_ui_->updateChassisCmdData(data, ros::Time::now());
if (rotation_time_change_ui_ && !is_adding_)
rotation_time_change_ui_->updateChassisCmdData(data);
}
Expand Down
14 changes: 14 additions & 0 deletions rm_referee/src/ui/flash_ui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,20 @@ void DeployFlashUi::updateChassisVelData(const geometry_msgs::Twist::ConstPtr& d
angular_z_ = data->angular.z;
}

void WirelessFlashUi::display(const ros::Time& time)
{
if (!(wireless_state_))
graph_->setOperation(rm_referee::GraphOperation::DELETE);
FlashUi::updateFlashUiForQueue(time, (wireless_state_), false);
}

void WirelessFlashUi::updateChassisCmdData(const rm_msgs::ChassisCmd::ConstPtr& data,
const ros::Time& last_get_data_time)
{
wireless_state_ = data->wireless_state;
display(last_get_data_time);
}

void HeroHitFlashUi::updateHittingConfig(const rm_msgs::GameRobotHp& msg)
{
if (base_.robot_id_ > 100)
Expand Down
Loading