From bb8ec274c3e7675e32733ac57e271b38cd9d0225 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 2 Aug 2024 06:57:23 +0000 Subject: [PATCH] Remove is_finite check --- .../rrbot_actuator_without_feedback.cpp | 28 +++++++++---------- 1 file changed, 13 insertions(+), 15 deletions(-) diff --git a/example_14/hardware/rrbot_actuator_without_feedback.cpp b/example_14/hardware/rrbot_actuator_without_feedback.cpp index 04d18af3..ac416eb3 100644 --- a/example_14/hardware/rrbot_actuator_without_feedback.cpp +++ b/example_14/hardware/rrbot_actuator_without_feedback.cpp @@ -217,23 +217,21 @@ hardware_interface::return_type RRBotActuatorWithoutFeedback::read( hardware_interface::return_type ros2_control_demo_example_14::RRBotActuatorWithoutFeedback::write( const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { - if (std::isfinite(hw_joint_command_)) - { - // START: This part here is for exemplary purposes - Please do not copy to your production code - RCLCPP_INFO( - rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Writing command: %f", hw_joint_command_); + // START: This part here is for exemplary purposes - Please do not copy to your production code + RCLCPP_INFO( + rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Writing command: %f", hw_joint_command_); - // Simulate sending commands to the hardware - std::ostringstream data; - data << hw_joint_command_; - RCLCPP_INFO( - rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Sending data command: %s", - data.str().c_str()); - send(sock_, data.str().c_str(), strlen(data.str().c_str()), 0); + // Simulate sending commands to the hardware + std::ostringstream data; + data << hw_joint_command_; + RCLCPP_INFO( + rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Sending data command: %s", + data.str().c_str()); + send(sock_, data.str().c_str(), strlen(data.str().c_str()), 0); + + RCLCPP_INFO(rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Joints successfully written!"); + // END: This part here is for exemplary purposes - Please do not copy to your production code - RCLCPP_INFO(rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Joints successfully written!"); - // END: This part here is for exemplary purposes - Please do not copy to your production code - } return hardware_interface::return_type::OK; }