From 79a46de628a34a74caa619a8a34f7752b9e1152b Mon Sep 17 00:00:00 2001 From: Harsh Deshpande Date: Mon, 27 Mar 2023 17:20:13 +0200 Subject: [PATCH] pass logger to GoalHandler Signed-off-by: Harsh Deshpande --- include/ros1_bridge/action_factory.hpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/include/ros1_bridge/action_factory.hpp b/include/ros1_bridge/action_factory.hpp index 437b0bd8..88785b25 100644 --- a/include/ros1_bridge/action_factory.hpp +++ b/include/ros1_bridge/action_factory.hpp @@ -102,7 +102,7 @@ class ActionFactory_1_2 : public ActionFactoryInterface // create a new handler for the goal std::shared_ptr handler; - handler = std::make_shared(gh1, client_); + handler = std::make_shared(gh1, client_, ros2_node_->get_logger()); std::lock_guard lock(mutex_); goals_.insert(std::make_pair(goal_id, handler)); @@ -138,7 +138,7 @@ class ActionFactory_1_2 : public ActionFactoryInterface translate_goal_1_to_2(*gh1_.getGoal(), goal2); if (!client_->wait_for_action_server(std::chrono::seconds(1))) { - RCLCPP_INFO(ros2_node_->get_logger(), "Action server not available after waiting"); + RCLCPP_INFO(this->logger_, "Action server not available after waiting"); gh1_.setRejected(); return; } @@ -190,13 +190,14 @@ class ActionFactory_1_2 : public ActionFactoryInterface } } - GoalHandler(ROS1GoalHandle & gh1, ROS2ClientSharedPtr & client) - : gh1_(gh1), gh2_(nullptr), client_(client), canceled_(false) {} + GoalHandler(ROS1GoalHandle & gh1, ROS2ClientSharedPtr & client, rclcpp::Logger logger) + : gh1_(gh1), gh2_(nullptr), client_(client), logger_(logger), canceled_(false) {} private: ROS1GoalHandle gh1_; ROS2ClientGoalHandle gh2_; ROS2ClientSharedPtr client_; + rclcpp::Logger logger_; bool canceled_; // cancel was called std::mutex mutex_gh_; };