Skip to content

Commit

Permalink
use new error handling API from rcutils (#577)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored Nov 2, 2018
1 parent ec834d3 commit 33a755c
Show file tree
Hide file tree
Showing 18 changed files with 81 additions and 87 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/message_memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class MessageMemoryStrategy
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy serialized message: %s", rcl_get_error_string_safe());
"failed to destroy serialized message: %s", rcl_get_error_string().str);
}
});

Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ class Service : public ServiceBase
RCLCPP_ERROR(
rclcpp::get_logger(rcl_node_get_logger_name(handle.get())).get_child("rclcpp"),
"Error in destruction of rcl service handle: %s",
rcl_get_error_string_safe());
rcl_get_error_string().str);
rcl_reset_error();
}
} else {
Expand Down Expand Up @@ -164,7 +164,7 @@ class Service : public ServiceBase
any_callback_(any_callback)
{
// check if service handle was initialized
if (!rcl_service_is_valid(service_handle.get(), nullptr)) {
if (!rcl_service_is_valid(service_handle.get())) {
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
throw std::runtime_error(
std::string("rcl_service_t in constructor argument must be initialized beforehand."));
Expand All @@ -182,7 +182,7 @@ class Service : public ServiceBase
any_callback_(any_callback)
{
// check if service handle was initialized
if (!rcl_service_is_valid(service_handle, nullptr)) {
if (!rcl_service_is_valid(service_handle)) {
// *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
throw std::runtime_error(
std::string("rcl_service_t in constructor argument must be initialized beforehand."));
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
if (rcl_wait_set_add_subscription(wait_set, subscription.get()) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Couldn't add subscription to wait set: %s", rcl_get_error_string_safe());
"Couldn't add subscription to wait set: %s", rcl_get_error_string().str);
return false;
}
}
Expand All @@ -195,7 +195,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
if (rcl_wait_set_add_client(wait_set, client.get()) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Couldn't add client to wait set: %s", rcl_get_error_string_safe());
"Couldn't add client to wait set: %s", rcl_get_error_string().str);
return false;
}
}
Expand All @@ -204,7 +204,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
if (rcl_wait_set_add_service(wait_set, service.get()) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Couldn't add service to wait set: %s", rcl_get_error_string_safe());
"Couldn't add service to wait set: %s", rcl_get_error_string().str);
return false;
}
}
Expand All @@ -213,7 +213,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
if (rcl_wait_set_add_timer(wait_set, timer.get()) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Couldn't add timer to wait set: %s", rcl_get_error_string_safe());
"Couldn't add timer to wait set: %s", rcl_get_error_string().str);
return false;
}
}
Expand All @@ -223,7 +223,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Couldn't add guard_condition to wait set: %s",
rcl_get_error_string_safe());
rcl_get_error_string().str);
return false;
}
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ ClientBase::ClientBase(
if (rcl_client_fini(client, handle.get()) != RCL_RET_OK) {
RCLCPP_ERROR(
rclcpp::get_logger(rcl_node_get_logger_name(handle.get())).get_child("rclcpp"),
"Error in destruction of rcl client handle: %s", rcl_get_error_string_safe());
"Error in destruction of rcl client handle: %s", rcl_get_error_string().str);
rcl_reset_error();
}
} else {
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/exceptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ throw_from_rcl_error(

RCLErrorBase::RCLErrorBase(rcl_ret_t ret, const rcl_error_state_t * error_state)
: ret(ret), message(error_state->message), file(error_state->file), line(error_state->line_number),
formatted_message(rcl_get_error_string_safe())
formatted_message(rcl_get_error_string().str)
{}

RCLError::RCLError(
Expand Down
30 changes: 15 additions & 15 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ Executor::Executor(const ExecutorArgs & args)
{
throw std::runtime_error(
std::string("Failed to create interrupt guard condition in Executor constructor: ") +
rcl_get_error_string_safe());
rcl_get_error_string().str);
}

// The number of guard conditions is always at least 2: 1 for the ctrl-c guard cond,
Expand All @@ -63,12 +63,12 @@ Executor::Executor(const ExecutorArgs & args)
{
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to create wait set: %s", rcl_get_error_string_safe());
"failed to create wait set: %s", rcl_get_error_string().str);
rcl_reset_error();
if (rcl_guard_condition_fini(&interrupt_guard_condition_) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy guard condition: %s", rcl_get_error_string_safe());
"failed to destroy guard condition: %s", rcl_get_error_string().str);
rcl_reset_error();
}
throw std::runtime_error("Failed to create wait set in Executor constructor");
Expand All @@ -91,14 +91,14 @@ Executor::~Executor()
if (rcl_wait_set_fini(&wait_set_) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy wait set: %s", rcl_get_error_string_safe());
"failed to destroy wait set: %s", rcl_get_error_string().str);
rcl_reset_error();
}
// Finalize the interrupt guard condition.
if (rcl_guard_condition_fini(&interrupt_guard_condition_) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy guard condition: %s", rcl_get_error_string_safe());
"failed to destroy guard condition: %s", rcl_get_error_string().str);
rcl_reset_error();
}
// Remove and release the sigint guard condition
Expand Down Expand Up @@ -127,7 +127,7 @@ Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_pt
if (notify) {
// Interrupt waiting to handle new node
if (rcl_trigger_guard_condition(&interrupt_guard_condition_) != RCL_RET_OK) {
throw std::runtime_error(rcl_get_error_string_safe());
throw std::runtime_error(rcl_get_error_string().str);
}
}
// Add the node's notify condition to the guard condition handles
Expand Down Expand Up @@ -161,7 +161,7 @@ Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node
// If the node was matched and removed, interrupt waiting
if (node_removed) {
if (rcl_trigger_guard_condition(&interrupt_guard_condition_) != RCL_RET_OK) {
throw std::runtime_error(rcl_get_error_string_safe());
throw std::runtime_error(rcl_get_error_string().str);
}
}
}
Expand Down Expand Up @@ -247,7 +247,7 @@ Executor::cancel()
{
spinning.store(false);
if (rcl_trigger_guard_condition(&interrupt_guard_condition_) != RCL_RET_OK) {
throw std::runtime_error(rcl_get_error_string_safe());
throw std::runtime_error(rcl_get_error_string().str);
}
}

Expand Down Expand Up @@ -286,7 +286,7 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
// Wake the wait, because it may need to be recalculated or work that
// was previously blocked is now available.
if (rcl_trigger_guard_condition(&interrupt_guard_condition_) != RCL_RET_OK) {
throw std::runtime_error(rcl_get_error_string_safe());
throw std::runtime_error(rcl_get_error_string().str);
}
}

Expand All @@ -309,7 +309,7 @@ Executor::execute_subscription(
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"take_serialized failed for subscription on topic '%s': %s",
subscription->get_topic_name(), rcl_get_error_string_safe());
subscription->get_topic_name(), rcl_get_error_string().str);
rcl_reset_error();
}
subscription->return_serialized_message(serialized_msg);
Expand All @@ -324,7 +324,7 @@ Executor::execute_subscription(
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"could not deserialize serialized message on topic '%s': %s",
subscription->get_topic_name(), rcl_get_error_string_safe());
subscription->get_topic_name(), rcl_get_error_string().str);
rcl_reset_error();
}
subscription->return_message(message);
Expand All @@ -349,7 +349,7 @@ Executor::execute_intra_process_subscription(
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"take failed for intra process subscription on topic '%s': %s",
subscription->get_topic_name(), rcl_get_error_string_safe());
subscription->get_topic_name(), rcl_get_error_string().str);
rcl_reset_error();
}
}
Expand Down Expand Up @@ -377,7 +377,7 @@ Executor::execute_service(
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"take request failed for server of service '%s': %s",
service->get_service_name(), rcl_get_error_string_safe());
service->get_service_name(), rcl_get_error_string().str);
rcl_reset_error();
}
}
Expand All @@ -398,7 +398,7 @@ Executor::execute_client(
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"take response failed for client of service '%s': %s",
client->get_service_name(), rcl_get_error_string_safe());
client->get_service_name(), rcl_get_error_string().str);
rcl_reset_error();
}
}
Expand Down Expand Up @@ -433,7 +433,7 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
memory_strategy_->number_of_ready_clients(), memory_strategy_->number_of_ready_services());
if (RCL_RET_OK != ret) {
throw std::runtime_error(
std::string("Couldn't resize the wait set : ") + rcl_get_error_string_safe());
std::string("Couldn't resize the wait set : ") + rcl_get_error_string().str);
}

if (!memory_strategy_->add_handles_to_wait_set(&wait_set_)) {
Expand Down
13 changes: 3 additions & 10 deletions rclcpp/src/rclcpp/expand_topic_or_service_name.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,25 +51,18 @@ rclcpp::expand_topic_or_service_name(
}
rcl_ret_t ret = rcl_get_default_topic_name_substitutions(&substitutions_map);
if (ret != RCL_RET_OK) {
rcutils_error_state_t error_state;
if (rcutils_error_state_copy(rcl_get_error_state(), &error_state) != RCUTILS_RET_OK) {
throw std::bad_alloc();
}
auto error_state_scope_exit = rclcpp::make_scope_exit(
[&error_state]() {
rcutils_error_state_fini(&error_state);
});
const rcutils_error_state_t * error_state = rcl_get_error_state();
// finalize the string map before throwing
rcutils_ret = rcutils_string_map_fini(&substitutions_map);
if (rcutils_ret != RCUTILS_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to fini string_map (%d) during error handling: %s",
rcutils_ret,
rcutils_get_error_string_safe());
rcutils_get_error_string().str);
rcutils_reset_error();
}
throw_from_rcl_error(ret, "", &error_state);
throw_from_rcl_error(ret, "", error_state);
}

ret = rcl_expand_topic_name(
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ NodeBase::NodeBase(
if (rcl_guard_condition_fini(&notify_guard_condition_) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy guard condition: %s", rcl_get_error_string_safe());
"failed to destroy guard condition: %s", rcl_get_error_string().str);
}
};

Expand Down Expand Up @@ -122,7 +122,7 @@ NodeBase::NodeBase(
// Print message because exception will be thrown later in this code block
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Failed to fini arguments during error handling: %s", rcl_get_error_string_safe());
"Failed to fini arguments during error handling: %s", rcl_get_error_string().str);
rcl_reset_error();
}

Expand Down Expand Up @@ -180,7 +180,7 @@ NodeBase::NodeBase(
if (rcl_node_fini(node) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Error in destruction of rcl node handle: %s", rcl_get_error_string_safe());
"Error in destruction of rcl node handle: %s", rcl_get_error_string().str);
}
delete node;
});
Expand All @@ -197,7 +197,7 @@ NodeBase::NodeBase(
// print message because throwing would prevent the destructor from being called
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"Failed to fini arguments: %s", rcl_get_error_string_safe());
"Failed to fini arguments: %s", rcl_get_error_string().str);
rcl_reset_error();
}
}
Expand All @@ -211,7 +211,7 @@ NodeBase::~NodeBase()
if (rcl_guard_condition_fini(&notify_guard_condition_) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
"failed to destroy guard condition: %s", rcl_get_error_string_safe());
"failed to destroy guard condition: %s", rcl_get_error_string().str);
}
}
}
Expand Down
26 changes: 13 additions & 13 deletions rclcpp/src/rclcpp/node_interfaces/node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ NodeGraph::get_topic_names_and_types(bool no_demangle) const
&topic_names_and_types);
if (ret != RCL_RET_OK) {
auto error_msg = std::string("failed to get topic names and types: ") +
rcl_get_error_string_safe();
rcl_get_error_string().str;
rcl_reset_error();
if (rcl_names_and_types_fini(&topic_names_and_types) != RCL_RET_OK) {
error_msg += std::string(", failed also to cleanup topic names and types, leaking memory: ") +
rcl_get_error_string_safe();
rcl_get_error_string().str;
}
throw std::runtime_error(error_msg + rcl_get_error_string_safe());
throw std::runtime_error(error_msg + rcl_get_error_string().str);
}

std::map<std::string, std::vector<std::string>> topics_and_types;
Expand All @@ -80,7 +80,7 @@ NodeGraph::get_topic_names_and_types(bool no_demangle) const
if (ret != RCL_RET_OK) {
// *INDENT-OFF*
throw std::runtime_error(
std::string("could not destroy topic names and types: ") + rcl_get_error_string_safe());
std::string("could not destroy topic names and types: ") + rcl_get_error_string().str);
// *INDENT-ON*
}

Expand All @@ -99,14 +99,14 @@ NodeGraph::get_service_names_and_types() const
&service_names_and_types);
if (ret != RCL_RET_OK) {
auto error_msg = std::string("failed to get service names and types: ") +
rcl_get_error_string_safe();
rcl_get_error_string().str;
rcl_reset_error();
if (rcl_names_and_types_fini(&service_names_and_types) != RCL_RET_OK) {
error_msg +=
std::string(", failed also to cleanup service names and types, leaking memory: ") +
rcl_get_error_string_safe();
rcl_get_error_string().str;
}
throw std::runtime_error(error_msg + rcl_get_error_string_safe());
throw std::runtime_error(error_msg + rcl_get_error_string().str);
}

std::map<std::string, std::vector<std::string>> services_and_types;
Expand All @@ -121,7 +121,7 @@ NodeGraph::get_service_names_and_types() const
if (ret != RCL_RET_OK) {
// *INDENT-OFF*
throw std::runtime_error(
std::string("could not destroy service names and types: ") + rcl_get_error_string_safe());
std::string("could not destroy service names and types: ") + rcl_get_error_string().str);
// *INDENT-ON*
}

Expand Down Expand Up @@ -155,16 +155,16 @@ NodeGraph::get_node_names_and_namespaces() const
&node_names_c,
&node_namespaces_c);
if (ret != RCL_RET_OK) {
auto error_msg = std::string("failed to get node names: ") + rcl_get_error_string_safe();
auto error_msg = std::string("failed to get node names: ") + rcl_get_error_string().str;
rcl_reset_error();
if (rcutils_string_array_fini(&node_names_c) != RCUTILS_RET_OK) {
error_msg += std::string(", failed also to cleanup node names, leaking memory: ") +
rcl_get_error_string_safe();
rcl_get_error_string().str;
rcl_reset_error();
}
if (rcutils_string_array_fini(&node_namespaces_c) != RCUTILS_RET_OK) {
error_msg += std::string(", failed also to cleanup node namespaces, leaking memory: ") +
rcl_get_error_string_safe();
rcl_get_error_string().str;
rcl_reset_error();
}
// TODO(karsten1987): Append rcutils_error_message once it's in master
Expand Down Expand Up @@ -217,7 +217,7 @@ NodeGraph::count_publishers(const std::string & topic_name) const
if (ret != RMW_RET_OK) {
// *INDENT-OFF*
throw std::runtime_error(
std::string("could not count publishers: ") + rmw_get_error_string_safe());
std::string("could not count publishers: ") + rmw_get_error_string().str);
// *INDENT-ON*
}
return count;
Expand All @@ -239,7 +239,7 @@ NodeGraph::count_subscribers(const std::string & topic_name) const
if (ret != RMW_RET_OK) {
// *INDENT-OFF*
throw std::runtime_error(
std::string("could not count subscribers: ") + rmw_get_error_string_safe());
std::string("could not count subscribers: ") + rmw_get_error_string().str);
// *INDENT-ON*
}
return count;
Expand Down
Loading

0 comments on commit 33a755c

Please sign in to comment.