-
Notifications
You must be signed in to change notification settings - Fork 366
/
Copy pathdiff_drive_controller.cpp
595 lines (510 loc) · 20 KB
/
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
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
// Copyright 2020 PAL Robotics S.L.
//
// 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.
/*
* Author: Bence Magyar, Enrique Fernández, Manuel Meraz
*/
#include <memory>
#include <queue>
#include <string>
#include <utility>
#include <vector>
#include "diff_drive_controller/diff_drive_controller.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/logging.hpp"
#include "tf2/LinearMath/Quaternion.h"
namespace
{
constexpr auto DEFAULT_COMMAND_TOPIC = "~/cmd_vel";
constexpr auto DEFAULT_COMMAND_OUT_TOPIC = "~/cmd_vel_out";
constexpr auto DEFAULT_ODOMETRY_TOPIC = "~/odom";
constexpr auto DEFAULT_TRANSFORM_TOPIC = "/tf";
} // namespace
namespace diff_drive_controller
{
using namespace std::chrono_literals;
using controller_interface::interface_configuration_type;
using controller_interface::InterfaceConfiguration;
using hardware_interface::HW_IF_POSITION;
using hardware_interface::HW_IF_VELOCITY;
using lifecycle_msgs::msg::State;
DiffDriveController::DiffDriveController() : controller_interface::ControllerInterface() {}
const char * DiffDriveController::feedback_type() const
{
return params_.position_feedback ? HW_IF_POSITION : HW_IF_VELOCITY;
}
controller_interface::CallbackReturn DiffDriveController::on_init()
{
try
{
// Create the parameter listener and get the parameters
param_listener_ = std::make_shared<ParamListener>(get_node());
params_ = param_listener_->get_params();
}
catch (const std::exception & e)
{
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
return controller_interface::CallbackReturn::ERROR;
}
return controller_interface::CallbackReturn::SUCCESS;
}
InterfaceConfiguration DiffDriveController::command_interface_configuration() const
{
std::vector<std::string> conf_names;
for (const auto & joint_name : params_.left_wheel_names)
{
conf_names.push_back(joint_name + "/" + HW_IF_VELOCITY);
}
for (const auto & joint_name : params_.right_wheel_names)
{
conf_names.push_back(joint_name + "/" + HW_IF_VELOCITY);
}
return {interface_configuration_type::INDIVIDUAL, conf_names};
}
InterfaceConfiguration DiffDriveController::state_interface_configuration() const
{
std::vector<std::string> conf_names;
for (const auto & joint_name : params_.left_wheel_names)
{
conf_names.push_back(joint_name + "/" + feedback_type());
}
for (const auto & joint_name : params_.right_wheel_names)
{
conf_names.push_back(joint_name + "/" + feedback_type());
}
return {interface_configuration_type::INDIVIDUAL, conf_names};
}
controller_interface::return_type DiffDriveController::update(
const rclcpp::Time & time, const rclcpp::Duration & period)
{
auto logger = get_node()->get_logger();
if (get_state().id() == State::PRIMARY_STATE_INACTIVE)
{
if (!is_halted)
{
halt();
is_halted = true;
}
return controller_interface::return_type::OK;
}
std::shared_ptr<Twist> last_command_msg;
received_velocity_msg_ptr_.get(last_command_msg);
if (last_command_msg == nullptr)
{
RCLCPP_WARN(logger, "Velocity message received was a nullptr.");
return controller_interface::return_type::ERROR;
}
const auto age_of_last_command = time - last_command_msg->header.stamp;
// Brake if cmd_vel has timeout, override the stored command
if (age_of_last_command > cmd_vel_timeout_)
{
last_command_msg->twist.linear.x = 0.0;
last_command_msg->twist.angular.z = 0.0;
}
// command may be limited further by SpeedLimit,
// without affecting the stored twist command
Twist command = *last_command_msg;
double & linear_command = command.twist.linear.x;
double & angular_command = command.twist.angular.z;
previous_update_timestamp_ = time;
// Apply (possibly new) multipliers:
const double wheel_separation = params_.wheel_separation_multiplier * params_.wheel_separation;
const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius;
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;
if (params_.open_loop)
{
odometry_.updateOpenLoop(linear_command, angular_command, time);
}
else
{
double left_feedback_mean = 0.0;
double right_feedback_mean = 0.0;
for (size_t index = 0; index < static_cast<size_t>(wheels_per_side_); ++index)
{
const double left_feedback = registered_left_wheel_handles_[index].feedback.get().get_value();
const double right_feedback =
registered_right_wheel_handles_[index].feedback.get().get_value();
if (std::isnan(left_feedback) || std::isnan(right_feedback))
{
RCLCPP_ERROR(
logger, "Either the left or right wheel %s is invalid for index [%zu]", feedback_type(),
index);
return controller_interface::return_type::ERROR;
}
left_feedback_mean += left_feedback;
right_feedback_mean += right_feedback;
}
left_feedback_mean /= static_cast<double>(wheels_per_side_);
right_feedback_mean /= static_cast<double>(wheels_per_side_);
if (params_.position_feedback)
{
odometry_.update(left_feedback_mean, right_feedback_mean, time);
}
else
{
odometry_.updateFromVelocity(
left_feedback_mean * left_wheel_radius * period.seconds(),
right_feedback_mean * right_wheel_radius * period.seconds(), time);
}
}
tf2::Quaternion orientation;
orientation.setRPY(0.0, 0.0, odometry_.getHeading());
bool should_publish = false;
try
{
if (previous_publish_timestamp_ + publish_period_ < time)
{
previous_publish_timestamp_ += publish_period_;
should_publish = true;
}
}
catch (const std::runtime_error &)
{
// Handle exceptions when the time source changes and initialize publish timestamp
previous_publish_timestamp_ = time;
should_publish = true;
}
if (should_publish)
{
if (realtime_odometry_publisher_->trylock())
{
auto & odometry_message = realtime_odometry_publisher_->msg_;
odometry_message.header.stamp = time;
odometry_message.pose.pose.position.x = odometry_.getX();
odometry_message.pose.pose.position.y = odometry_.getY();
odometry_message.pose.pose.orientation.x = orientation.x();
odometry_message.pose.pose.orientation.y = orientation.y();
odometry_message.pose.pose.orientation.z = orientation.z();
odometry_message.pose.pose.orientation.w = orientation.w();
odometry_message.twist.twist.linear.x = odometry_.getLinear();
odometry_message.twist.twist.angular.z = odometry_.getAngular();
realtime_odometry_publisher_->unlockAndPublish();
}
if (params_.enable_odom_tf && realtime_odometry_transform_publisher_->trylock())
{
auto & transform = realtime_odometry_transform_publisher_->msg_.transforms.front();
transform.header.stamp = time;
transform.transform.translation.x = odometry_.getX();
transform.transform.translation.y = odometry_.getY();
transform.transform.rotation.x = orientation.x();
transform.transform.rotation.y = orientation.y();
transform.transform.rotation.z = orientation.z();
transform.transform.rotation.w = orientation.w();
realtime_odometry_transform_publisher_->unlockAndPublish();
}
}
auto & last_command = previous_commands_.back().twist;
auto & second_to_last_command = previous_commands_.front().twist;
limiter_linear_.limit(
linear_command, last_command.linear.x, second_to_last_command.linear.x, period.seconds());
limiter_angular_.limit(
angular_command, last_command.angular.z, second_to_last_command.angular.z, period.seconds());
previous_commands_.pop();
previous_commands_.emplace(command);
// Publish limited velocity
if (publish_limited_velocity_ && realtime_limited_velocity_publisher_->trylock())
{
auto & limited_velocity_command = realtime_limited_velocity_publisher_->msg_;
limited_velocity_command.header.stamp = time;
limited_velocity_command.twist = command.twist;
realtime_limited_velocity_publisher_->unlockAndPublish();
}
// Compute wheels velocities:
const double velocity_left =
(linear_command - angular_command * wheel_separation / 2.0) / left_wheel_radius;
const double velocity_right =
(linear_command + angular_command * wheel_separation / 2.0) / right_wheel_radius;
// Set wheels velocities:
for (size_t index = 0; index < static_cast<size_t>(wheels_per_side_); ++index)
{
registered_left_wheel_handles_[index].velocity.get().set_value(velocity_left);
registered_right_wheel_handles_[index].velocity.get().set_value(velocity_right);
}
return controller_interface::return_type::OK;
}
controller_interface::CallbackReturn DiffDriveController::on_configure(
const rclcpp_lifecycle::State &)
{
auto logger = get_node()->get_logger();
// update parameters if they have changed
if (param_listener_->is_old(params_))
{
params_ = param_listener_->get_params();
RCLCPP_INFO(logger, "Parameters were updated");
}
if (params_.left_wheel_names.size() != params_.right_wheel_names.size())
{
RCLCPP_ERROR(
logger, "The number of left wheels [%zu] and the number of right wheels [%zu] are different",
params_.left_wheel_names.size(), params_.right_wheel_names.size());
return controller_interface::CallbackReturn::ERROR;
}
const double wheel_separation = params_.wheel_separation_multiplier * params_.wheel_separation;
const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius;
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;
odometry_.setWheelParams(wheel_separation, left_wheel_radius, right_wheel_radius);
odometry_.setVelocityRollingWindowSize(params_.velocity_rolling_window_size);
cmd_vel_timeout_ = std::chrono::milliseconds{static_cast<int>(params_.cmd_vel_timeout * 1000.0)};
publish_limited_velocity_ = params_.publish_limited_velocity;
limiter_linear_ = SpeedLimiter(
params_.linear.x.has_velocity_limits, params_.linear.x.has_acceleration_limits,
params_.linear.x.has_jerk_limits, params_.linear.x.min_velocity, params_.linear.x.max_velocity,
params_.linear.x.min_acceleration, params_.linear.x.max_acceleration, params_.linear.x.min_jerk,
params_.linear.x.max_jerk);
limiter_angular_ = SpeedLimiter(
params_.angular.z.has_velocity_limits, params_.angular.z.has_acceleration_limits,
params_.angular.z.has_jerk_limits, params_.angular.z.min_velocity,
params_.angular.z.max_velocity, params_.angular.z.min_acceleration,
params_.angular.z.max_acceleration, params_.angular.z.min_jerk, params_.angular.z.max_jerk);
if (!reset())
{
return controller_interface::CallbackReturn::ERROR;
}
// left and right sides are both equal at this point
wheels_per_side_ = static_cast<int>(params_.left_wheel_names.size());
if (publish_limited_velocity_)
{
limited_velocity_publisher_ =
get_node()->create_publisher<Twist>(DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS());
realtime_limited_velocity_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<Twist>>(limited_velocity_publisher_);
}
const Twist empty_twist;
received_velocity_msg_ptr_.set(std::make_shared<Twist>(empty_twist));
// Fill last two commands with default constructed commands
previous_commands_.emplace(empty_twist);
previous_commands_.emplace(empty_twist);
// initialize command subscriber
velocity_command_subscriber_ = get_node()->create_subscription<Twist>(
DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS(),
[this](const std::shared_ptr<Twist> msg) -> void
{
if (!subscriber_is_active_)
{
RCLCPP_WARN(get_node()->get_logger(), "Can't accept new commands. subscriber is inactive");
return;
}
if ((msg->header.stamp.sec == 0) && (msg->header.stamp.nanosec == 0))
{
RCLCPP_WARN_ONCE(
get_node()->get_logger(),
"Received TwistStamped with zero timestamp, setting it to current "
"time, this message will only be shown once");
msg->header.stamp = get_node()->get_clock()->now();
}
received_velocity_msg_ptr_.set(std::move(msg));
});
// initialize odometry publisher and messasge
odometry_publisher_ = get_node()->create_publisher<nav_msgs::msg::Odometry>(
DEFAULT_ODOMETRY_TOPIC, rclcpp::SystemDefaultsQoS());
realtime_odometry_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>(
odometry_publisher_);
// Append the tf prefix if there is one
std::string tf_prefix = "";
if (params_.tf_frame_prefix_enable)
{
if (params_.tf_frame_prefix != "")
{
tf_prefix = params_.tf_frame_prefix;
}
else
{
tf_prefix = std::string(get_node()->get_namespace());
}
if (tf_prefix == "/")
{
tf_prefix = "";
}
else
{
tf_prefix = tf_prefix + "/";
}
}
const auto odom_frame_id = tf_prefix + params_.odom_frame_id;
const auto base_frame_id = tf_prefix + params_.base_frame_id;
for (auto & joint_name : params_.left_wheel_names)
{
joint_name = tf_prefix + joint_name;
}
for (auto & joint_name : params_.right_wheel_names)
{
joint_name = tf_prefix + joint_name;
}
auto & odometry_message = realtime_odometry_publisher_->msg_;
odometry_message.header.frame_id = odom_frame_id;
odometry_message.child_frame_id = base_frame_id;
// limit the publication on the topics /odom and /tf
publish_rate_ = params_.publish_rate;
publish_period_ = rclcpp::Duration::from_seconds(1.0 / publish_rate_);
// initialize odom values zeros
odometry_message.twist =
geometry_msgs::msg::TwistWithCovariance(rosidl_runtime_cpp::MessageInitialization::ALL);
constexpr size_t NUM_DIMENSIONS = 6;
for (size_t index = 0; index < 6; ++index)
{
// 0, 7, 14, 21, 28, 35
const size_t diagonal_index = NUM_DIMENSIONS * index + index;
odometry_message.pose.covariance[diagonal_index] = params_.pose_covariance_diagonal[index];
odometry_message.twist.covariance[diagonal_index] = params_.twist_covariance_diagonal[index];
}
// initialize transform publisher and message
odometry_transform_publisher_ = get_node()->create_publisher<tf2_msgs::msg::TFMessage>(
DEFAULT_TRANSFORM_TOPIC, rclcpp::SystemDefaultsQoS());
realtime_odometry_transform_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>(
odometry_transform_publisher_);
// keeping track of odom and base_link transforms only
auto & odometry_transform_message = realtime_odometry_transform_publisher_->msg_;
odometry_transform_message.transforms.resize(1);
odometry_transform_message.transforms.front().header.frame_id = odom_frame_id;
odometry_transform_message.transforms.front().child_frame_id = base_frame_id;
previous_update_timestamp_ = get_node()->get_clock()->now();
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn DiffDriveController::on_activate(
const rclcpp_lifecycle::State &)
{
const auto left_result =
configure_side("left", params_.left_wheel_names, registered_left_wheel_handles_);
const auto right_result =
configure_side("right", params_.right_wheel_names, registered_right_wheel_handles_);
if (
left_result == controller_interface::CallbackReturn::ERROR ||
right_result == controller_interface::CallbackReturn::ERROR)
{
return controller_interface::CallbackReturn::ERROR;
}
if (registered_left_wheel_handles_.empty() || registered_right_wheel_handles_.empty())
{
RCLCPP_ERROR(
get_node()->get_logger(),
"Either left wheel interfaces, right wheel interfaces are non existent");
return controller_interface::CallbackReturn::ERROR;
}
is_halted = false;
subscriber_is_active_ = true;
RCLCPP_DEBUG(get_node()->get_logger(), "Subscriber and publisher are now active.");
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn DiffDriveController::on_deactivate(
const rclcpp_lifecycle::State &)
{
subscriber_is_active_ = false;
if (!is_halted)
{
halt();
is_halted = true;
}
registered_left_wheel_handles_.clear();
registered_right_wheel_handles_.clear();
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn DiffDriveController::on_cleanup(
const rclcpp_lifecycle::State &)
{
if (!reset())
{
return controller_interface::CallbackReturn::ERROR;
}
received_velocity_msg_ptr_.set(std::make_shared<Twist>());
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn DiffDriveController::on_error(const rclcpp_lifecycle::State &)
{
if (!reset())
{
return controller_interface::CallbackReturn::ERROR;
}
return controller_interface::CallbackReturn::SUCCESS;
}
bool DiffDriveController::reset()
{
odometry_.resetOdometry();
// release the old queue
std::queue<Twist> empty;
std::swap(previous_commands_, empty);
registered_left_wheel_handles_.clear();
registered_right_wheel_handles_.clear();
subscriber_is_active_ = false;
velocity_command_subscriber_.reset();
received_velocity_msg_ptr_.set(nullptr);
is_halted = false;
return true;
}
controller_interface::CallbackReturn DiffDriveController::on_shutdown(
const rclcpp_lifecycle::State &)
{
return controller_interface::CallbackReturn::SUCCESS;
}
void DiffDriveController::halt()
{
const auto halt_wheels = [](auto & wheel_handles)
{
for (const auto & wheel_handle : wheel_handles)
{
wheel_handle.velocity.get().set_value(0.0);
}
};
halt_wheels(registered_left_wheel_handles_);
halt_wheels(registered_right_wheel_handles_);
}
controller_interface::CallbackReturn DiffDriveController::configure_side(
const std::string & side, const std::vector<std::string> & wheel_names,
std::vector<WheelHandle> & registered_handles)
{
auto logger = get_node()->get_logger();
if (wheel_names.empty())
{
RCLCPP_ERROR(logger, "No '%s' wheel names specified", side.c_str());
return controller_interface::CallbackReturn::ERROR;
}
// register handles
registered_handles.reserve(wheel_names.size());
for (const auto & wheel_name : wheel_names)
{
const auto interface_name = feedback_type();
const auto state_handle = std::find_if(
state_interfaces_.cbegin(), state_interfaces_.cend(),
[&wheel_name, &interface_name](const auto & interface)
{
return interface.get_prefix_name() == wheel_name &&
interface.get_interface_name() == interface_name;
});
if (state_handle == state_interfaces_.cend())
{
RCLCPP_ERROR(logger, "Unable to obtain joint state handle for %s", wheel_name.c_str());
return controller_interface::CallbackReturn::ERROR;
}
const auto command_handle = std::find_if(
command_interfaces_.begin(), command_interfaces_.end(),
[&wheel_name](const auto & interface)
{
return interface.get_prefix_name() == wheel_name &&
interface.get_interface_name() == HW_IF_VELOCITY;
});
if (command_handle == command_interfaces_.end())
{
RCLCPP_ERROR(logger, "Unable to obtain joint command handle for %s", wheel_name.c_str());
return controller_interface::CallbackReturn::ERROR;
}
registered_handles.emplace_back(
WheelHandle{std::ref(*state_handle), std::ref(*command_handle)});
}
return controller_interface::CallbackReturn::SUCCESS;
}
} // namespace diff_drive_controller
#include "class_loader/register_macro.hpp"
CLASS_LOADER_REGISTER_CLASS(
diff_drive_controller::DiffDriveController, controller_interface::ControllerInterface)