From d4c0ed5b10dcd0bfec5cfe558c906bfa809cbfa6 Mon Sep 17 00:00:00 2001 From: Vincenzo Di Pentima Date: Tue, 17 Dec 2024 16:53:57 +0000 Subject: [PATCH] Updated callback name and added comment for Command Intefaces --- .../include/ur_controllers/freedrive_mode_controller.hpp | 4 ++-- ur_controllers/src/freedrive_mode_controller.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp b/ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp index c3274595..04e90805 100644 --- a/ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp +++ b/ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp @@ -87,7 +87,7 @@ class FreedriveModeController : public controller_interface::ControllerInterface CallbackReturn on_init() override; private: - // Command interfaces + // Command interfaces: optional is used only to avoid adding reference initialization std::optional> async_success_command_interface_; std::optional> enable_command_interface_; std::optional> abort_command_interface_; @@ -96,7 +96,7 @@ class FreedriveModeController : public controller_interface::ControllerInterface rclcpp::TimerBase::SharedPtr freedrive_sub_timer_; ///< Timer to check for timeout on input mutable std::chrono::seconds timeout_interval_; - void readFreedriveModeCmd(const std_msgs::msg::Bool::SharedPtr msg); + void freedrive_cmd_callback(const std_msgs::msg::Bool::SharedPtr msg); std::shared_ptr freedrive_param_listener_; freedrive_mode_controller::Params freedrive_params_; diff --git a/ur_controllers/src/freedrive_mode_controller.cpp b/ur_controllers/src/freedrive_mode_controller.cpp index a3074e24..e1ae016e 100644 --- a/ur_controllers/src/freedrive_mode_controller.cpp +++ b/ur_controllers/src/freedrive_mode_controller.cpp @@ -87,7 +87,7 @@ ur_controllers::FreedriveModeController::on_configure(const rclcpp_lifecycle::St // Subscriber definition enable_freedrive_mode_sub_ = get_node()->create_subscription( "~/enable_freedrive_mode", 10, - std::bind(&FreedriveModeController::readFreedriveModeCmd, this, std::placeholders::_1)); + std::bind(&FreedriveModeController::freedrive_cmd_callback, this, std::placeholders::_1)); timer_started_ = false; @@ -230,7 +230,7 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat return controller_interface::return_type::OK; } -void FreedriveModeController::readFreedriveModeCmd(const std_msgs::msg::Bool::SharedPtr msg) +void FreedriveModeController::freedrive_cmd_callback(const std_msgs::msg::Bool::SharedPtr msg) { // Process the freedrive_mode command. if (get_node()->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {