diff --git a/example_14/bringup/config/rrbot_modular_actuators_without_feedback_sensors_for_position_feedback.yaml b/example_14/bringup/config/rrbot_modular_actuators_without_feedback_sensors_for_position_feedback.yaml index fdf375705..46c8a98dc 100644 --- a/example_14/bringup/config/rrbot_modular_actuators_without_feedback_sensors_for_position_feedback.yaml +++ b/example_14/bringup/config/rrbot_modular_actuators_without_feedback_sensors_for_position_feedback.yaml @@ -1,6 +1,6 @@ controller_manager: ros__parameters: - update_rate: 10 # Hz + update_rate: 100 # Hz joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster diff --git a/example_14/doc/userdoc.rst b/example_14/doc/userdoc.rst index 91e7742cb..5e1c2b836 100644 --- a/example_14/doc/userdoc.rst +++ b/example_14/doc/userdoc.rst @@ -128,6 +128,10 @@ Tutorial steps [ros2_control_node-1] Writing command: 5.00 [ros2_control_node-1] Sending data command: 5 [ros2_control_node-1] + [ros2_control_node-1] [INFO] [1728858168.775863217] [controller_manager.resource_manager.hardware_component.sensor.RRBotModularPositionSensorJoint2]: Reading... + [ros2_control_node-1] Got measured velocity 5.00 + [ros2_control_node-1] Got state 0.29 for joint 'joint2' + [ros2_control_node-1] [ros2_control_node-1] [INFO] [1728858168.776052116] [controller_manager.resource_manager.hardware_component.actuator.RRBotModularJoint2]: Writing... [ros2_control_node-1] Writing command: 5.00 [ros2_control_node-1] Sending data command: 5 @@ -136,10 +140,6 @@ Tutorial steps [ros2_control_node-1] Got measured velocity 5.00 [ros2_control_node-1] Got state 0.34 for joint 'joint1' [ros2_control_node-1] - [ros2_control_node-1] [INFO] [1728858169.775863217] [controller_manager.resource_manager.hardware_component.sensor.RRBotModularPositionSensorJoint2]: Reading... - [ros2_control_node-1] Got measured velocity 5.00 - [ros2_control_node-1] Got state 0.29 for joint 'joint2' - [ros2_control_node-1] Files used for this demos diff --git a/example_14/hardware/rrbot_actuator_without_feedback.cpp b/example_14/hardware/rrbot_actuator_without_feedback.cpp index 4608e8a43..b3a2e722a 100644 --- a/example_14/hardware/rrbot_actuator_without_feedback.cpp +++ b/example_14/hardware/rrbot_actuator_without_feedback.cpp @@ -219,7 +219,7 @@ hardware_interface::return_type ros2_control_demo_example_14::RRBotActuatorWitho std::ostringstream data; data << hw_joint_command_; ss << "Sending data command: " << data.str() << std::endl; - RCLCPP_INFO(get_logger(), ss.str().c_str()); + RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 500, ss.str().c_str()); // Simulate sending commands to the hardware send(sock_, data.str().c_str(), strlen(data.str().c_str()), 0); diff --git a/example_14/hardware/rrbot_sensor_for_position_feedback.cpp b/example_14/hardware/rrbot_sensor_for_position_feedback.cpp index 50a7393e2..5257cd950 100644 --- a/example_14/hardware/rrbot_sensor_for_position_feedback.cpp +++ b/example_14/hardware/rrbot_sensor_for_position_feedback.cpp @@ -266,7 +266,7 @@ hardware_interface::return_type RRBotSensorPositionFeedback::read( ss << "Got measured velocity " << measured_velocity << std::endl; ss << "Got state " << hw_joint_state_ << " for joint '" << info_.joints[0].name << "'" << std::endl; - RCLCPP_INFO(get_logger(), ss.str().c_str()); + RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 500, ss.str().c_str()); // END: This part here is for exemplary purposes - Please do not copy to your production code return hardware_interface::return_type::OK; diff --git a/example_6/bringup/config/rrbot_modular_actuators.yaml b/example_6/bringup/config/rrbot_modular_actuators.yaml index 0a658759c..5061aef17 100644 --- a/example_6/bringup/config/rrbot_modular_actuators.yaml +++ b/example_6/bringup/config/rrbot_modular_actuators.yaml @@ -1,6 +1,6 @@ controller_manager: ros__parameters: - update_rate: 10 # Hz + update_rate: 100 # Hz joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster diff --git a/example_6/hardware/rrbot_actuator.cpp b/example_6/hardware/rrbot_actuator.cpp index a1528b623..1adeb8d12 100644 --- a/example_6/hardware/rrbot_actuator.cpp +++ b/example_6/hardware/rrbot_actuator.cpp @@ -164,7 +164,7 @@ hardware_interface::return_type RRBotModularJoint::read( ss << std::fixed << std::setprecision(2) << std::endl << "\t" << hw_joint_state_ << " for joint '" << info_.joints[0].name.c_str() << "'"; - RCLCPP_INFO(get_logger(), "%s", ss.str().c_str()); + RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 500, "%s", ss.str().c_str()); // END: This part here is for exemplary purposes - Please do not copy to your production code return hardware_interface::return_type::OK; @@ -181,7 +181,7 @@ hardware_interface::return_type ros2_control_demo_example_6::RRBotModularJoint:: ss << std::fixed << std::setprecision(2) << std::endl << "\t" << hw_joint_command_ << " for joint '" << info_.joints[0].name.c_str() << "'"; - RCLCPP_INFO(get_logger(), "%s", ss.str().c_str()); + RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 500, "%s", ss.str().c_str()); // END: This part here is for exemplary purposes - Please do not copy to your production code return hardware_interface::return_type::OK;