@@ -22,14 +22,23 @@ InitReceptionist::InitReceptionist(
2222: BT::ActionNodeBase(xml_tag_name, conf)
2323{
2424 config ().blackboard ->get (" node" , node_);
25-
26- node_->declare_parameter (" cam_frame" , " head_front_camera_color_optical_frame" );
27- node_->declare_parameter (" manipulation_frame" , " base_link" );
25+ if (!node_->has_parameter (" cam_frame" )) {
26+ node_->declare_parameter (" cam_frame" , " head_front_camera_color_optical_frame" );
27+ }
28+ if (!node_->has_parameter (" manipulation_frame" )) {
29+ node_->declare_parameter (" manipulation_frame" , " base_link" );
30+ }
2831 // node_->declare_parameter("party_wp", std::vector<double>{0.0, 0.0, 0.0});
2932 // node_->declare_parameter("entrance_wp", std::vector<double>{0.0, 0.0, 0.0});
30- node_->declare_parameter (" host_name" , " John Doe" );
31- node_->declare_parameter (" host_drink" , " beer" );
32- node_->declare_parameter (" waypoints_names" , std::vector<std::string>{});
33+ if (!node_->has_parameter (" host_name" )) {
34+ node_->declare_parameter (" host_name" , " John Doe" );
35+ }
36+ if (!node_->has_parameter (" host_drink" )) {
37+ node_->declare_parameter (" host_drink" , " beer" );
38+ }
39+ if (!node_->has_parameter (" waypoints_names" )) {
40+ node_->declare_parameter (" waypoints_names" , std::vector<std::string>{});
41+ }
3342
3443 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock ());
3544 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
@@ -58,7 +67,7 @@ BT::NodeStatus InitReceptionist::tick()
5867 std::to_string (wp_names_.size ()).c_str ());
5968
6069 for (auto wp : wp_names_) {
61- node_->declare_parameter (" waypoints." + wp, std::vector<double >());
70+ // node_->declare_parameter("waypoints." + wp, std::vector<double>());
6271 std::vector<double > wp_pos;
6372 node_->get_parameter (" waypoints." + wp, wp_pos);
6473 RCLCPP_INFO (
0 commit comments