Skip to content

Commit 7187083

Browse files
authored
Migrate from deprecated controller_interface::return_type::SUCCESS -> OK (#167)
1 parent fee6d15 commit 7187083

15 files changed

+58
-58
lines changed

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ DiffDriveController::init(const std::string & controller_name)
5454
{
5555
// initialize lifecycle node
5656
auto ret = ControllerInterface::init(controller_name);
57-
if (ret != controller_interface::return_type::SUCCESS) {
57+
if (ret != controller_interface::return_type::OK) {
5858
return ret;
5959
}
6060

@@ -113,7 +113,7 @@ DiffDriveController::init(const std::string & controller_name)
113113
return controller_interface::return_type::ERROR;
114114
}
115115

116-
return controller_interface::return_type::SUCCESS;
116+
return controller_interface::return_type::OK;
117117
}
118118

119119
InterfaceConfiguration DiffDriveController::command_interface_configuration() const
@@ -149,7 +149,7 @@ controller_interface::return_type DiffDriveController::update()
149149
halt();
150150
is_halted = true;
151151
}
152-
return controller_interface::return_type::SUCCESS;
152+
return controller_interface::return_type::OK;
153153
}
154154

155155
const auto current_time = node_->get_clock()->now();
@@ -271,7 +271,7 @@ controller_interface::return_type DiffDriveController::update()
271271
registered_right_wheel_handles_[index].velocity.get().set_value(velocity_right);
272272
}
273273

274-
return controller_interface::return_type::SUCCESS;
274+
return controller_interface::return_type::OK;
275275
}
276276

277277
CallbackReturn DiffDriveController::on_configure(const rclcpp_lifecycle::State &)

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -171,15 +171,15 @@ class TestDiffDriveController : public ::testing::Test
171171
TEST_F(TestDiffDriveController, configure_fails_without_parameters)
172172
{
173173
const auto ret = controller_->init(controller_name);
174-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
174+
ASSERT_EQ(ret, controller_interface::return_type::OK);
175175

176176
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
177177
}
178178

179179
TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_side_defined)
180180
{
181181
const auto ret = controller_->init(controller_name);
182-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
182+
ASSERT_EQ(ret, controller_interface::return_type::OK);
183183

184184
controller_->get_node()->set_parameter(
185185
rclcpp::Parameter(
@@ -207,7 +207,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_sid
207207
TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size)
208208
{
209209
const auto ret = controller_->init(controller_name);
210-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
210+
ASSERT_EQ(ret, controller_interface::return_type::OK);
211211

212212
controller_->get_node()->set_parameter(
213213
rclcpp::Parameter(
@@ -227,7 +227,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size
227227
TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)
228228
{
229229
const auto ret = controller_->init(controller_name);
230-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
230+
ASSERT_EQ(ret, controller_interface::return_type::OK);
231231

232232
controller_->get_node()->set_parameter(
233233
rclcpp::Parameter(
@@ -251,7 +251,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)
251251
TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)
252252
{
253253
const auto ret = controller_->init(controller_name);
254-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
254+
ASSERT_EQ(ret, controller_interface::return_type::OK);
255255

256256
controller_->get_node()->set_parameter(
257257
rclcpp::Parameter(
@@ -270,7 +270,7 @@ TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)
270270
TEST_F(TestDiffDriveController, activate_succeeds_with_resources_assigned)
271271
{
272272
const auto ret = controller_->init(controller_name);
273-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
273+
ASSERT_EQ(ret, controller_interface::return_type::OK);
274274

275275
controller_->get_node()->set_parameter(
276276
rclcpp::Parameter(
@@ -290,7 +290,7 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_resources_assigned)
290290
TEST_F(TestDiffDriveController, cleanup)
291291
{
292292
const auto ret = controller_->init(controller_name);
293-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
293+
ASSERT_EQ(ret, controller_interface::return_type::OK);
294294

295295
controller_->get_node()->set_parameter(
296296
rclcpp::Parameter(
@@ -320,11 +320,11 @@ TEST_F(TestDiffDriveController, cleanup)
320320
publish(linear, angular);
321321
controller_->wait_for_twist(executor);
322322

323-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
323+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
324324

325325
state = controller_->deactivate();
326326
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
327-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
327+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
328328

329329
state = controller_->cleanup();
330330
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
@@ -339,7 +339,7 @@ TEST_F(TestDiffDriveController, cleanup)
339339
TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
340340
{
341341
const auto ret = controller_->init(controller_name);
342-
ASSERT_EQ(ret, controller_interface::return_type::SUCCESS);
342+
ASSERT_EQ(ret, controller_interface::return_type::OK);
343343

344344
controller_->get_node()->set_parameter(
345345
rclcpp::Parameter(
@@ -372,7 +372,7 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
372372
// wait for msg is be published to the system
373373
ASSERT_TRUE(controller_->wait_for_twist(executor));
374374

375-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
375+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
376376
EXPECT_EQ(1.0, left_wheel_vel_cmd_.get_value());
377377
EXPECT_EQ(1.0, right_wheel_vel_cmd_.get_value());
378378

@@ -381,7 +381,7 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
381381
std::this_thread::sleep_for(std::chrono::milliseconds(500));
382382
state = controller_->deactivate();
383383
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
384-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
384+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
385385

386386
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()";
387387
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()";

effort_controllers/src/joint_group_effort_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ JointGroupEffortController::init(
3535
const std::string & controller_name)
3636
{
3737
auto ret = ForwardCommandController::init(controller_name);
38-
if (ret != controller_interface::return_type::SUCCESS) {
38+
if (ret != controller_interface::return_type::OK) {
3939
return ret;
4040
}
4141

@@ -47,7 +47,7 @@ JointGroupEffortController::init(
4747
return controller_interface::return_type::ERROR;
4848
}
4949

50-
return controller_interface::return_type::SUCCESS;
50+
return controller_interface::return_type::OK;
5151
}
5252

5353
CallbackReturn JointGroupEffortController::on_deactivate(

effort_controllers/test/test_joint_group_effort_controller.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ void JointGroupEffortControllerTest::TearDown()
6464
void JointGroupEffortControllerTest::SetUpController()
6565
{
6666
const auto result = controller_->init("group_effort_controller");
67-
ASSERT_EQ(result, controller_interface::return_type::SUCCESS);
67+
ASSERT_EQ(result, controller_interface::return_type::OK);
6868

6969
std::vector<LoanedCommandInterface> command_ifs;
7070
command_ifs.emplace_back(joint_1_cmd_);
@@ -123,7 +123,7 @@ TEST_F(JointGroupEffortControllerTest, CommandSuccessTest)
123123
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
124124

125125
// update successful though no command has been send yet
126-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
126+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
127127

128128
// check joint commands are still the default ones
129129
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
@@ -137,7 +137,7 @@ TEST_F(JointGroupEffortControllerTest, CommandSuccessTest)
137137
controller_->rt_command_ptr_.writeFromNonRT(command_ptr);
138138

139139
// update successful, command received
140-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
140+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
141141

142142
// check joint commands have been modified
143143
ASSERT_EQ(joint_1_cmd_.get_value(), 10.0);
@@ -173,7 +173,7 @@ TEST_F(JointGroupEffortControllerTest, NoCommandCheckTest)
173173
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
174174

175175
// update successful, no command received yet
176-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
176+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
177177

178178
// check joint commands are still the default ones
179179
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
@@ -213,7 +213,7 @@ TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
213213
rclcpp::spin_some(controller_->get_node()->get_node_base_interface());
214214

215215
// update successful
216-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
216+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
217217

218218
// check command in handle was set
219219
ASSERT_EQ(joint_1_cmd_.get_value(), 10.0);

forward_command_controller/src/forward_command_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ controller_interface::return_type
3838
ForwardCommandController::init(const std::string & controller_name)
3939
{
4040
auto ret = ControllerInterface::init(controller_name);
41-
if (ret != controller_interface::return_type::SUCCESS) {
41+
if (ret != controller_interface::return_type::OK) {
4242
return ret;
4343
}
4444

@@ -52,7 +52,7 @@ ForwardCommandController::init(const std::string & controller_name)
5252
return controller_interface::return_type::ERROR;
5353
}
5454

55-
return controller_interface::return_type::SUCCESS;
55+
return controller_interface::return_type::OK;
5656
}
5757

5858
CallbackReturn ForwardCommandController::on_configure(
@@ -158,7 +158,7 @@ controller_interface::return_type ForwardCommandController::update()
158158

159159
// no command received yet
160160
if (!joint_commands || !(*joint_commands)) {
161-
return controller_interface::return_type::SUCCESS;
161+
return controller_interface::return_type::OK;
162162
}
163163

164164
if ((*joint_commands)->data.size() != command_interfaces_.size()) {
@@ -175,7 +175,7 @@ controller_interface::return_type ForwardCommandController::update()
175175
command_interfaces_[index].set_value((*joint_commands)->data[index]);
176176
}
177177

178-
return controller_interface::return_type::SUCCESS;
178+
return controller_interface::return_type::OK;
179179
}
180180

181181
} // namespace forward_command_controller

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ void ForwardCommandControllerTest::TearDown()
7272
void ForwardCommandControllerTest::SetUpController()
7373
{
7474
const auto result = controller_->init("forward_command_controller");
75-
ASSERT_EQ(result, controller_interface::return_type::SUCCESS);
75+
ASSERT_EQ(result, controller_interface::return_type::OK);
7676

7777
std::vector<LoanedCommandInterface> command_ifs;
7878
command_ifs.emplace_back(joint_1_pos_cmd_);
@@ -187,7 +187,7 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
187187
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
188188

189189
// update successful though no command has been send yet
190-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
190+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
191191

192192
// check joint commands are still the default ones
193193
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
@@ -201,7 +201,7 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
201201
controller_->rt_command_ptr_.writeFromNonRT(command_ptr);
202202

203203
// update successful, command received
204-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
204+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
205205

206206
// check joint commands have been modified
207207
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
@@ -244,7 +244,7 @@ TEST_F(ForwardCommandControllerTest, NoCommandCheckTest)
244244
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
245245

246246
// update successful, no command received yet
247-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
247+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
248248

249249
// check joint commands are still the default ones
250250
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
@@ -286,7 +286,7 @@ TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
286286
rclcpp::spin_some(controller_->get_node()->get_node_base_interface());
287287

288288
// update successful
289-
ASSERT_EQ(controller_->update(), controller_interface::return_type::SUCCESS);
289+
ASSERT_EQ(controller_->update(), controller_interface::return_type::OK);
290290

291291
// check command in handle was set
292292
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);

joint_state_broadcaster/src/joint_state_broadcaster.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -226,7 +226,7 @@ JointStateBroadcaster::update()
226226
joint_state_publisher_->publish(joint_state_msg_);
227227
dynamic_joint_state_publisher_->publish(dynamic_joint_state_msg_);
228228

229-
return controller_interface::return_type::SUCCESS;
229+
return controller_interface::return_type::OK;
230230
}
231231

232232
} // namespace joint_state_broadcaster

joint_state_broadcaster/test/test_joint_state_broadcaster.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ void JointStateBroadcasterTest::TearDown()
8282
void JointStateBroadcasterTest::SetUpStateBroadcaster()
8383
{
8484
const auto result = state_broadcaster_->init("joint_state_broadcaster");
85-
ASSERT_EQ(result, controller_interface::return_type::SUCCESS);
85+
ASSERT_EQ(result, controller_interface::return_type::OK);
8686

8787
std::vector<LoanedStateInterface> state_ifs;
8888
state_ifs.emplace_back(joint_1_pos_state_);
@@ -195,7 +195,7 @@ TEST_F(JointStateBroadcasterTest, UpdateTest)
195195
auto node_state = state_broadcaster_->configure();
196196
node_state = state_broadcaster_->activate();
197197
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
198-
ASSERT_EQ(state_broadcaster_->update(), controller_interface::return_type::SUCCESS);
198+
ASSERT_EQ(state_broadcaster_->update(), controller_interface::return_type::OK);
199199
}
200200

201201
TEST_F(JointStateBroadcasterTest, JointStatePublishTest)
@@ -217,7 +217,7 @@ TEST_F(JointStateBroadcasterTest, JointStatePublishTest)
217217
10,
218218
subs_callback);
219219

220-
ASSERT_EQ(state_broadcaster_->update(), controller_interface::return_type::SUCCESS);
220+
ASSERT_EQ(state_broadcaster_->update(), controller_interface::return_type::OK);
221221

222222
// wait for message to be passed
223223
ASSERT_EQ(wait_for(subscription), rclcpp::WaitResultKind::Ready);
@@ -257,7 +257,7 @@ TEST_F(JointStateBroadcasterTest, DynamicJointStatePublishTest)
257257
10,
258258
subs_callback);
259259

260-
ASSERT_EQ(state_broadcaster_->update(), controller_interface::return_type::SUCCESS);
260+
ASSERT_EQ(state_broadcaster_->update(), controller_interface::return_type::OK);
261261

262262
// wait for message to be passed
263263
ASSERT_EQ(wait_for(subscription), rclcpp::WaitResultKind::Ready);

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ JointTrajectoryController::init(const std::string & controller_name)
5858
{
5959
// initialize lifecycle node
6060
const auto ret = ControllerInterface::init(controller_name);
61-
if (ret != controller_interface::return_type::SUCCESS) {
61+
if (ret != controller_interface::return_type::OK) {
6262
return ret;
6363
}
6464

@@ -70,7 +70,7 @@ JointTrajectoryController::init(const std::string & controller_name)
7070
node_->declare_parameter<double>("constraints.stopped_velocity_tolerance", 0.01);
7171
node_->declare_parameter<double>("constraints.goal_time", 0.0);
7272

73-
return controller_interface::return_type::SUCCESS;
73+
return controller_interface::return_type::OK;
7474
}
7575

7676
controller_interface::InterfaceConfiguration JointTrajectoryController::
@@ -106,7 +106,7 @@ JointTrajectoryController::update()
106106
halt();
107107
is_halted = true;
108108
}
109-
return controller_interface::return_type::SUCCESS;
109+
return controller_interface::return_type::OK;
110110
}
111111

112112
auto resize_joint_trajectory_point =
@@ -250,7 +250,7 @@ JointTrajectoryController::update()
250250
}
251251

252252
publish_state(state_desired, state_current, state_error);
253-
return controller_interface::return_type::SUCCESS;
253+
return controller_interface::return_type::OK;
254254
}
255255

256256
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,7 @@ TEST_F(TestTrajectoryController, configuration) {
9595
// auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>(
9696
// joint_names_, op_mode_);
9797
// auto ret = traj_controller->init(test_robot_, controller_name_);
98-
// if (ret != controller_interface::return_type::SUCCESS) {
98+
// if (ret != controller_interface::return_type::OK) {
9999
// FAIL();
100100
// }
101101
//
@@ -137,7 +137,7 @@ TEST_F(TestTrajectoryController, configuration) {
137137
// auto traj_controller = std::make_shared<ros_controllers::JointTrajectoryController>(
138138
// joint_names_, op_mode_);
139139
// auto ret = traj_controller->init(test_robot_, controller_name_);
140-
// if (ret != controller_interface::return_type::SUCCESS) {
140+
// if (ret != controller_interface::return_type::OK) {
141141
// FAIL();
142142
// }
143143
//

0 commit comments

Comments
 (0)