Switch to using new rcutils_strerror. (#993)
* Switch to using new rcutils_strerror. Also increase timeouts for test_logging, which should reduce flakes on Windows. Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
This commit is contained in:
parent
1644e926f9
commit
f30329fbec
4 changed files with 9 additions and 26 deletions
|
@ -8,6 +8,7 @@ find_package(rcl REQUIRED)
|
|||
find_package(rcl_interfaces REQUIRED)
|
||||
find_package(rcl_yaml_param_parser REQUIRED)
|
||||
find_package(rcpputils REQUIRED)
|
||||
find_package(rcutils REQUIRED)
|
||||
find_package(rmw REQUIRED)
|
||||
find_package(rosgraph_msgs REQUIRED)
|
||||
find_package(rosidl_generator_cpp REQUIRED)
|
||||
|
@ -112,6 +113,7 @@ ament_target_dependencies(${PROJECT_NAME}
|
|||
"rcl"
|
||||
"rcl_yaml_param_parser"
|
||||
"rcpputils"
|
||||
"rcutils"
|
||||
"builtin_interfaces"
|
||||
"rosgraph_msgs"
|
||||
"rosidl_typesupport_cpp"
|
||||
|
@ -138,6 +140,7 @@ ament_export_libraries(${PROJECT_NAME})
|
|||
ament_export_dependencies(ament_cmake)
|
||||
ament_export_dependencies(rcl)
|
||||
ament_export_dependencies(rcpputils)
|
||||
ament_export_dependencies(rcutils)
|
||||
ament_export_dependencies(builtin_interfaces)
|
||||
ament_export_dependencies(rosgraph_msgs)
|
||||
ament_export_dependencies(rosidl_typesupport_cpp)
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
<depend>rcl</depend>
|
||||
<depend>rcl_yaml_param_parser</depend>
|
||||
<depend>rcpputils</depend>
|
||||
<depend>rcutils</depend>
|
||||
<depend>rmw</depend>
|
||||
<depend>tracetools</depend>
|
||||
|
||||
|
|
|
@ -30,6 +30,7 @@
|
|||
#endif
|
||||
|
||||
#include "rclcpp/logging.hpp"
|
||||
#include "rcutils/strerror.h"
|
||||
#include "rmw/impl/cpp/demangle.hpp"
|
||||
|
||||
using rclcpp::SignalHandler;
|
||||
|
@ -159,28 +160,6 @@ SignalHandler::~SignalHandler()
|
|||
}
|
||||
}
|
||||
|
||||
RCLCPP_LOCAL
|
||||
void
|
||||
__safe_strerror(int errnum, char * buffer, size_t buffer_length)
|
||||
{
|
||||
#if defined(_WIN32)
|
||||
strerror_s(buffer, buffer_length, errnum);
|
||||
#elif defined(_GNU_SOURCE) && (!defined(ANDROID) || __ANDROID_API__ >= 23)
|
||||
/* GNU-specific */
|
||||
char * msg = strerror_r(errnum, buffer, buffer_length);
|
||||
if (msg != buffer) {
|
||||
strncpy(buffer, msg, buffer_length);
|
||||
buffer[buffer_length - 1] = '\0';
|
||||
}
|
||||
#else
|
||||
/* XSI-compliant */
|
||||
int error_status = strerror_r(errnum, buffer, buffer_length);
|
||||
if (error_status != 0) {
|
||||
throw std::runtime_error("Failed to get error string for errno: " + std::to_string(errnum));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
SignalHandler::signal_handler_type
|
||||
SignalHandler::set_signal_handler(
|
||||
int signal_value,
|
||||
|
@ -197,7 +176,7 @@ SignalHandler::set_signal_handler(
|
|||
#endif
|
||||
if (signal_handler_install_failed) {
|
||||
char error_string[1024];
|
||||
__safe_strerror(errno, error_string, sizeof(error_string));
|
||||
rcutils_strerror(error_string, sizeof(error_string));
|
||||
auto msg =
|
||||
"Failed to set SIGINT signal handler (" + std::to_string(errno) + "): " + error_string;
|
||||
throw std::runtime_error(msg);
|
||||
|
|
|
@ -205,9 +205,9 @@ TEST_F(TestLoggingMacros, test_throttle) {
|
|||
RCLCPP_DEBUG_SKIPFIRST_THROTTLE(g_logger, steady_clock, 1, "Skip first throttling");
|
||||
EXPECT_EQ(1u, g_log_calls);
|
||||
for (uint64_t i = 0; i < 6; ++i) {
|
||||
RCLCPP_DEBUG_THROTTLE(g_logger, steady_clock, 10, "Throttling");
|
||||
RCLCPP_DEBUG_SKIPFIRST_THROTTLE(g_logger, steady_clock, 40, "Throttling");
|
||||
std::this_thread::sleep_for(5ms);
|
||||
RCLCPP_DEBUG_THROTTLE(g_logger, steady_clock, 100, "Throttling");
|
||||
RCLCPP_DEBUG_SKIPFIRST_THROTTLE(g_logger, steady_clock, 400, "Throttling");
|
||||
std::this_thread::sleep_for(50ms);
|
||||
}
|
||||
EXPECT_EQ(4u, g_log_calls);
|
||||
rclcpp::Clock ros_clock(RCL_ROS_TIME);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue