Skip to content

Commit d4afd58

Browse files
Add error output and update includes
1 parent c1dba05 commit d4afd58

File tree

4 files changed

+9
-5
lines changed

4 files changed

+9
-5
lines changed

example_14/hardware/include/ros2_control_demo_example_14/rrbot_actuator_without_feedback.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#define ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_ACTUATOR_WITHOUT_FEEDBACK_HPP_
2121

2222
#include <netinet/in.h>
23-
#include <sys/socket.h>
2423
#include <memory>
2524
#include <string>
2625
#include <vector>

example_14/hardware/include/ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#define ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_SENSOR_FOR_POSITION_FEEDBACK_HPP_
2121

2222
#include <netinet/in.h>
23-
#include <sys/socket.h>
2423
#include <memory>
2524
#include <string>
2625
#include <thread>

example_14/hardware/rrbot_actuator_without_feedback.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,10 @@
1919
#include "ros2_control_demo_example_14/rrbot_actuator_without_feedback.hpp"
2020

2121
#include <netdb.h>
22+
#include <sys/socket.h>
2223
#include <chrono>
2324
#include <cmath>
25+
#include <cstring>
2426
#include <limits>
2527
#include <memory>
2628
#include <vector>
@@ -94,7 +96,8 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init(
9496
if (connect(sock_, (struct sockaddr *)&address_, sizeof(address_)) < 0)
9597
{
9698
RCLCPP_FATAL(
97-
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Connection over socket failed.");
99+
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Connection over socket failed: %s",
100+
strerror(errno)); // Print the error message
98101
return hardware_interface::CallbackReturn::ERROR;
99102
}
100103
RCLCPP_INFO(rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Connected to socket");

example_14/hardware/rrbot_sensor_for_position_feedback.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,11 @@
1818

1919
#include "ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp"
2020

21-
#include <netinet/in.h>
21+
#include <netdb.h>
2222
#include <sys/socket.h>
2323
#include <chrono>
2424
#include <cmath>
25+
#include <cstring>
2526
#include <limits>
2627
#include <memory>
2728
#include <thread>
@@ -101,7 +102,9 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init(
101102
RCLCPP_INFO(rclcpp::get_logger("RRBotSensorPositionFeedback"), "Binding to socket address.");
102103
if (bind(obj_socket_, reinterpret_cast<struct sockaddr *>(&address_), sizeof(address_)) < 0)
103104
{
104-
RCLCPP_FATAL(rclcpp::get_logger("RRBotSensorPositionFeedback"), "Binding to socket failed.");
105+
RCLCPP_FATAL(
106+
rclcpp::get_logger("RRBotSensorPositionFeedback"), "Binding to socket failed: %s",
107+
strerror(errno)); // Print the error message
105108
return hardware_interface::CallbackReturn::ERROR;
106109
}
107110

0 commit comments

Comments
 (0)