@@ -346,37 +346,61 @@ void AckermannSteering::Configure(const Entity &_entity,
346
346
{
347
347
const double minVel = _sdf->Get <double >(" min_velocity" );
348
348
this ->dataPtr ->limiterLin ->SetMinVelocity (minVel);
349
- this ->dataPtr ->limiterAng ->SetMinVelocity (minVel);
349
+ }
350
+ if (_sdf->HasElement (" min_angular_velocity" ))
351
+ {
352
+ const double minAngVel = _sdf->Get <double >(" min_angular_velocity" );
353
+ this ->dataPtr ->limiterAng ->SetMinVelocity (minAngVel);
350
354
}
351
355
if (_sdf->HasElement (" max_velocity" ))
352
356
{
353
357
const double maxVel = _sdf->Get <double >(" max_velocity" );
354
358
this ->dataPtr ->limiterLin ->SetMaxVelocity (maxVel);
355
- this ->dataPtr ->limiterAng ->SetMaxVelocity (maxVel);
359
+ }
360
+ if (_sdf->HasElement (" max_angular_velocity" ))
361
+ {
362
+ const double maxAngVel = _sdf->Get <double >(" max_angular_velocity" );
363
+ this ->dataPtr ->limiterAng ->SetMaxVelocity (maxAngVel);
356
364
}
357
365
if (_sdf->HasElement (" min_acceleration" ))
358
366
{
359
367
const double minAccel = _sdf->Get <double >(" min_acceleration" );
360
368
this ->dataPtr ->limiterLin ->SetMinAcceleration (minAccel);
361
- this ->dataPtr ->limiterAng ->SetMinAcceleration (minAccel);
369
+ }
370
+ if (_sdf->HasElement (" min_angular_acceleration" ))
371
+ {
372
+ const double minAngAccel = _sdf->Get <double >(" min_angular_acceleration" );
373
+ this ->dataPtr ->limiterAng ->SetMinAcceleration (minAngAccel);
362
374
}
363
375
if (_sdf->HasElement (" max_acceleration" ))
364
376
{
365
377
const double maxAccel = _sdf->Get <double >(" max_acceleration" );
366
378
this ->dataPtr ->limiterLin ->SetMaxAcceleration (maxAccel);
367
- this ->dataPtr ->limiterAng ->SetMaxAcceleration (maxAccel);
379
+ }
380
+ if (_sdf->HasElement (" max_angular_acceleration" ))
381
+ {
382
+ const double maxAngAccel = _sdf->Get <double >(" max_angular_acceleration" );
383
+ this ->dataPtr ->limiterAng ->SetMaxAcceleration (maxAngAccel);
368
384
}
369
385
if (_sdf->HasElement (" min_jerk" ))
370
386
{
371
387
const double minJerk = _sdf->Get <double >(" min_jerk" );
372
388
this ->dataPtr ->limiterLin ->SetMinJerk (minJerk);
373
- this ->dataPtr ->limiterAng ->SetMinJerk (minJerk);
389
+ }
390
+ if (_sdf->HasElement (" min_angular_jerk" ))
391
+ {
392
+ const double minAngJerk = _sdf->Get <double >(" min_angular_jerk" );
393
+ this ->dataPtr ->limiterAng ->SetMinJerk (minAngJerk);
374
394
}
375
395
if (_sdf->HasElement (" max_jerk" ))
376
396
{
377
397
const double maxJerk = _sdf->Get <double >(" max_jerk" );
378
398
this ->dataPtr ->limiterLin ->SetMaxJerk (maxJerk);
379
- this ->dataPtr ->limiterAng ->SetMaxJerk (maxJerk);
399
+ }
400
+ if (_sdf->HasElement (" max_angular_jerk" ))
401
+ {
402
+ const double maxAngJerk = _sdf->Get <double >(" max_angular_jerk" );
403
+ this ->dataPtr ->limiterAng ->SetMaxJerk (maxAngJerk);
380
404
}
381
405
382
406
if (!this ->dataPtr ->steeringOnly )
0 commit comments