Skip to content

Commit 642faa2

Browse files
clalancetteAlberto Soragna
authored andcommitted
Make lifecycle impl get_current_state() const. (ros2#2031)
We should only need to update the current state when it changes, so we do that in the change_state method (which is not const). Then we can just return the current_state_ object in get_current_state, and then mark it as const. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 3f82d12 commit 642faa2

File tree

4 files changed

+16
-5
lines changed

4 files changed

+16
-5
lines changed

rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -744,7 +744,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
744744
*/
745745
RCLCPP_LIFECYCLE_PUBLIC
746746
const State &
747-
get_current_state();
747+
get_current_state() const;
748748

749749
/// Return a list with the available states.
750750
/**

rclcpp_lifecycle/src/lifecycle_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -503,7 +503,7 @@ LifecycleNode::register_on_error(
503503
}
504504

505505
const State &
506-
LifecycleNode::get_current_state()
506+
LifecycleNode::get_current_state() const
507507
{
508508
return impl_->get_current_state();
509509
}

rclcpp_lifecycle/src/lifecycle_node_interface_impl.cpp

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,8 @@ LifecycleNode::LifecycleNodeInterfaceImpl::init(bool enable_communication_interf
196196
nullptr);
197197
}
198198
}
199+
200+
current_state_ = State(state_machine_.current_state);
199201
}
200202

201203
bool
@@ -341,9 +343,8 @@ LifecycleNode::LifecycleNodeInterfaceImpl::on_get_transition_graph(
341343
}
342344

343345
const State &
344-
LifecycleNode::LifecycleNodeInterfaceImpl::get_current_state()
346+
LifecycleNode::LifecycleNodeInterfaceImpl::get_current_state() const
345347
{
346-
current_state_ = State(state_machine_.current_state);
347348
return current_state_;
348349
}
349350

@@ -410,6 +411,9 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
410411
return RCL_RET_ERROR;
411412
}
412413

414+
// Update the internal current_state_
415+
current_state_ = State(state_machine_.current_state);
416+
413417
auto get_label_for_return_code =
414418
[](node_interfaces::LifecycleNodeInterface::CallbackReturn cb_return_code) -> const char *{
415419
auto cb_id = static_cast<uint8_t>(cb_return_code);
@@ -435,6 +439,9 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
435439
return RCL_RET_ERROR;
436440
}
437441

442+
// Update the internal current_state_
443+
current_state_ = State(state_machine_.current_state);
444+
438445
// error handling ?!
439446
// TODO(karsten1987): iterate over possible ret value
440447
if (cb_return_code == node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR) {
@@ -451,6 +458,10 @@ LifecycleNode::LifecycleNodeInterfaceImpl::change_state(
451458
return RCL_RET_ERROR;
452459
}
453460
}
461+
462+
// Update the internal current_state_
463+
current_state_ = State(state_machine_.current_state);
464+
454465
// This true holds in both cases where the actual callback
455466
// was successful or not, since at this point we have a valid transistion
456467
// to either a new primary state or error state

rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class LifecycleNode::LifecycleNodeInterfaceImpl final
6565
std::function<node_interfaces::LifecycleNodeInterface::CallbackReturn(const State &)> & cb);
6666

6767
const State &
68-
get_current_state();
68+
get_current_state() const;
6969

7070
std::vector<State>
7171
get_available_states() const;

0 commit comments

Comments
 (0)