diff --git a/example_14/hardware/rrbot_actuator_without_feedback.cpp b/example_14/hardware/rrbot_actuator_without_feedback.cpp index a67c3d5e..e074a353 100644 --- a/example_14/hardware/rrbot_actuator_without_feedback.cpp +++ b/example_14/hardware/rrbot_actuator_without_feedback.cpp @@ -73,8 +73,6 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init( } // BEGIN: This part here is for exemplary purposes - Please do not copy to your production code - RCLCPP_INFO(get_logger(), "Configuring ...please wait..."); - // Initialize objects for fake mechanical connection sock_ = socket(AF_INET, SOCK_STREAM, 0); if (sock_ < 0) @@ -135,6 +133,8 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init( hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_configure( const rclcpp_lifecycle::State & /*previous_state*/) { + RCLCPP_INFO(get_logger(), "Configuring ...please wait..."); + // reset values always when configuring hardware for (const auto & [name, descr] : joint_command_interfaces_) { diff --git a/example_14/hardware/rrbot_sensor_for_position_feedback.cpp b/example_14/hardware/rrbot_sensor_for_position_feedback.cpp index fb2c0547..8e1ba59a 100644 --- a/example_14/hardware/rrbot_sensor_for_position_feedback.cpp +++ b/example_14/hardware/rrbot_sensor_for_position_feedback.cpp @@ -170,6 +170,8 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init( hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_configure( const rclcpp_lifecycle::State & /*previous_state*/) { + RCLCPP_INFO(get_logger(), "Configuring ...please wait..."); + // set some default values for joints // reset values always when configuring hardware for (const auto & [name, descr] : sensor_state_interfaces_)