diff --git a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp index 52882996d3c..5a9bf0b3759 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp @@ -95,7 +95,7 @@ class DockingServer : public nav2_util::LifecycleNode /** * @brief Perform a pure rotation to dock orientation. */ -void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose) + void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose); /** @@ -255,7 +255,7 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po // depending on the initial robot orientation and k_phi, k_delta. bool initial_rotation_; // Enable aproaching a docking station only with initial detection without updates - bool backward_blind; + bool backward_blind_; // This is a class member so it can be accessed in publish feedback rclcpp::Time action_start_time_; diff --git a/nav2_docking/opennav_docking/src/docking_server.cpp b/nav2_docking/opennav_docking/src/docking_server.cpp index 2f1f9f1b0ed..fc5836f54a4 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -64,8 +64,7 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("initial_rotation", initial_rotation_); get_parameter("backward_blind", backward_blind_); if(backward_blind_ && !dock_backwards_){ - RCLCPP_ERROR(get_logger(), "Docking server configuration is invalid. - backward_blind is enabled when dock_backwards is disabled."); + RCLCPP_ERROR(get_logger(), "backward_blind is enabled when dock_backwards is disabled."); return nav2_util::CallbackReturn::FAILURE; } else{ // If you have backward_blind and dock_backward then