From f722a8d3f5ecb43570c53e73649668953bd2f832 Mon Sep 17 00:00:00 2001 From: Bill Finger Date: Fri, 22 Dec 2023 22:40:42 +0300 Subject: [PATCH] fix merge mistakes --- rbs_bt_executor/src/PoseEstimation.cpp | 25 ++++++++++--------------- 1 file changed, 10 insertions(+), 15 deletions(-) diff --git a/rbs_bt_executor/src/PoseEstimation.cpp b/rbs_bt_executor/src/PoseEstimation.cpp index b68c457..0a6b183 100644 --- a/rbs_bt_executor/src/PoseEstimation.cpp +++ b/rbs_bt_executor/src/PoseEstimation.cpp @@ -23,10 +23,12 @@ public: while (!_set_params_client->wait_for_service(1s)) { if (!rclcpp::ok()) { - RCLCPP_ERROR(_node->get_logger(), "Interrupted while waiting for the service. Exiting."); + RCLCPP_ERROR(_node->get_logger(), + "Interrupted while waiting for the service. Exiting."); break; } - RCLCPP_WARN(_node->get_logger(), "service not available, waiting again..."); + RCLCPP_WARN(_node->get_logger(), + "service not available, waiting again..."); } _model_name = getInput("ObjectName").value(); @@ -80,7 +82,7 @@ private: } else if (req_type == "cleanup") { transition_id_ = lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP; } - //calibrate + // calibrate translation.set__id(transition_id_); return translation; } @@ -95,18 +97,11 @@ private: } void set_str_param() { - RCLCPP_INFO_STREAM(_node->get_logger(), "Set string parameter: <" + _model_name + ">"); + RCLCPP_INFO_STREAM(_node->get_logger(), + "Set string parameter: <" + _model_name + ">"); - std::vector _parameters{rclcpp::Parameter("mesh_path", _model_name)}; - _set_params_client->set_parameters(_parameters); - } - - void set_mesh_param() { - auto _package_name = ament_index_cpp::get_package_share_directory("rbs_perception"); - _model_path = build_model_path(_model_name, _package_name); - RCLCPP_INFO_STREAM(_node->get_logger(), _model_path); - - std::vector _parameters{rclcpp::Parameter("mesh_path", _model_name)}; + std::vector _parameters{ + rclcpp::Parameter("mesh_path", _model_name)}; _set_params_client->set_parameters(_parameters); } @@ -117,7 +112,7 @@ private: RCLCPP_INFO_STREAM(_node->get_logger(), _model_path); std::vector _parameters{ - rclcpp::Parameter("mesh_path", _model_path)}; + rclcpp::Parameter("mesh_path", _model_name)}; _set_params_client->set_parameters(_parameters); } };