Skip to content

Commit 945d254

Browse files
authored
Switch lifecycle to use the RCLCPP macros. (#2233)
This ensures that they'll go out to /rosout and the disk. Signed-off-by: Chris Lalancette <[email protected]>
1 parent deebbc3 commit 945d254

File tree

3 files changed

+31
-13
lines changed

3 files changed

+31
-13
lines changed

rclcpp_lifecycle/src/lifecycle_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ LifecycleNode::LifecycleNode(
122122
)),
123123
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
124124
node_options_(options),
125-
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
125+
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_, node_logging_))
126126
{
127127
impl_->init(enable_communication_interface);
128128

rclcpp_lifecycle/src/lifecycle_node_interface_impl.cpp

Lines changed: 25 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
#include "lifecycle_msgs/srv/get_available_transitions.hpp"
3030

3131
#include "rclcpp/node_interfaces/node_base_interface.hpp"
32+
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
3233
#include "rclcpp/node_interfaces/node_services_interface.hpp"
3334

3435
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
@@ -50,9 +51,11 @@ namespace rclcpp_lifecycle
5051

5152
LifecycleNode::LifecycleNodeInterfaceImpl::LifecycleNodeInterfaceImpl(
5253
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_interface,
53-
std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services_interface)
54+
std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services_interface,
55+
std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> node_logging_interface)
5456
: node_base_interface_(node_base_interface),
55-
node_services_interface_(node_services_interface)
57+
node_services_interface_(node_services_interface),
58+
node_logging_interface_(node_logging_interface)
5659
{
5760
}
5861

@@ -65,8 +68,8 @@ LifecycleNode::LifecycleNodeInterfaceImpl::~LifecycleNodeInterfaceImpl()
6568
ret = rcl_lifecycle_state_machine_fini(&state_machine_, node_handle);
6669
}
6770
if (ret != RCL_RET_OK) {
68-
RCUTILS_LOG_FATAL_NAMED(
69-
"rclcpp_lifecycle",
71+
RCLCPP_FATAL(
72+
node_logging_interface_->get_logger(),
7073
"failed to destroy rcl_state_machine");
7174
}
7275
}
@@ -398,7 +401,8 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
398401
{
399402
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
400403
if (rcl_lifecycle_state_machine_is_initialized(&state_machine_) != RCL_RET_OK) {
401-
RCUTILS_LOG_ERROR(
404+
RCLCPP_ERROR(
405+
node_logging_interface_->get_logger(),
402406
"Unable to change state for state machine for %s: %s",
403407
node_base_interface_->get_name(), rcl_get_error_string().str);
404408
return RCL_RET_ERROR;
@@ -411,7 +415,8 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
411415
rcl_lifecycle_trigger_transition_by_id(
412416
&state_machine_, transition_id, publish_update) != RCL_RET_OK)
413417
{
414-
RCUTILS_LOG_ERROR(
418+
RCLCPP_ERROR(
419+
node_logging_interface_->get_logger(),
415420
"Unable to start transition %u from current state %s: %s",
416421
transition_id, state_machine_.current_state->label, rcl_get_error_string().str);
417422
rcutils_reset_error();
@@ -443,7 +448,8 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
443448
rcl_lifecycle_trigger_transition_by_label(
444449
&state_machine_, transition_label, publish_update) != RCL_RET_OK)
445450
{
446-
RCUTILS_LOG_ERROR(
451+
RCLCPP_ERROR(
452+
node_logging_interface_->get_logger(),
447453
"Failed to finish transition %u. Current state is now: %s (%s)",
448454
transition_id, state_machine_.current_state->label, rcl_get_error_string().str);
449455
rcutils_reset_error();
@@ -458,7 +464,9 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
458464
// error handling ?!
459465
// TODO(karsten1987): iterate over possible ret value
460466
if (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR) {
461-
RCUTILS_LOG_WARN("Error occurred while doing error handling.");
467+
RCLCPP_WARN(
468+
node_logging_interface_->get_logger(),
469+
"Error occurred while doing error handling.");
462470

463471
auto error_cb_code = execute_callback(current_state_id, initial_state);
464472
auto error_cb_label = get_label_for_return_code(error_cb_code);
@@ -467,7 +475,9 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
467475
rcl_lifecycle_trigger_transition_by_label(
468476
&state_machine_, error_cb_label, publish_update) != RCL_RET_OK)
469477
{
470-
RCUTILS_LOG_ERROR("Failed to call cleanup on error state: %s", rcl_get_error_string().str);
478+
RCLCPP_ERROR(
479+
node_logging_interface_->get_logger(),
480+
"Failed to call cleanup on error state: %s", rcl_get_error_string().str);
471481
rcutils_reset_error();
472482
return RCL_RET_ERROR;
473483
}
@@ -495,8 +505,12 @@ LifecycleNode::LifecycleNodeInterfaceImpl::execute_callback(
495505
try {
496506
cb_success = callback(State(previous_state));
497507
} catch (const std::exception & e) {
498-
RCUTILS_LOG_ERROR("Caught exception in callback for transition %d", it->first);
499-
RCUTILS_LOG_ERROR("Original error: %s", e.what());
508+
RCLCPP_ERROR(
509+
node_logging_interface_->get_logger(),
510+
"Caught exception in callback for transition %d", it->first);
511+
RCLCPP_ERROR(
512+
node_logging_interface_->get_logger(),
513+
"Original error: %s", e.what());
500514
cb_success = node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
501515
}
502516
}

rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232

3333
#include "rclcpp/macros.hpp"
3434
#include "rclcpp/node_interfaces/node_base_interface.hpp"
35+
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
3536
#include "rclcpp/node_interfaces/node_services_interface.hpp"
3637

3738
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
@@ -52,7 +53,8 @@ class LifecycleNode::LifecycleNodeInterfaceImpl final
5253
public:
5354
LifecycleNodeInterfaceImpl(
5455
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_interface,
55-
std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services_interface);
56+
std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services_interface,
57+
std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> node_logging_interface);
5658

5759
~LifecycleNodeInterfaceImpl();
5860

@@ -152,6 +154,7 @@ class LifecycleNode::LifecycleNodeInterfaceImpl final
152154

153155
using NodeBasePtr = std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>;
154156
using NodeServicesPtr = std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>;
157+
using NodeLoggingPtr = std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>;
155158
using ChangeStateSrvPtr = std::shared_ptr<rclcpp::Service<ChangeStateSrv>>;
156159
using GetStateSrvPtr = std::shared_ptr<rclcpp::Service<GetStateSrv>>;
157160
using GetAvailableStatesSrvPtr =
@@ -163,6 +166,7 @@ class LifecycleNode::LifecycleNodeInterfaceImpl final
163166

164167
NodeBasePtr node_base_interface_;
165168
NodeServicesPtr node_services_interface_;
169+
NodeLoggingPtr node_logging_interface_;
166170
ChangeStateSrvPtr srv_change_state_;
167171
GetStateSrvPtr srv_get_state_;
168172
GetAvailableStatesSrvPtr srv_get_available_states_;

0 commit comments

Comments
 (0)