-
Notifications
You must be signed in to change notification settings - Fork 277
/
Copy pathDiffDrive.cc
682 lines (577 loc) · 21 KB
/
DiffDrive.cc
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
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
/*
* Copyright (C) 2018 Open Source Robotics Foundation
*
* 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 "DiffDrive.hh"
#include <ignition/msgs/odometry.pb.h>
#include <limits>
#include <mutex>
#include <set>
#include <string>
#include <vector>
#include <ignition/common/Profiler.hh>
#include <ignition/math/DiffDriveOdometry.hh>
#include <ignition/math/Quaternion.hh>
#include <ignition/math/SpeedLimiter.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/transport/Node.hh>
#include "ignition/gazebo/components/CanonicalLink.hh"
#include "ignition/gazebo/components/JointPosition.hh"
#include "ignition/gazebo/components/JointVelocityCmd.hh"
#include "ignition/gazebo/Link.hh"
#include "ignition/gazebo/Model.hh"
#include "ignition/gazebo/Util.hh"
using namespace ignition;
using namespace gazebo;
using namespace systems;
/// \brief Velocity command.
struct Commands
{
/// \brief Linear velocity.
double lin;
/// \brief Angular velocity.
double ang;
Commands() : lin(0.0), ang(0.0) {}
};
class ignition::gazebo::systems::DiffDrivePrivate
{
/// \brief Callback for velocity subscription
/// \param[in] _msg Velocity message
public: void OnCmdVel(const ignition::msgs::Twist &_msg);
/// \brief Callback for enable/disable subscription
/// \param[in] _msg Boolean message
public: void OnEnable(const ignition::msgs::Boolean &_msg);
/// \brief Update odometry and publish an odometry message.
/// \param[in] _info System update information.
/// \param[in] _ecm The EntityComponentManager of the given simulation
/// instance.
public: void UpdateOdometry(const ignition::gazebo::UpdateInfo &_info,
const ignition::gazebo::EntityComponentManager &_ecm);
/// \brief Update the linear and angular velocities.
/// \param[in] _info System update information.
/// \param[in] _ecm The EntityComponentManager of the given simulation
/// instance.
public: void UpdateVelocity(const ignition::gazebo::UpdateInfo &_info,
const ignition::gazebo::EntityComponentManager &_ecm);
/// \brief Ignition communication node.
public: transport::Node node;
/// \brief Entity of the left joint
public: std::vector<Entity> leftJoints;
/// \brief Entity of the right joint
public: std::vector<Entity> rightJoints;
/// \brief Name of left joint
public: std::vector<std::string> leftJointNames;
/// \brief Name of right joint
public: std::vector<std::string> rightJointNames;
/// \brief Calculated speed of left joint
public: double leftJointSpeed{0};
/// \brief Calculated speed of right joint
public: double rightJointSpeed{0};
/// \brief Distance between wheels
public: double wheelSeparation{1.0};
/// \brief Wheel radius
public: double wheelRadius{0.2};
/// \brief Model interface
public: Model model{kNullEntity};
/// \brief The model's canonical link.
public: Link canonicalLink{kNullEntity};
/// \brief Update period calculated from <odom__publish_frequency>.
public: std::chrono::steady_clock::duration odomPubPeriod{0};
/// \brief Last sim time odom was published.
public: std::chrono::steady_clock::duration lastOdomPubTime{0};
/// \brief Diff drive odometry.
public: math::DiffDriveOdometry odom;
/// \brief Diff drive odometry message publisher.
public: transport::Node::Publisher odomPub;
/// \brief Diff drive tf message publisher.
public: transport::Node::Publisher tfPub;
/// \brief Linear velocity limiter.
public: std::unique_ptr<ignition::math::SpeedLimiter> limiterLin;
/// \brief Angular velocity limiter.
public: std::unique_ptr<ignition::math::SpeedLimiter> limiterAng;
/// \brief Previous control command.
public: Commands last0Cmd;
/// \brief Previous control command to last0Cmd.
public: Commands last1Cmd;
/// \brief Last target velocity requested.
public: msgs::Twist targetVel;
/// \brief Enable/disable state of the controller.
public: bool enabled;
/// \brief A mutex to protect the target velocity command.
public: std::mutex mutex;
/// \brief frame_id from sdf.
public: std::string sdfFrameId;
/// \brief child_frame_id from sdf.
public: std::string sdfChildFrameId;
};
//////////////////////////////////////////////////
DiffDrive::DiffDrive()
: dataPtr(std::make_unique<DiffDrivePrivate>())
{
}
//////////////////////////////////////////////////
void DiffDrive::Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &/*_eventMgr*/)
{
this->dataPtr->model = Model(_entity);
// Get the canonical link
std::vector<Entity> links = _ecm.ChildrenByComponents(
this->dataPtr->model.Entity(), components::CanonicalLink());
if (!links.empty())
this->dataPtr->canonicalLink = Link(links[0]);
if (!this->dataPtr->model.Valid(_ecm))
{
ignerr << "DiffDrive plugin should be attached to a model entity. "
<< "Failed to initialize." << std::endl;
return;
}
// Ugly, but needed because the sdf::Element::GetElement is not a const
// function and _sdf is a const shared pointer to a const sdf::Element.
auto ptr = const_cast<sdf::Element *>(_sdf.get());
// Get params from SDF
sdf::ElementPtr sdfElem = ptr->GetElement("left_joint");
while (sdfElem)
{
this->dataPtr->leftJointNames.push_back(sdfElem->Get<std::string>());
sdfElem = sdfElem->GetNextElement("left_joint");
}
sdfElem = ptr->GetElement("right_joint");
while (sdfElem)
{
this->dataPtr->rightJointNames.push_back(sdfElem->Get<std::string>());
sdfElem = sdfElem->GetNextElement("right_joint");
}
this->dataPtr->wheelSeparation = _sdf->Get<double>("wheel_separation",
this->dataPtr->wheelSeparation).first;
this->dataPtr->wheelRadius = _sdf->Get<double>("wheel_radius",
this->dataPtr->wheelRadius).first;
// Instantiate the speed limiters.
this->dataPtr->limiterLin = std::make_unique<ignition::math::SpeedLimiter>();
this->dataPtr->limiterAng = std::make_unique<ignition::math::SpeedLimiter>();
// Parse speed limiter parameters.
// Min Velocity
if (_sdf->HasElement("min_velocity"))
{
const double minVel = _sdf->Get<double>("min_velocity");
this->dataPtr->limiterLin->SetMinVelocity(minVel);
this->dataPtr->limiterAng->SetMinVelocity(minVel);
}
if (_sdf->HasElement("min_linear_velocity"))
{
const double minLinVel = _sdf->Get<double>("min_linear_velocity");
this->dataPtr->limiterLin->SetMinVelocity(minLinVel);
}
if (_sdf->HasElement("min_angular_velocity"))
{
const double minAngVel = _sdf->Get<double>("min_angular_velocity");
this->dataPtr->limiterAng->SetMinVelocity(minAngVel);
}
// Max Velocity
if (_sdf->HasElement("max_velocity"))
{
const double maxVel = _sdf->Get<double>("max_velocity");
this->dataPtr->limiterLin->SetMaxVelocity(maxVel);
this->dataPtr->limiterAng->SetMaxVelocity(maxVel);
}
if (_sdf->HasElement("max_linear_velocity"))
{
const double maxLinVel = _sdf->Get<double>("max_linear_velocity");
this->dataPtr->limiterLin->SetMaxVelocity(maxLinVel);
}
if (_sdf->HasElement("max_angular_velocity"))
{
const double maxAngVel = _sdf->Get<double>("max_angular_velocity");
this->dataPtr->limiterAng->SetMaxVelocity(maxAngVel);
}
// Min Acceleration
if (_sdf->HasElement("min_acceleration"))
{
const double minAccel = _sdf->Get<double>("min_acceleration");
this->dataPtr->limiterLin->SetMinAcceleration(minAccel);
this->dataPtr->limiterAng->SetMinAcceleration(minAccel);
}
if (_sdf->HasElement("min_linear_acceleration"))
{
const double minLinAccel = _sdf->Get<double>("min_linear_acceleration");
this->dataPtr->limiterLin->SetMinAcceleration(minLinAccel);
}
if (_sdf->HasElement("min_angular_acceleration"))
{
const double minAngAccel = _sdf->Get<double>("min_angular_acceleration");
this->dataPtr->limiterAng->SetMinAcceleration(minAngAccel);
}
// Max Acceleration
if (_sdf->HasElement("max_acceleration"))
{
const double maxAccel = _sdf->Get<double>("max_acceleration");
this->dataPtr->limiterLin->SetMaxAcceleration(maxAccel);
this->dataPtr->limiterAng->SetMaxAcceleration(maxAccel);
}
if (_sdf->HasElement("max_linear_acceleration"))
{
const double maxLinAccel = _sdf->Get<double>("max_linear_acceleration");
this->dataPtr->limiterLin->SetMaxAcceleration(maxLinAccel);
}
if (_sdf->HasElement("max_angular_acceleration"))
{
const double maxAngAccel = _sdf->Get<double>("max_angular_acceleration");
this->dataPtr->limiterAng->SetMaxAcceleration(maxAngAccel);
}
// Min Jerk
if (_sdf->HasElement("min_jerk"))
{
const double minJerk = _sdf->Get<double>("min_jerk");
this->dataPtr->limiterLin->SetMinJerk(minJerk);
this->dataPtr->limiterAng->SetMinJerk(minJerk);
}
if (_sdf->HasElement("min_linear_jerk"))
{
const double minLinJerk = _sdf->Get<double>("min_linear_jerk");
this->dataPtr->limiterLin->SetMinJerk(minLinJerk);
}
if (_sdf->HasElement("min_angular_jerk"))
{
const double minAngJerk = _sdf->Get<double>("min_angular_jerk");
this->dataPtr->limiterAng->SetMinJerk(minAngJerk);
}
// Max Jerk
if (_sdf->HasElement("max_jerk"))
{
const double maxJerk = _sdf->Get<double>("max_jerk");
this->dataPtr->limiterLin->SetMaxJerk(maxJerk);
this->dataPtr->limiterAng->SetMaxJerk(maxJerk);
}
if (_sdf->HasElement("max_linear_jerk"))
{
const double maxLinJerk = _sdf->Get<double>("max_linear_jerk");
this->dataPtr->limiterLin->SetMaxJerk(maxLinJerk);
}
if (_sdf->HasElement("max_angular_jerk"))
{
const double maxAngJerk = _sdf->Get<double>("max_angular_jerk");
this->dataPtr->limiterAng->SetMaxJerk(maxAngJerk);
}
double odomFreq = _sdf->Get<double>("odom_publish_frequency", 50).first;
if (odomFreq > 0)
{
std::chrono::duration<double> odomPer{1 / odomFreq};
this->dataPtr->odomPubPeriod =
std::chrono::duration_cast<std::chrono::steady_clock::duration>(odomPer);
}
// Setup odometry.
this->dataPtr->odom.SetWheelParams(this->dataPtr->wheelSeparation,
this->dataPtr->wheelRadius, this->dataPtr->wheelRadius);
// Subscribe to commands
std::vector<std::string> topics;
if (_sdf->HasElement("topic"))
{
topics.push_back(_sdf->Get<std::string>("topic"));
}
topics.push_back("/model/" + this->dataPtr->model.Name(_ecm) + "/cmd_vel");
auto topic = validTopic(topics);
this->dataPtr->node.Subscribe(topic, &DiffDrivePrivate::OnCmdVel,
this->dataPtr.get());
// Subscribe to enable/disable
std::vector<std::string> enableTopics;
enableTopics.push_back(
"/model/" + this->dataPtr->model.Name(_ecm) + "/enable");
auto enableTopic = validTopic(enableTopics);
if (!enableTopic.empty())
{
this->dataPtr->node.Subscribe(enableTopic, &DiffDrivePrivate::OnEnable,
this->dataPtr.get());
}
this->dataPtr->enabled = true;
std::vector<std::string> odomTopics;
if (_sdf->HasElement("odom_topic"))
{
odomTopics.push_back(_sdf->Get<std::string>("odom_topic"));
}
odomTopics.push_back("/model/" + this->dataPtr->model.Name(_ecm) +
"/odometry");
auto odomTopic = validTopic(odomTopics);
this->dataPtr->odomPub = this->dataPtr->node.Advertise<msgs::Odometry>(
odomTopic);
std::string tfTopic{"/model/" + this->dataPtr->model.Name(_ecm) +
"/tf"};
if (_sdf->HasElement("tf_topic"))
tfTopic = _sdf->Get<std::string>("tf_topic");
this->dataPtr->tfPub = this->dataPtr->node.Advertise<msgs::Pose_V>(
tfTopic);
if (_sdf->HasElement("frame_id"))
this->dataPtr->sdfFrameId = _sdf->Get<std::string>("frame_id");
if (_sdf->HasElement("child_frame_id"))
this->dataPtr->sdfChildFrameId = _sdf->Get<std::string>("child_frame_id");
ignmsg << "DiffDrive subscribing to twist messages on [" << topic << "]"
<< std::endl;
}
//////////////////////////////////////////////////
void DiffDrive::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
ignition::gazebo::EntityComponentManager &_ecm)
{
IGN_PROFILE("DiffDrive::PreUpdate");
// \TODO(anyone) Support rewind
if (_info.dt < std::chrono::steady_clock::duration::zero())
{
ignwarn << "Detected jump back in time ["
<< std::chrono::duration_cast<std::chrono::seconds>(_info.dt).count()
<< "s]. System may not work properly." << std::endl;
}
// If the joints haven't been identified yet, look for them
static std::set<std::string> warnedModels;
auto modelName = this->dataPtr->model.Name(_ecm);
if (this->dataPtr->leftJoints.empty() ||
this->dataPtr->rightJoints.empty())
{
bool warned{false};
for (const std::string &name : this->dataPtr->leftJointNames)
{
Entity joint = this->dataPtr->model.JointByName(_ecm, name);
if (joint != kNullEntity)
this->dataPtr->leftJoints.push_back(joint);
else if (warnedModels.find(modelName) == warnedModels.end())
{
ignwarn << "Failed to find left joint [" << name << "] for model ["
<< modelName << "]" << std::endl;
warned = true;
}
}
for (const std::string &name : this->dataPtr->rightJointNames)
{
Entity joint = this->dataPtr->model.JointByName(_ecm, name);
if (joint != kNullEntity)
this->dataPtr->rightJoints.push_back(joint);
else if (warnedModels.find(modelName) == warnedModels.end())
{
ignwarn << "Failed to find right joint [" << name << "] for model ["
<< modelName << "]" << std::endl;
warned = true;
}
}
if (warned)
{
warnedModels.insert(modelName);
}
}
if (this->dataPtr->leftJoints.empty() || this->dataPtr->rightJoints.empty())
return;
if (warnedModels.find(modelName) != warnedModels.end())
{
ignmsg << "Found joints for model [" << modelName
<< "], plugin will start working." << std::endl;
warnedModels.erase(modelName);
}
// Nothing left to do if paused.
if (_info.paused)
return;
for (Entity joint : this->dataPtr->leftJoints)
{
// skip this entity if it has been removed
if (!_ecm.HasEntity(joint))
continue;
// Update wheel velocity
auto vel = _ecm.Component<components::JointVelocityCmd>(joint);
if (vel == nullptr)
{
_ecm.CreateComponent(
joint, components::JointVelocityCmd({this->dataPtr->leftJointSpeed}));
}
else
{
*vel = components::JointVelocityCmd({this->dataPtr->leftJointSpeed});
}
}
for (Entity joint : this->dataPtr->rightJoints)
{
// skip this entity if it has been removed
if (!_ecm.HasEntity(joint))
continue;
// Update wheel velocity
auto vel = _ecm.Component<components::JointVelocityCmd>(joint);
if (vel == nullptr)
{
_ecm.CreateComponent(joint,
components::JointVelocityCmd({this->dataPtr->rightJointSpeed}));
}
else
{
*vel = components::JointVelocityCmd({this->dataPtr->rightJointSpeed});
}
}
// Create the left and right side joint position components if they
// don't exist.
auto leftPos = _ecm.Component<components::JointPosition>(
this->dataPtr->leftJoints[0]);
if (!leftPos && _ecm.HasEntity(this->dataPtr->leftJoints[0]))
{
_ecm.CreateComponent(this->dataPtr->leftJoints[0],
components::JointPosition());
}
auto rightPos = _ecm.Component<components::JointPosition>(
this->dataPtr->rightJoints[0]);
if (!rightPos && _ecm.HasEntity(this->dataPtr->rightJoints[0]))
{
_ecm.CreateComponent(this->dataPtr->rightJoints[0],
components::JointPosition());
}
}
//////////////////////////////////////////////////
void DiffDrive::PostUpdate(const UpdateInfo &_info,
const EntityComponentManager &_ecm)
{
IGN_PROFILE("DiffDrive::PostUpdate");
// Nothing left to do if paused.
if (_info.paused)
return;
this->dataPtr->UpdateVelocity(_info, _ecm);
this->dataPtr->UpdateOdometry(_info, _ecm);
}
//////////////////////////////////////////////////
void DiffDrivePrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo &_info,
const ignition::gazebo::EntityComponentManager &_ecm)
{
IGN_PROFILE("DiffDrive::UpdateOdometry");
// Initialize, if not already initialized.
if (!this->odom.Initialized())
{
this->odom.Init(std::chrono::steady_clock::time_point(_info.simTime));
return;
}
if (this->leftJoints.empty() || this->rightJoints.empty())
return;
// Get the first joint positions for the left and right side.
auto leftPos = _ecm.Component<components::JointPosition>(this->leftJoints[0]);
auto rightPos = _ecm.Component<components::JointPosition>(
this->rightJoints[0]);
// Abort if the joints were not found or just created.
if (!leftPos || !rightPos || leftPos->Data().empty() ||
rightPos->Data().empty())
{
return;
}
this->odom.Update(leftPos->Data()[0], rightPos->Data()[0],
std::chrono::steady_clock::time_point(_info.simTime));
// Throttle publishing
auto diff = _info.simTime - this->lastOdomPubTime;
if (diff > std::chrono::steady_clock::duration::zero() &&
diff < this->odomPubPeriod)
{
return;
}
this->lastOdomPubTime = _info.simTime;
// Construct the odometry message and publish it.
msgs::Odometry msg;
msg.mutable_pose()->mutable_position()->set_x(this->odom.X());
msg.mutable_pose()->mutable_position()->set_y(this->odom.Y());
math::Quaterniond orientation(0, 0, *this->odom.Heading());
msgs::Set(msg.mutable_pose()->mutable_orientation(), orientation);
msg.mutable_twist()->mutable_linear()->set_x(this->odom.LinearVelocity());
msg.mutable_twist()->mutable_angular()->set_z(*this->odom.AngularVelocity());
// Set the time stamp in the header
msg.mutable_header()->mutable_stamp()->CopyFrom(
convert<msgs::Time>(_info.simTime));
// Set the frame id.
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
if (this->sdfFrameId.empty())
{
frame->add_value(this->model.Name(_ecm) + "/odom");
}
else
{
frame->add_value(this->sdfFrameId);
}
std::optional<std::string> linkName = this->canonicalLink.Name(_ecm);
if (this->sdfChildFrameId.empty())
{
if (linkName)
{
auto childFrame = msg.mutable_header()->add_data();
childFrame->set_key("child_frame_id");
childFrame->add_value(this->model.Name(_ecm) + "/" + *linkName);
}
}
else
{
auto childFrame = msg.mutable_header()->add_data();
childFrame->set_key("child_frame_id");
childFrame->add_value(this->sdfChildFrameId);
}
// Construct the Pose_V/tf message and publish it.
msgs::Pose_V tfMsg;
ignition::msgs::Pose *tfMsgPose = tfMsg.add_pose();
tfMsgPose->mutable_header()->CopyFrom(*msg.mutable_header());
tfMsgPose->mutable_position()->CopyFrom(msg.mutable_pose()->position());
tfMsgPose->mutable_orientation()->CopyFrom(msg.mutable_pose()->orientation());
// Publish the messages
this->odomPub.Publish(msg);
this->tfPub.Publish(tfMsg);
}
//////////////////////////////////////////////////
void DiffDrivePrivate::UpdateVelocity(const ignition::gazebo::UpdateInfo &_info,
const ignition::gazebo::EntityComponentManager &/*_ecm*/)
{
IGN_PROFILE("DiffDrive::UpdateVelocity");
double linVel;
double angVel;
{
std::lock_guard<std::mutex> lock(this->mutex);
linVel = this->targetVel.linear().x();
angVel = this->targetVel.angular().z();
}
// Limit the target velocity if needed.
this->limiterLin->Limit(
linVel, this->last0Cmd.lin, this->last1Cmd.lin, _info.dt);
this->limiterAng->Limit(
angVel, this->last0Cmd.ang, this->last1Cmd.ang, _info.dt);
// Update history of commands.
this->last1Cmd = last0Cmd;
this->last0Cmd.lin = linVel;
this->last0Cmd.ang = angVel;
// Convert the target velocities to joint velocities.
this->rightJointSpeed =
(linVel + angVel * this->wheelSeparation / 2.0) / this->wheelRadius;
this->leftJointSpeed =
(linVel - angVel * this->wheelSeparation / 2.0) / this->wheelRadius;
}
//////////////////////////////////////////////////
void DiffDrivePrivate::OnCmdVel(const msgs::Twist &_msg)
{
std::lock_guard<std::mutex> lock(this->mutex);
if (this->enabled)
{
this->targetVel = _msg;
}
}
//////////////////////////////////////////////////
void DiffDrivePrivate::OnEnable(const msgs::Boolean &_msg)
{
std::lock_guard<std::mutex> lock(this->mutex);
this->enabled = _msg.data();
if (!this->enabled)
{
math::Vector3d zeroVector{0, 0, 0};
msgs::Set(this->targetVel.mutable_linear(), zeroVector);
msgs::Set(this->targetVel.mutable_angular(), zeroVector);
}
}
IGNITION_ADD_PLUGIN(DiffDrive,
ignition::gazebo::System,
DiffDrive::ISystemConfigure,
DiffDrive::ISystemPreUpdate,
DiffDrive::ISystemPostUpdate)
IGNITION_ADD_PLUGIN_ALIAS(DiffDrive, "ignition::gazebo::systems::DiffDrive")