@@ -43,14 +43,16 @@ const rclcpp_lifecycle::State & Actuator::initialize(const HardwareInfo & actuat
43
43
switch (impl_->on_init (actuator_info))
44
44
{
45
45
case CallbackReturn::SUCCESS:
46
- impl_->set_state (rclcpp_lifecycle::State (
47
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
48
- lifecycle_state_names::UNCONFIGURED));
46
+ impl_->set_state (
47
+ rclcpp_lifecycle::State (
48
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
49
+ lifecycle_state_names::UNCONFIGURED));
49
50
break ;
50
51
case CallbackReturn::FAILURE:
51
52
case CallbackReturn::ERROR:
52
- impl_->set_state (rclcpp_lifecycle::State (
53
- lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
53
+ impl_->set_state (
54
+ rclcpp_lifecycle::State (
55
+ lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
54
56
break ;
55
57
}
56
58
}
@@ -64,13 +66,15 @@ const rclcpp_lifecycle::State & Actuator::configure()
64
66
switch (impl_->on_configure (impl_->get_state ()))
65
67
{
66
68
case CallbackReturn::SUCCESS:
67
- impl_->set_state (rclcpp_lifecycle::State (
68
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
69
+ impl_->set_state (
70
+ rclcpp_lifecycle::State (
71
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
69
72
break ;
70
73
case CallbackReturn::FAILURE:
71
- impl_->set_state (rclcpp_lifecycle::State (
72
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
73
- lifecycle_state_names::UNCONFIGURED));
74
+ impl_->set_state (
75
+ rclcpp_lifecycle::State (
76
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
77
+ lifecycle_state_names::UNCONFIGURED));
74
78
break ;
75
79
case CallbackReturn::ERROR:
76
80
impl_->set_state (error ());
@@ -87,9 +91,10 @@ const rclcpp_lifecycle::State & Actuator::cleanup()
87
91
switch (impl_->on_cleanup (impl_->get_state ()))
88
92
{
89
93
case CallbackReturn::SUCCESS:
90
- impl_->set_state (rclcpp_lifecycle::State (
91
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
92
- lifecycle_state_names::UNCONFIGURED));
94
+ impl_->set_state (
95
+ rclcpp_lifecycle::State (
96
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
97
+ lifecycle_state_names::UNCONFIGURED));
93
98
break ;
94
99
case CallbackReturn::FAILURE:
95
100
case CallbackReturn::ERROR:
@@ -109,8 +114,9 @@ const rclcpp_lifecycle::State & Actuator::shutdown()
109
114
switch (impl_->on_shutdown (impl_->get_state ()))
110
115
{
111
116
case CallbackReturn::SUCCESS:
112
- impl_->set_state (rclcpp_lifecycle::State (
113
- lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
117
+ impl_->set_state (
118
+ rclcpp_lifecycle::State (
119
+ lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
114
120
break ;
115
121
case CallbackReturn::FAILURE:
116
122
case CallbackReturn::ERROR:
@@ -128,12 +134,14 @@ const rclcpp_lifecycle::State & Actuator::activate()
128
134
switch (impl_->on_activate (impl_->get_state ()))
129
135
{
130
136
case CallbackReturn::SUCCESS:
131
- impl_->set_state (rclcpp_lifecycle::State (
132
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
137
+ impl_->set_state (
138
+ rclcpp_lifecycle::State (
139
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
133
140
break ;
134
141
case CallbackReturn::FAILURE:
135
- impl_->set_state (rclcpp_lifecycle::State (
136
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
142
+ impl_->set_state (
143
+ rclcpp_lifecycle::State (
144
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
137
145
break ;
138
146
case CallbackReturn::ERROR:
139
147
impl_->set_state (error ());
@@ -150,12 +158,14 @@ const rclcpp_lifecycle::State & Actuator::deactivate()
150
158
switch (impl_->on_deactivate (impl_->get_state ()))
151
159
{
152
160
case CallbackReturn::SUCCESS:
153
- impl_->set_state (rclcpp_lifecycle::State (
154
- lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
161
+ impl_->set_state (
162
+ rclcpp_lifecycle::State (
163
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
155
164
break ;
156
165
case CallbackReturn::FAILURE:
157
- impl_->set_state (rclcpp_lifecycle::State (
158
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
166
+ impl_->set_state (
167
+ rclcpp_lifecycle::State (
168
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
159
169
break ;
160
170
case CallbackReturn::ERROR:
161
171
impl_->set_state (error ());
@@ -172,14 +182,16 @@ const rclcpp_lifecycle::State & Actuator::error()
172
182
switch (impl_->on_error (impl_->get_state ()))
173
183
{
174
184
case CallbackReturn::SUCCESS:
175
- impl_->set_state (rclcpp_lifecycle::State (
176
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
177
- lifecycle_state_names::UNCONFIGURED));
185
+ impl_->set_state (
186
+ rclcpp_lifecycle::State (
187
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
188
+ lifecycle_state_names::UNCONFIGURED));
178
189
break ;
179
190
case CallbackReturn::FAILURE:
180
191
case CallbackReturn::ERROR:
181
- impl_->set_state (rclcpp_lifecycle::State (
182
- lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
192
+ impl_->set_state (
193
+ rclcpp_lifecycle::State (
194
+ lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
183
195
break ;
184
196
}
185
197
}
0 commit comments