Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ex14: Remove is_finite check #560

Merged
merged 1 commit into from
Aug 5, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 13 additions & 15 deletions example_14/hardware/rrbot_actuator_without_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
Loading