Skip to content

Commit 260bf33

Browse files
committed
adjust tests to reflect changes in handles
1 parent 8e09235 commit 260bf33

13 files changed

+190
-171
lines changed

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 16 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -175,10 +175,12 @@ class TestDiffDriveController : public ::testing::Test
175175
std::shared_ptr<hardware_interface::StateInterface> right_wheel_vel_state_ =
176176
std::make_shared<hardware_interface::StateInterface>(
177177
right_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[1]);
178-
hardware_interface::CommandInterface left_wheel_vel_cmd_{
179-
left_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[0]};
180-
hardware_interface::CommandInterface right_wheel_vel_cmd_{
181-
right_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[1]};
178+
std::shared_ptr<hardware_interface::CommandInterface> left_wheel_vel_cmd_ =
179+
std::make_shared<hardware_interface::CommandInterface>(
180+
left_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[0]);
181+
std::shared_ptr<hardware_interface::CommandInterface> right_wheel_vel_cmd_ =
182+
std::make_shared<hardware_interface::CommandInterface>(
183+
right_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[1]);
182184

183185
rclcpp::Node::SharedPtr pub_node;
184186
rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr velocity_publisher;
@@ -372,8 +374,8 @@ TEST_F(TestDiffDriveController, cleanup)
372374
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
373375

374376
// should be stopped
375-
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value());
376-
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value());
377+
EXPECT_EQ(0.0, left_wheel_vel_cmd_->get_value());
378+
EXPECT_EQ(0.0, right_wheel_vel_cmd_->get_value());
377379

378380
executor.cancel();
379381
}
@@ -397,8 +399,8 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
397399
assignResourcesPosFeedback();
398400

399401
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
400-
EXPECT_EQ(0.01, left_wheel_vel_cmd_.get_value());
401-
EXPECT_EQ(0.02, right_wheel_vel_cmd_.get_value());
402+
EXPECT_EQ(0.01, left_wheel_vel_cmd_->get_value());
403+
EXPECT_EQ(0.02, right_wheel_vel_cmd_->get_value());
402404

403405
state = controller_->get_node()->activate();
404406
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
@@ -413,8 +415,8 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
413415
ASSERT_EQ(
414416
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
415417
controller_interface::return_type::OK);
416-
EXPECT_EQ(1.0, left_wheel_vel_cmd_.get_value());
417-
EXPECT_EQ(1.0, right_wheel_vel_cmd_.get_value());
418+
EXPECT_EQ(1.0, left_wheel_vel_cmd_->get_value());
419+
EXPECT_EQ(1.0, right_wheel_vel_cmd_->get_value());
418420

419421
// deactivated
420422
// wait so controller process the second point when deactivated
@@ -425,14 +427,14 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
425427
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
426428
controller_interface::return_type::OK);
427429

428-
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()";
429-
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()";
430+
EXPECT_EQ(0.0, left_wheel_vel_cmd_->get_value()) << "Wheels are halted on deactivate()";
431+
EXPECT_EQ(0.0, right_wheel_vel_cmd_->get_value()) << "Wheels are halted on deactivate()";
430432

431433
// cleanup
432434
state = controller_->get_node()->cleanup();
433435
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
434-
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value());
435-
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value());
436+
EXPECT_EQ(0.0, left_wheel_vel_cmd_->get_value());
437+
EXPECT_EQ(0.0, right_wheel_vel_cmd_->get_value());
436438

437439
state = controller_->get_node()->configure();
438440
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());

effort_controllers/test/test_joint_group_effort_controller.cpp

Lines changed: 24 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -119,9 +119,9 @@ TEST_F(JointGroupEffortControllerTest, CommandSuccessTest)
119119
controller_interface::return_type::OK);
120120

121121
// check joint commands are still the default ones
122-
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
123-
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
124-
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
122+
ASSERT_EQ(joint_1_cmd_->get_value(), 1.1);
123+
ASSERT_EQ(joint_2_cmd_->get_value(), 2.1);
124+
ASSERT_EQ(joint_3_cmd_->get_value(), 3.1);
125125

126126
// send command
127127
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
@@ -134,9 +134,9 @@ TEST_F(JointGroupEffortControllerTest, CommandSuccessTest)
134134
controller_interface::return_type::OK);
135135

136136
// check joint commands have been modified
137-
ASSERT_EQ(joint_1_cmd_.get_value(), 10.0);
138-
ASSERT_EQ(joint_2_cmd_.get_value(), 20.0);
139-
ASSERT_EQ(joint_3_cmd_.get_value(), 30.0);
137+
ASSERT_EQ(joint_1_cmd_->get_value(), 10.0);
138+
ASSERT_EQ(joint_2_cmd_->get_value(), 20.0);
139+
ASSERT_EQ(joint_3_cmd_->get_value(), 30.0);
140140
}
141141

142142
TEST_F(JointGroupEffortControllerTest, WrongCommandCheckTest)
@@ -156,9 +156,9 @@ TEST_F(JointGroupEffortControllerTest, WrongCommandCheckTest)
156156
controller_interface::return_type::ERROR);
157157

158158
// check joint commands are still the default ones
159-
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
160-
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
161-
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
159+
ASSERT_EQ(joint_1_cmd_->get_value(), 1.1);
160+
ASSERT_EQ(joint_2_cmd_->get_value(), 2.1);
161+
ASSERT_EQ(joint_3_cmd_->get_value(), 3.1);
162162
}
163163

164164
TEST_F(JointGroupEffortControllerTest, NoCommandCheckTest)
@@ -173,9 +173,9 @@ TEST_F(JointGroupEffortControllerTest, NoCommandCheckTest)
173173
controller_interface::return_type::OK);
174174

175175
// check joint commands are still the default ones
176-
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
177-
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
178-
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
176+
ASSERT_EQ(joint_1_cmd_->get_value(), 1.1);
177+
ASSERT_EQ(joint_2_cmd_->get_value(), 2.1);
178+
ASSERT_EQ(joint_3_cmd_->get_value(), 3.1);
179179
}
180180

181181
TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
@@ -184,9 +184,9 @@ TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
184184
controller_->get_node()->set_parameter({"joints", joint_names_});
185185

186186
// default values
187-
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
188-
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
189-
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
187+
ASSERT_EQ(joint_1_cmd_->get_value(), 1.1);
188+
ASSERT_EQ(joint_2_cmd_->get_value(), 2.1);
189+
ASSERT_EQ(joint_3_cmd_->get_value(), 3.1);
190190

191191
auto node_state = controller_->get_node()->configure();
192192
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
@@ -214,9 +214,9 @@ TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
214214
controller_interface::return_type::OK);
215215

216216
// check command in handle was set
217-
ASSERT_EQ(joint_1_cmd_.get_value(), 10.0);
218-
ASSERT_EQ(joint_2_cmd_.get_value(), 20.0);
219-
ASSERT_EQ(joint_3_cmd_.get_value(), 30.0);
217+
ASSERT_EQ(joint_1_cmd_->get_value(), 10.0);
218+
ASSERT_EQ(joint_2_cmd_->get_value(), 20.0);
219+
ASSERT_EQ(joint_3_cmd_->get_value(), 30.0);
220220
}
221221

222222
TEST_F(JointGroupEffortControllerTest, StopJointsOnDeactivateTest)
@@ -228,15 +228,15 @@ TEST_F(JointGroupEffortControllerTest, StopJointsOnDeactivateTest)
228228
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
229229

230230
// check joint commands are still the default ones
231-
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
232-
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
233-
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
231+
ASSERT_EQ(joint_1_cmd_->get_value(), 1.1);
232+
ASSERT_EQ(joint_2_cmd_->get_value(), 2.1);
233+
ASSERT_EQ(joint_3_cmd_->get_value(), 3.1);
234234

235235
// stop the controller
236236
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
237237

238238
// check joint commands are now zero
239-
ASSERT_EQ(joint_1_cmd_.get_value(), 0.0);
240-
ASSERT_EQ(joint_2_cmd_.get_value(), 0.0);
241-
ASSERT_EQ(joint_3_cmd_.get_value(), 0.0);
239+
ASSERT_EQ(joint_1_cmd_->get_value(), 0.0);
240+
ASSERT_EQ(joint_2_cmd_->get_value(), 0.0);
241+
ASSERT_EQ(joint_3_cmd_->get_value(), 0.0);
242242
}

effort_controllers/test/test_joint_group_effort_controller.hpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,9 +54,12 @@ class JointGroupEffortControllerTest : public ::testing::Test
5454
const std::vector<std::string> joint_names_ = {"joint1", "joint2", "joint3"};
5555
std::vector<double> joint_commands_ = {1.1, 2.1, 3.1};
5656

57-
CommandInterface joint_1_cmd_{joint_names_[0], HW_IF_EFFORT, &joint_commands_[0]};
58-
CommandInterface joint_2_cmd_{joint_names_[1], HW_IF_EFFORT, &joint_commands_[1]};
59-
CommandInterface joint_3_cmd_{joint_names_[2], HW_IF_EFFORT, &joint_commands_[2]};
57+
std::shared_ptr<CommandInterface> joint_1_cmd_ =
58+
std::make_shared<CommandInterface>(joint_names_[0], HW_IF_EFFORT, &joint_commands_[0]);
59+
std::shared_ptr<CommandInterface> joint_2_cmd_ =
60+
std::make_shared<CommandInterface>(joint_names_[1], HW_IF_EFFORT, &joint_commands_[1]);
61+
std::shared_ptr<CommandInterface> joint_3_cmd_ =
62+
std::make_shared<CommandInterface>(joint_names_[2], HW_IF_EFFORT, &joint_commands_[2]);
6063
};
6164

6265
#endif // TEST_JOINT_GROUP_EFFORT_CONTROLLER_HPP_

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 30 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -195,9 +195,9 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
195195
controller_interface::return_type::OK);
196196

197197
// check joint commands are still the default ones
198-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
199-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
200-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
198+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 1.1);
199+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 2.1);
200+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 3.1);
201201

202202
// send command
203203
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
@@ -210,9 +210,9 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
210210
controller_interface::return_type::OK);
211211

212212
// check joint commands have been modified
213-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
214-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20.0);
215-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30.0);
213+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 10.0);
214+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 20.0);
215+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 30.0);
216216
}
217217

218218
TEST_F(ForwardCommandControllerTest, WrongCommandCheckTest)
@@ -238,9 +238,9 @@ TEST_F(ForwardCommandControllerTest, WrongCommandCheckTest)
238238
controller_interface::return_type::ERROR);
239239

240240
// check joint commands are still the default ones
241-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
242-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
243-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
241+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 1.1);
242+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 2.1);
243+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 3.1);
244244
}
245245

246246
TEST_F(ForwardCommandControllerTest, NoCommandCheckTest)
@@ -260,9 +260,9 @@ TEST_F(ForwardCommandControllerTest, NoCommandCheckTest)
260260
controller_interface::return_type::OK);
261261

262262
// check joint commands are still the default ones
263-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
264-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
265-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
263+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 1.1);
264+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 2.1);
265+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 3.1);
266266
}
267267

268268
TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
@@ -273,9 +273,9 @@ TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
273273
controller_->get_node()->set_parameter({"interface_name", "position"});
274274

275275
// default values
276-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
277-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
278-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
276+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 1.1);
277+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 2.1);
278+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 3.1);
279279

280280
auto node_state = controller_->get_node()->configure();
281281
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
@@ -303,9 +303,9 @@ TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
303303
controller_interface::return_type::OK);
304304

305305
// check command in handle was set
306-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
307-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20.0);
308-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30.0);
306+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 10.0);
307+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 20.0);
308+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 30.0);
309309
}
310310

311311
TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
@@ -316,9 +316,9 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
316316
controller_->get_node()->set_parameter({"interface_name", "position"});
317317

318318
// default values
319-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
320-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
321-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
319+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 1.1);
320+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 2.1);
321+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 3.1);
322322

323323
auto node_state = controller_->configure();
324324
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
@@ -337,9 +337,9 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
337337
controller_interface::return_type::OK);
338338

339339
// check command in handle was set
340-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10);
341-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20);
342-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30);
340+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 10);
341+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 20);
342+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 30);
343343

344344
node_state = controller_->get_node()->deactivate();
345345
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
@@ -381,9 +381,9 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
381381
controller_interface::return_type::OK);
382382

383383
// values should not change
384-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10);
385-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20);
386-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30);
384+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 10);
385+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 20);
386+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 30);
387387

388388
// set commands again
389389
controller_->rt_command_ptr_.writeFromNonRT(command_msg);
@@ -394,7 +394,7 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
394394
controller_interface::return_type::OK);
395395

396396
// check command in handle was set
397-
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 5.5);
398-
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 6.6);
399-
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 7.7);
397+
ASSERT_EQ(joint_1_pos_cmd_->get_value(), 5.5);
398+
ASSERT_EQ(joint_2_pos_cmd_->get_value(), 6.6);
399+
ASSERT_EQ(joint_3_pos_cmd_->get_value(), 7.7);
400400
}

forward_command_controller/test/test_forward_command_controller.hpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,9 +66,12 @@ class ForwardCommandControllerTest : public ::testing::Test
6666
const std::vector<std::string> joint_names_ = {"joint1", "joint2", "joint3"};
6767
std::vector<double> joint_commands_ = {1.1, 2.1, 3.1};
6868

69-
CommandInterface joint_1_pos_cmd_{joint_names_[0], HW_IF_POSITION, &joint_commands_[0]};
70-
CommandInterface joint_2_pos_cmd_{joint_names_[1], HW_IF_POSITION, &joint_commands_[1]};
71-
CommandInterface joint_3_pos_cmd_{joint_names_[2], HW_IF_POSITION, &joint_commands_[2]};
69+
std::shared_ptr<CommandInterface> joint_1_pos_cmd_ =
70+
std::make_shared<CommandInterface>(joint_names_[0], HW_IF_POSITION, &joint_commands_[0]);
71+
std::shared_ptr<CommandInterface> joint_2_pos_cmd_ =
72+
std::make_shared<CommandInterface>(joint_names_[1], HW_IF_POSITION, &joint_commands_[1]);
73+
std::shared_ptr<CommandInterface> joint_3_pos_cmd_ =
74+
std::make_shared<CommandInterface>(joint_names_[2], HW_IF_POSITION, &joint_commands_[2]);
7275
};
7376

7477
#endif // TEST_FORWARD_COMMAND_CONTROLLER_HPP_

0 commit comments

Comments
 (0)