@@ -54,7 +54,8 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
5454 nh.subscribe <std_msgs::UInt32>(" /customize_display_ui" , 1 , &RefereeBase::customizeDisplayCmdCallBack, this );
5555 RefereeBase::visualize_state_data_sub_ =
5656 nh.subscribe <rm_msgs::VisualizeStateData>(" /visualize_state" , 1 , &RefereeBase::visualizeStateDataCallBack, this );
57-
57+ RefereeBase::dis_base2target_data_sub_ =
58+ nh.subscribe <std_msgs::Float32>(" /dis_baselink2target" , 1 , &RefereeBase::disBase2TargetDataCallBack, this );
5859 XmlRpc::XmlRpcValue rpc_value;
5960 send_ui_queue_delay_ = getParam (nh, " send_ui_queue_delay" , 0.15 );
6061 add_ui_frequency_ = getParam (nh, " add_ui_frequency" , 5 );
@@ -113,6 +114,9 @@ RefereeBase::RefereeBase(ros::NodeHandle& nh, Base& base) : base_(base), nh_(nh)
113114 if (rpc_value[i][" name" ] == " lane_line" )
114115 lane_line_time_change_ui_ =
115116 new LaneLineTimeChangeGroupUi (rpc_value[i], base_, &graph_queue_, &character_queue_);
117+ if (rpc_value[i][" name" ] == " distance" )
118+ distance_base_time_change_ui_ =
119+ new DistanceBaseTimeChangeUi (rpc_value[i], base_, &graph_queue_, &character_queue_);
116120 if (rpc_value[i][" name" ] == " pitch" )
117121 pitch_angle_time_change_ui_ = new PitchAngleTimeChangeUi (rpc_value[i], base_, &graph_queue_, &character_queue_);
118122 if (rpc_value[i][" name" ] == " image_transmission" )
@@ -235,6 +239,8 @@ void RefereeBase::addUi()
235239 lane_line_time_change_ui_->addForQueue ();
236240 if (balance_pitch_time_change_group_ui_)
237241 balance_pitch_time_change_group_ui_->addForQueue ();
242+ if (distance_base_time_change_ui_)
243+ distance_base_time_change_ui_->addForQueue ();
238244 if (pitch_angle_time_change_ui_)
239245 pitch_angle_time_change_ui_->addForQueue ();
240246 if (image_transmission_angle_time_change_ui_)
@@ -635,4 +641,10 @@ void RefereeBase::visualizeStateDataCallBack(const rm_msgs::VisualizeStateDataCo
635641 }
636642}
637643
644+ void RefereeBase::disBase2TargetDataCallBack (const std_msgs::Float32ConstPtr& data)
645+ {
646+ if (distance_base_time_change_ui_ && !is_adding_)
647+ distance_base_time_change_ui_->updateDistanceBaseData (data, ros::Time::now ());
648+ }
649+
638650} // namespace rm_referee
0 commit comments