-
Notifications
You must be signed in to change notification settings - Fork 293
/
test_diff_drive_controller.cpp
436 lines (359 loc) · 16.7 KB
/
test_diff_drive_controller.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
// Copyright 2020 PAL Robotics SL.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gmock/gmock.h>
#include <array>
#include <memory>
#include <string>
#include <thread>
#include <utility>
#include <vector>
#include "diff_drive_controller/diff_drive_controller.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/rclcpp.hpp"
using CallbackReturn = controller_interface::CallbackReturn;
using hardware_interface::HW_IF_POSITION;
using hardware_interface::HW_IF_VELOCITY;
using hardware_interface::LoanedCommandInterface;
using hardware_interface::LoanedStateInterface;
using lifecycle_msgs::msg::State;
using testing::SizeIs;
class TestableDiffDriveController : public diff_drive_controller::DiffDriveController
{
public:
using DiffDriveController::DiffDriveController;
std::shared_ptr<geometry_msgs::msg::TwistStamped> getLastReceivedTwist()
{
std::shared_ptr<geometry_msgs::msg::TwistStamped> ret;
received_velocity_msg_ptr_.get(ret);
return ret;
}
/**
* @brief wait_for_twist block until a new twist is received.
* Requires that the executor is not spinned elsewhere between the
* message publication and the call to this function
*
* @return true if new twist msg was received, false if timeout
*/
bool wait_for_twist(
rclcpp::Executor & executor,
const std::chrono::milliseconds & timeout = std::chrono::milliseconds(500))
{
rclcpp::WaitSet wait_set;
wait_set.add_subscription(velocity_command_subscriber_);
if (wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready)
{
executor.spin_some();
return true;
}
return false;
}
};
class TestDiffDriveController : public ::testing::Test
{
protected:
static void SetUpTestCase() { rclcpp::init(0, nullptr); }
void SetUp() override
{
controller_ = std::make_unique<TestableDiffDriveController>();
pub_node = std::make_shared<rclcpp::Node>("velocity_publisher");
velocity_publisher = pub_node->create_publisher<geometry_msgs::msg::TwistStamped>(
controller_name + "/cmd_vel", rclcpp::SystemDefaultsQoS());
}
static void TearDownTestCase() { rclcpp::shutdown(); }
/// Publish velocity msgs
/**
* linear - magnitude of the linear command in the geometry_msgs::twist message
* angular - the magnitude of the angular command in geometry_msgs::twist message
*/
void publish(double linear, double angular)
{
int wait_count = 0;
auto topic = velocity_publisher->get_topic_name();
while (pub_node->count_subscribers(topic) == 0)
{
if (wait_count >= 5)
{
auto error_msg = std::string("publishing to ") + topic + " but no node subscribes to it";
throw std::runtime_error(error_msg);
}
std::this_thread::sleep_for(std::chrono::milliseconds(100));
++wait_count;
}
geometry_msgs::msg::TwistStamped velocity_message;
velocity_message.header.stamp = pub_node->get_clock()->now();
velocity_message.twist.linear.x = linear;
velocity_message.twist.angular.z = angular;
velocity_publisher->publish(velocity_message);
}
/// \brief wait for the subscriber and publisher to completely setup
void waitForSetup()
{
constexpr std::chrono::seconds TIMEOUT{2};
auto clock = pub_node->get_clock();
auto start = clock->now();
while (velocity_publisher->get_subscription_count() <= 0)
{
if ((clock->now() - start) > TIMEOUT)
{
FAIL();
}
rclcpp::spin_some(pub_node);
}
}
void assignResourcesPosFeedback()
{
std::vector<LoanedStateInterface> state_ifs;
state_ifs.emplace_back(left_wheel_pos_state_);
state_ifs.emplace_back(right_wheel_pos_state_);
std::vector<LoanedCommandInterface> command_ifs;
command_ifs.emplace_back(left_wheel_vel_cmd_);
command_ifs.emplace_back(right_wheel_vel_cmd_);
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));
}
void assignResourcesVelFeedback()
{
std::vector<LoanedStateInterface> state_ifs;
state_ifs.emplace_back(left_wheel_vel_state_);
state_ifs.emplace_back(right_wheel_vel_state_);
std::vector<LoanedCommandInterface> command_ifs;
command_ifs.emplace_back(left_wheel_vel_cmd_);
command_ifs.emplace_back(right_wheel_vel_cmd_);
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));
}
const std::string controller_name = "test_diff_drive_controller";
std::unique_ptr<TestableDiffDriveController> controller_;
const std::vector<std::string> left_wheel_names = {"left_wheel_joint"};
const std::vector<std::string> right_wheel_names = {"right_wheel_joint"};
std::vector<double> position_values_ = {0.1, 0.2};
std::vector<double> velocity_values_ = {0.01, 0.02};
hardware_interface::StateInterface left_wheel_pos_state_{
left_wheel_names[0], HW_IF_POSITION, &position_values_[0]};
hardware_interface::StateInterface right_wheel_pos_state_{
right_wheel_names[0], HW_IF_POSITION, &position_values_[1]};
hardware_interface::StateInterface left_wheel_vel_state_{
left_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[0]};
hardware_interface::StateInterface right_wheel_vel_state_{
right_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[1]};
hardware_interface::CommandInterface left_wheel_vel_cmd_{
left_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[0]};
hardware_interface::CommandInterface right_wheel_vel_cmd_{
right_wheel_names[0], HW_IF_VELOCITY, &velocity_values_[1]};
rclcpp::Node::SharedPtr pub_node;
rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr velocity_publisher;
};
TEST_F(TestDiffDriveController, configure_fails_without_parameters)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}
TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_side_defined)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(std::vector<std::string>())));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(std::vector<std::string>())));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}
TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
auto extended_right_wheel_names = right_wheel_names;
extended_right_wheel_names.push_back("extra_wheel");
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(extended_right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}
TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
ASSERT_THAT(
controller_->state_interface_configuration().names,
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
ASSERT_THAT(
controller_->command_interface_configuration().names,
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
}
TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}
TEST_F(TestDiffDriveController, activate_succeeds_with_pos_resources_assigned)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
// We implicitly test that by default position feedback is required
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
assignResourcesPosFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
}
TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("position_feedback", rclcpp::ParameterValue(false)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
assignResourcesVelFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
}
TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("position_feedback", rclcpp::ParameterValue(false)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
assignResourcesPosFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}
TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("position_feedback", rclcpp::ParameterValue(true)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
assignResourcesVelFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}
TEST_F(TestDiffDriveController, cleanup)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheel_separation", 0.4));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheel_radius", 0.1));
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());
auto state = controller_->get_node()->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
assignResourcesPosFeedback();
state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
waitForSetup();
// send msg
const double linear = 1.0;
const double angular = 1.0;
publish(linear, angular);
controller_->wait_for_twist(executor);
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
state = controller_->get_node()->deactivate();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
state = controller_->get_node()->cleanup();
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
// should be stopped
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value());
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value());
executor.cancel();
}
TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
{
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
controller_->get_node()->set_parameter(
rclcpp::Parameter("left_wheel_names", rclcpp::ParameterValue(left_wheel_names)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("right_wheel_names", rclcpp::ParameterValue(right_wheel_names)));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheel_separation", 0.4));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheel_radius", 1.0));
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());
auto state = controller_->get_node()->configure();
assignResourcesPosFeedback();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
EXPECT_EQ(0.01, left_wheel_vel_cmd_.get_value());
EXPECT_EQ(0.02, right_wheel_vel_cmd_.get_value());
state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
// send msg
const double linear = 1.0;
const double angular = 0.0;
publish(linear, angular);
// wait for msg is be published to the system
ASSERT_TRUE(controller_->wait_for_twist(executor));
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
EXPECT_EQ(1.0, left_wheel_vel_cmd_.get_value());
EXPECT_EQ(1.0, right_wheel_vel_cmd_.get_value());
// deactivated
// wait so controller process the second point when deactivated
std::this_thread::sleep_for(std::chrono::milliseconds(500));
state = controller_->get_node()->deactivate();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()";
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()";
// cleanup
state = controller_->get_node()->cleanup();
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value());
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value());
state = controller_->get_node()->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
executor.cancel();
}