Skip to content

Commit 7a5779c

Browse files
authored
Rename get_state and set_state Functions to get/set_lifecylce_state (variant support) (#1683)
1 parent 6164883 commit 7a5779c

28 files changed

+700
-480
lines changed

controller_interface/include/controller_interface/async_controller.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,8 @@ class AsyncControllerThread
8282
TimePoint next_iteration_time =
8383
TimePoint(std::chrono::nanoseconds(controller_->get_node()->now().nanoseconds()));
8484

85-
if (controller_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
85+
if (
86+
controller_->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
8687
{
8788
auto const current_time = controller_->get_node()->now();
8889
auto const measured_period = current_time - previous_time;

controller_interface/include/controller_interface/controller_interface_base.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
147147
std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
148148

149149
CONTROLLER_INTERFACE_PUBLIC
150-
const rclcpp_lifecycle::State & get_state() const;
150+
const rclcpp_lifecycle::State & get_lifecycle_state() const;
151151

152152
CONTROLLER_INTERFACE_PUBLIC
153153
unsigned int get_update_rate() const;

controller_interface/src/chainable_controller_interface.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ bool ChainableControllerInterface::set_chained_mode(bool chained_mode)
9797
{
9898
bool result = false;
9999

100-
if (get_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
100+
if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
101101
{
102102
result = on_set_chained_mode(chained_mode);
103103

@@ -112,7 +112,8 @@ bool ChainableControllerInterface::set_chained_mode(bool chained_mode)
112112
get_node()->get_logger(),
113113
"Can not change controller's chained mode because it is no in '%s' state. "
114114
"Current state is '%s'.",
115-
hardware_interface::lifecycle_state_names::UNCONFIGURED, get_state().label().c_str());
115+
hardware_interface::lifecycle_state_names::UNCONFIGURED,
116+
get_lifecycle_state().label().c_str());
116117
}
117118

118119
return result;

controller_interface/src/controller_interface_base.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::configure()
8383
// Then we don't need to do state-machine related checks.
8484
//
8585
// Other solution is to add check into the LifecycleNode if a transition is valid to trigger
86-
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
86+
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
8787
{
8888
update_rate_ = static_cast<unsigned int>(get_node()->get_parameter("update_rate").as_int());
8989
is_async_ = get_node()->get_parameter("is_async").as_bool();
@@ -106,7 +106,7 @@ void ControllerInterfaceBase::release_interfaces()
106106
state_interfaces_.clear();
107107
}
108108

109-
const rclcpp_lifecycle::State & ControllerInterfaceBase::get_state() const
109+
const rclcpp_lifecycle::State & ControllerInterfaceBase::get_lifecycle_state() const
110110
{
111111
return node_->get_current_state();
112112
}

controller_manager/src/controller_manager.cpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,8 @@ static const rmw_qos_profile_t qos_services = {
5858

5959
inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller)
6060
{
61-
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE;
61+
return controller.get_lifecycle_state().id() ==
62+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE;
6263
}
6364

6465
inline bool is_controller_inactive(
@@ -69,7 +70,7 @@ inline bool is_controller_inactive(
6970

7071
inline bool is_controller_active(const controller_interface::ControllerInterfaceBase & controller)
7172
{
72-
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
73+
return controller.get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
7374
}
7475

7576
inline bool is_controller_active(
@@ -659,7 +660,7 @@ controller_interface::return_type ControllerManager::configure_controller(
659660
}
660661
auto controller = found_it->c;
661662

662-
auto state = controller->get_state();
663+
auto state = controller->get_lifecycle_state();
663664
if (
664665
state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE ||
665666
state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
@@ -670,7 +671,7 @@ controller_interface::return_type ControllerManager::configure_controller(
670671
return controller_interface::return_type::ERROR;
671672
}
672673

673-
auto new_state = controller->get_state();
674+
auto new_state = controller->get_lifecycle_state();
674675
if (state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
675676
{
676677
RCLCPP_DEBUG(
@@ -1744,7 +1745,7 @@ void ControllerManager::list_controllers_srv_cb(
17441745
controller_state.name = controllers[i].info.name;
17451746
controller_state.type = controllers[i].info.type;
17461747
controller_state.claimed_interfaces = controllers[i].info.claimed_interfaces;
1747-
controller_state.state = controllers[i].c->get_state().label();
1748+
controller_state.state = controllers[i].c->get_lifecycle_state().label();
17481749
controller_state.is_chainable = controllers[i].c->is_chainable();
17491750
controller_state.is_chained = controllers[i].c->is_in_chained_mode();
17501751

@@ -2728,7 +2729,7 @@ void ControllerManager::controller_activity_diagnostic_callback(
27282729
{
27292730
all_active = false;
27302731
}
2731-
stat.add(controllers[i].info.name, controllers[i].c->get_state().label());
2732+
stat.add(controllers[i].info.name, controllers[i].c->get_lifecycle_state().label());
27322733
}
27332734

27342735
if (all_active)

controller_manager/test/test_chainable_controller/test_chainable_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,8 @@ controller_interface::InterfaceConfiguration
3333
TestChainableController::command_interface_configuration() const
3434
{
3535
if (
36-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
37-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
36+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
37+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
3838
{
3939
return cmd_iface_cfg_;
4040
}
@@ -49,8 +49,8 @@ controller_interface::InterfaceConfiguration
4949
TestChainableController::state_interface_configuration() const
5050
{
5151
if (
52-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
53-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
52+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
53+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
5454
{
5555
auto state_iface_cfg = state_iface_cfg_;
5656
if (imu_sensor_)

controller_manager/test/test_controller/test_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,8 @@ TestController::TestController()
3131
controller_interface::InterfaceConfiguration TestController::command_interface_configuration() const
3232
{
3333
if (
34-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
35-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
34+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
35+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
3636
{
3737
return cmd_iface_cfg_;
3838
}
@@ -46,8 +46,8 @@ controller_interface::InterfaceConfiguration TestController::command_interface_c
4646
controller_interface::InterfaceConfiguration TestController::state_interface_configuration() const
4747
{
4848
if (
49-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
50-
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
49+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
50+
get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
5151
{
5252
return state_iface_cfg_;
5353
}

controller_manager/test/test_controller_manager.cpp

Lines changed: 33 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,8 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
127127
<< "Update should not reach an unconfigured controller";
128128

129129
EXPECT_EQ(
130-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());
130+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
131+
test_controller->get_lifecycle_state().id());
131132

132133
// configure controller
133134
{
@@ -141,7 +142,9 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
141142
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started";
142143
EXPECT_EQ(0u, test_controller2->internal_counter) << "Controller is not started";
143144

144-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
145+
EXPECT_EQ(
146+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
147+
test_controller->get_lifecycle_state().id());
145148

146149
// Start controller, will take effect at the end of the update function
147150
std::vector<std::string> start_controllers = {"fake_controller", TEST_CONTROLLER2_NAME};
@@ -182,7 +185,8 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
182185
ControllerManagerRunner cm_runner(this);
183186
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
184187
}
185-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());
188+
EXPECT_EQ(
189+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state().id());
186190

187191
EXPECT_EQ(
188192
controller_interface::return_type::OK,
@@ -210,7 +214,9 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
210214
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
211215
}
212216

213-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
217+
EXPECT_EQ(
218+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
219+
test_controller->get_lifecycle_state().id());
214220
auto unload_future = std::async(
215221
std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_,
216222
test_controller::TEST_CONTROLLER_NAME);
@@ -221,7 +227,8 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
221227
EXPECT_EQ(controller_interface::return_type::OK, unload_future.get());
222228

223229
EXPECT_EQ(
224-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());
230+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
231+
test_controller->get_lifecycle_state().id());
225232
EXPECT_EQ(1, test_controller.use_count());
226233
}
227234

@@ -242,7 +249,8 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
242249
<< "Update should not reach an unconfigured controller";
243250

244251
EXPECT_EQ(
245-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());
252+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
253+
test_controller->get_lifecycle_state().id());
246254

247255
test_controller->get_node()->set_parameter({"update_rate", 4});
248256
// configure controller
@@ -255,7 +263,9 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
255263
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
256264
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started";
257265

258-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
266+
EXPECT_EQ(
267+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
268+
test_controller->get_lifecycle_state().id());
259269

260270
// Start controller, will take effect at the end of the update function
261271
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
@@ -276,7 +286,8 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
276286
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
277287
}
278288

279-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());
289+
EXPECT_EQ(
290+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state().id());
280291

281292
// As the controller frequency is 4Hz, it needs to pass 25 iterations for 1 update cycle
282293
for (size_t i = 0; i < 25; i++)
@@ -323,7 +334,8 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
323334
<< "Update should not reach an unconfigured controller";
324335

325336
EXPECT_EQ(
326-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());
337+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
338+
test_controller->get_lifecycle_state().id());
327339

328340
rclcpp::Parameter update_rate_parameter("update_rate", static_cast<int>(ctrl_update_rate));
329341
test_controller->get_node()->set_parameter(update_rate_parameter);
@@ -337,7 +349,9 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
337349
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
338350
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
339351
<< "Controller is not started";
340-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
352+
EXPECT_EQ(
353+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
354+
test_controller->get_lifecycle_state().id());
341355

342356
// Start controller, will take effect at the end of the update function
343357
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
@@ -360,7 +374,8 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
360374
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
361375
}
362376

363-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());
377+
EXPECT_EQ(
378+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state().id());
364379

365380
const auto pre_internal_counter = test_controller->internal_counter;
366381
rclcpp::Rate loop_rate(cm_->get_update_rate());
@@ -430,7 +445,8 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
430445
EXPECT_EQ(2, test_controller.use_count());
431446

432447
EXPECT_EQ(
433-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());
448+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
449+
test_controller->get_lifecycle_state().id());
434450

435451
test_controller->get_node()->set_parameter({"update_rate", static_cast<int>(ctrl_update_rate)});
436452
// configure controller
@@ -443,7 +459,9 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
443459
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
444460
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started";
445461

446-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
462+
EXPECT_EQ(
463+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
464+
test_controller->get_lifecycle_state().id());
447465

448466
// Start controller, will take effect at the end of the update function
449467
time_ = test_controller->get_node()->now(); // set to something nonzero
@@ -467,7 +485,8 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
467485
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
468486
}
469487

470-
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());
488+
EXPECT_EQ(
489+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state().id());
471490

472491
EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate);
473492
const auto cm_update_rate = cm_->get_update_rate();

0 commit comments

Comments
 (0)