Skip to content

Commit

Permalink
Example 14: Check for NaN in write method
Browse files Browse the repository at this point in the history
Since activation of the "hardware" takes some time, the resource manager
might try to write the initial NaN value to the hardware. This commit adds
a check to the write method for that.
  • Loading branch information
fmauch committed Mar 2, 2024
1 parent cf80391 commit 798f77c
Showing 1 changed file with 15 additions and 13 deletions.
28 changes: 15 additions & 13 deletions example_14/hardware/rrbot_actuator_without_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,21 +183,23 @@ 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*/)
{
// 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);
if (!std::isnan(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_);

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
// 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
}
return hardware_interface::return_type::OK;
}

Expand Down

0 comments on commit 798f77c

Please sign in to comment.