Skip to content

Commit e5ca0df

Browse files
committed
add params
1 parent 1f1491b commit e5ca0df

2 files changed

Lines changed: 19 additions & 14 deletions

File tree

bt_nodes/configuration/src/configuration/init_receptionist.cpp

Lines changed: 16 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -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(

bt_nodes/hri/src/hri/dialog/get_guest_info.cpp

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -83,17 +83,12 @@ void GetGuestInfo::on_result()
8383
setStatus(BT::NodeStatus::FAILURE);
8484
}
8585

86-
std::regex guest_regex("\"guest\"\\s*:\\s*\"([^\"]*)\"");
8786
std::regex name_regex("\"name\"\\s*:\\s*\"([^\"]*)\"");
8887
std::regex drink_regex("\"drink\"\\s*:\\s*\"([^\"]*)\"");
8988
std::regex desc_regex("\"desc\"\\s*:\\s*\"([^\"]*)\"");
9089

9190
std::smatch match;
9291

93-
if (std::regex_search(result_.json, match, guest_regex)) {
94-
guest_id_ = match[1];
95-
}
96-
9792
if (std::regex_search(result_.json, match, name_regex)) {
9893
guest_name_ = match[1];
9994
}
@@ -117,9 +112,10 @@ void GetGuestInfo::on_result()
117112
std_msgs::msg::String fact_msg;
118113

119114
// Delete attending fact
120-
if (!guest_id_.empty()) {
121-
fact_msg.data = "robot1 oro:attends " + guest_id_;
115+
if (!guest_attending_id_.empty()) {
116+
fact_msg.data = "robot1 oro:attends " + guest_attending_id_;
122117
kb_publisher_->publish(fact_msg);
118+
RCLCPP_INFO(node_->get_logger(), "[GetGuestInfo] Removing fact: robot1 oro:attends %s", guest_id_.c_str());
123119
}
124120

125121
setStatus(BT::NodeStatus::SUCCESS);

0 commit comments

Comments
 (0)