@@ -50,6 +50,10 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
5050 " /sentry_target_to_referee" , 1 , &RefereeBase::sentryAttackingTargetCallback, this );
5151 RefereeBase::radar_to_referee_sub_ =
5252 nh.subscribe <rm_msgs::RadarToSentry>(" /radar_to_referee" , 1 , &RefereeBase::radarToRefereeCallBack, this );
53+ RefereeBase::customize_display_cmd_sub_ =
54+ nh.subscribe <std_msgs::UInt32>(" /customize_display_ui" , 1 , &RefereeBase::customizeDisplayCmdCallBack, this );
55+ RefereeBase::visualize_state_data_sub_ =
56+ nh.subscribe <rm_msgs::VisualizeStateData>(" /visualize_state" , 1 , &RefereeBase::visualizeStateDataCallBack, this );
5357
5458 XmlRpc::XmlRpcValue rpc_value;
5559 send_ui_queue_delay_ = getParam (nh, " send_ui_queue_delay" , 0.15 );
@@ -88,6 +92,9 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
8892 if (rpc_value[i][" name" ] == " stone" )
8993 stone_num_trigger_change_ui_ =
9094 new StringTriggerChangeUi (rpc_value[i], base_, " stone_num" , &graph_queue_, &character_queue_);
95+ if (rpc_value[i][" name" ] == " visualize_state" )
96+ visualize_state_trigger_change_ui_ =
97+ new VisualizeStateTriggerChangeUi (rpc_value[i], base_, " visualize_state" , &graph_queue_, &character_queue_);
9198 }
9299
93100 ui_nh.getParam (" time_change" , rpc_value);
@@ -148,17 +155,16 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
148155 if (rpc_value[i][" name" ] == " exceed_bullet_speed" )
149156 exceed_bullet_speed_flash_ui_ =
150157 new ExceedBulletSpeedFlashUi (rpc_value[i], base_, &graph_queue_, &character_queue_);
151- if (rpc_value[i][" name" ] == " engineer_action" )
152- engineer_action_flash_ui_ = new EngineerActionFlashUi (rpc_value[i], base_, &graph_queue_, &character_queue_);
158+ if (rpc_value[i][" name" ] == " customize_display" )
159+ customize_display_flash_ui_ =
160+ new CustomizeDisplayFlashUi (rpc_value[i], base_, &graph_queue_, &character_queue_);
153161 }
154162 }
155163 if (nh.hasParam (" interactive_data" ))
156164 {
157165 nh.getParam (" interactive_data" , rpc_value);
158166 for (int i = 0 ; i < rpc_value.size (); i++)
159167 {
160- // if (rpc_value[i]["name"] == "enemy_hero_state")
161- // enemy_hero_state_sender_ = new CustomInfoSender(rpc_value[i], base_);
162168 if (rpc_value[i][" name" ] == " custom_info" )
163169 custom_info_sender = new CustomInfoSender (rpc_value[i], base_);
164170 if (rpc_value[i][" name" ] == " bullet_num_share" )
@@ -247,6 +253,8 @@ void RefereeBase::addUi()
247253 target_distance_time_change_ui_->addForQueue ();
248254 if (friend_bullets_time_change_group_ui_)
249255 friend_bullets_time_change_group_ui_->addForQueue ();
256+ if (visualize_state_trigger_change_ui_)
257+ visualize_state_trigger_change_ui_->addForQueue ();
250258 add_ui_times_++;
251259}
252260
@@ -453,8 +461,8 @@ void RefereeBase::engineerUiDataCallback(const rm_msgs::EngineerUi::ConstPtr& da
453461 stone_num_trigger_change_ui_->updateStringUiData (std::to_string (data->stone_num ));
454462 if (servo_mode_trigger_change_ui_ && !is_adding_)
455463 servo_mode_trigger_change_ui_->updateStringUiData (data->control_mode );
456- if (engineer_action_flash_ui_ && !is_adding_)
457- engineer_action_flash_ui_-> updateEngineerUiCmdData (data, ros::Time::now () );
464+ if (customize_display_flash_ui_ && !is_adding_)
465+ customize_display_flash_ui_-> updateCmdData (data-> symbol );
458466}
459467void RefereeBase::manualDataCallBack (const rm_msgs::ManualToReferee::ConstPtr& data)
460468{
@@ -585,4 +593,21 @@ void RefereeBase::radarToRefereeCallBack(const rm_msgs::RadarToSentryConstPtr& d
585593 radar_to_sentry_->updateRadarToSentryData (data);
586594}
587595
596+ void RefereeBase::customizeDisplayCmdCallBack (const std_msgs::UInt32ConstPtr& data)
597+ {
598+ if (customize_display_flash_ui_ && !is_adding_)
599+ customize_display_flash_ui_->updateCmdData (data->data );
600+ }
601+
602+ void RefereeBase::visualizeStateDataCallBack (const rm_msgs::VisualizeStateDataConstPtr& data)
603+ {
604+ if (visualize_state_trigger_change_ui_ && !is_adding_)
605+ {
606+ std::vector<bool > state;
607+ for (auto state_data : data->state )
608+ state.push_back (state_data);
609+ visualize_state_trigger_change_ui_->updateUiColor (state);
610+ }
611+ }
612+
588613} // namespace rm_referee
0 commit comments