Skip to content

Commit

Permalink
Add error output and update includes
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jul 26, 2024
1 parent c1dba05 commit d4afd58
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#define ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_ACTUATOR_WITHOUT_FEEDBACK_HPP_

#include <netinet/in.h>
#include <sys/socket.h>
#include <memory>
#include <string>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#define ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_SENSOR_FOR_POSITION_FEEDBACK_HPP_

#include <netinet/in.h>
#include <sys/socket.h>
#include <memory>
#include <string>
#include <thread>
Expand Down
5 changes: 4 additions & 1 deletion example_14/hardware/rrbot_actuator_without_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,10 @@
#include "ros2_control_demo_example_14/rrbot_actuator_without_feedback.hpp"

#include <netdb.h>
#include <sys/socket.h>
#include <chrono>
#include <cmath>
#include <cstring>
#include <limits>
#include <memory>
#include <vector>
Expand Down Expand Up @@ -94,7 +96,8 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init(
if (connect(sock_, (struct sockaddr *)&address_, sizeof(address_)) < 0)
{
RCLCPP_FATAL(
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Connection over socket failed.");
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Connection over socket failed: %s",
strerror(errno)); // Print the error message
return hardware_interface::CallbackReturn::ERROR;
}
RCLCPP_INFO(rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Connected to socket");
Expand Down
7 changes: 5 additions & 2 deletions example_14/hardware/rrbot_sensor_for_position_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,11 @@

#include "ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp"

#include <netinet/in.h>
#include <netdb.h>
#include <sys/socket.h>
#include <chrono>
#include <cmath>
#include <cstring>
#include <limits>
#include <memory>
#include <thread>
Expand Down Expand Up @@ -101,7 +102,9 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init(
RCLCPP_INFO(rclcpp::get_logger("RRBotSensorPositionFeedback"), "Binding to socket address.");
if (bind(obj_socket_, reinterpret_cast<struct sockaddr *>(&address_), sizeof(address_)) < 0)
{
RCLCPP_FATAL(rclcpp::get_logger("RRBotSensorPositionFeedback"), "Binding to socket failed.");
RCLCPP_FATAL(
rclcpp::get_logger("RRBotSensorPositionFeedback"), "Binding to socket failed: %s",
strerror(errno)); // Print the error message
return hardware_interface::CallbackReturn::ERROR;
}

Expand Down

0 comments on commit d4afd58

Please sign in to comment.