@@ -123,7 +123,8 @@ namespace diff_drive_controller
123
123
124
124
DiffDriveController::DiffDriveController ()
125
125
: open_loop_(false )
126
- , position_feedback_(true )
126
+ , pose_from_joint_position_(true )
127
+ , twist_from_joint_position_(false )
127
128
, command_struct_()
128
129
, dynamic_params_struct_()
129
130
, wheel_separation_(0.0 )
@@ -184,10 +185,18 @@ namespace diff_drive_controller
184
185
ROS_INFO_STREAM_NAMED (name_, " Odometry will be computed in "
185
186
<< (open_loop_ ? " open" : " close" ) << " loop." );
186
187
187
- controller_nh.param (" position_feedback" , position_feedback_, position_feedback_);
188
- ROS_DEBUG_STREAM_COND_NAMED (!open_loop_, name_,
189
- " Odometry will be computed using the wheel " <<
190
- (position_feedback_ ? " postion" : " velocity" ) << " feedback." );
188
+ controller_nh.param (" pose_from_joint_position" , pose_from_joint_position_, pose_from_joint_position_);
189
+ ROS_INFO_STREAM_COND_NAMED (!open_loop_, name_,
190
+ " Odometry pose will be computed using the wheel joint " <<
191
+ (pose_from_joint_position_ ? " position" : " velocity" ) << " feedback." );
192
+
193
+ controller_nh.param (" twist_from_joint_position" , twist_from_joint_position_, twist_from_joint_position_);
194
+ ROS_INFO_STREAM_COND_NAMED (!open_loop_, name_,
195
+ " Odometry twist will be computed using the wheel joint " <<
196
+ (twist_from_joint_position_ ? " position" : " velocity" ) << " feedback." );
197
+
198
+ use_position_ = pose_from_joint_position_ || twist_from_joint_position_;
199
+ use_velocity_ = !pose_from_joint_position_ || !twist_from_joint_position_;
191
200
192
201
controller_nh.param (" wheel_separation_multiplier" ,
193
202
wheel_separation_multiplier_, wheel_separation_multiplier_);
@@ -303,6 +312,9 @@ namespace diff_drive_controller
303
312
" Measurement Covariance Model params : k_l " << k_l_
304
313
<< " , k_r " << k_r_);
305
314
315
+ dynamic_params_struct_.pose_from_joint_position = pose_from_joint_position_;
316
+ dynamic_params_struct_.twist_from_joint_position = twist_from_joint_position_;
317
+
306
318
dynamic_params_struct_.wheel_separation_multiplier = wheel_separation_multiplier_;
307
319
308
320
dynamic_params_struct_.left_wheel_radius_multiplier = left_wheel_radius_multiplier_;
@@ -449,6 +461,9 @@ namespace diff_drive_controller
449
461
//
450
462
// ...
451
463
// }
464
+ pose_from_joint_position_ = dynamic_params.pose_from_joint_position ;
465
+ twist_from_joint_position_ = dynamic_params.twist_from_joint_position ;
466
+
452
467
wheel_separation_multiplier_ = dynamic_params.wheel_separation_multiplier ;
453
468
left_wheel_radius_multiplier_ = dynamic_params.left_wheel_radius_multiplier ;
454
469
right_wheel_radius_multiplier_ = dynamic_params.right_wheel_radius_multiplier ;
@@ -469,51 +484,44 @@ namespace diff_drive_controller
469
484
odometry_.setMeasCovarianceParams (k_l_, k_r_);
470
485
471
486
// COMPUTE AND PUBLISH ODOMETRY
472
- if (open_loop_)
487
+ // Read wheel joint positions and velocities:
488
+ for (size_t i = 0 ; i < wheel_joints_size_; ++i)
473
489
{
474
- odometry_.updateOpenLoop (last0_cmd_.lin , last0_cmd_.ang , time);
490
+ left_positions_[i] = left_wheel_joints_[i].getPosition ();
491
+ right_positions_[i] = right_wheel_joints_[i].getPosition ();
492
+
493
+ left_velocities_[i] = left_wheel_joints_[i].getVelocity ();
494
+ right_velocities_[i] = right_wheel_joints_[i].getVelocity ();
475
495
}
476
- else
496
+
497
+ // Check for NaNs on wheel joint positions if we're going to use them:
498
+ use_position_ = pose_from_joint_position_ || twist_from_joint_position_;
499
+ use_velocity_ = !pose_from_joint_position_ || !twist_from_joint_position_;
500
+
501
+ if (use_position_)
477
502
{
478
- if (position_feedback_ )
503
+ for ( size_t i = 0 ; i < wheel_joints_size_; ++i )
479
504
{
480
- double left_pos = 0.0 ;
481
- double right_pos = 0.0 ;
482
- for (size_t i = 0 ; i < wheel_joints_size_; ++i)
505
+ if (std::isnan (left_positions_[i]) ||
506
+ std::isnan (right_positions_[i]))
483
507
{
484
- left_positions_[i] = left_wheel_joints_[i].getPosition ();
485
- right_positions_[i] = right_wheel_joints_[i].getPosition ();
486
- if (std::isnan (left_positions_[i]) || std::isnan (right_positions_[i]))
487
- return ;
488
-
489
- left_pos += left_positions_[i];
490
- right_pos += right_positions_[i];
508
+ // @todo add a diagnostic message
509
+ return ;
491
510
}
492
- left_pos /= wheel_joints_size_;
493
- right_pos /= wheel_joints_size_;
494
-
495
- // Estimate linear and angular velocity using joint position information
496
- odometry_.updateCloseLoop (left_pos, right_pos, time);
497
511
}
498
- else
512
+ }
513
+
514
+ // Check for NaNs on wheel joint velocities if we're going to use them:
515
+ if (use_velocity_)
516
+ {
517
+ for (size_t i = 0 ; i < wheel_joints_size_; ++i)
499
518
{
500
- double left_vel = 0.0 ;
501
- double right_vel = 0.0 ;
502
- for (size_t i = 0 ; i < wheel_joints_size_; ++i)
519
+ if (std::isnan (left_velocities_[i]) ||
520
+ std::isnan (right_velocities_[i]))
503
521
{
504
- left_velocities_[i] = left_wheel_joints_[i].getVelocity ();
505
- right_velocities_[i] = right_wheel_joints_[i].getVelocity ();
506
- if (std::isnan (left_velocities_[i]) || std::isnan (right_velocities_[i]))
507
- return ;
508
-
509
- left_vel += left_velocities_[i];
510
- right_vel += right_velocities_[i];
522
+ // @todo add a diagnostic message
523
+ return ;
511
524
}
512
- left_vel /= wheel_joints_size_;
513
- right_vel /= wheel_joints_size_;
514
-
515
- // Estimate linear and angular velocity using joint velocity information
516
- odometry_.updateCloseLoopFromVelocity (left_vel, right_vel, time);
517
525
}
518
526
}
519
527
@@ -547,10 +555,30 @@ namespace diff_drive_controller
547
555
const double left_velocity_estimated_average = std::accumulate (left_velocities_estimated_.begin (), left_velocities_estimated_.end (), 0.0 ) / wheel_joints_size_;
548
556
const double right_velocity_estimated_average = std::accumulate (right_velocities_estimated_.begin (), right_velocities_estimated_.end (), 0.0 ) / wheel_joints_size_;
549
557
558
+ // Set the wheel joint position that will be used to compute the pose:
559
+ const double left_position = pose_from_joint_position_ ? left_position_average : left_position_estimated_average;
560
+ const double right_position = pose_from_joint_position_ ? right_position_average : right_position_estimated_average;
561
+
562
+ // Set the wheel joint velocity that will be used to compute the twist:
563
+ const double left_velocity = twist_from_joint_position_ ? left_velocity_estimated_average : left_velocity_average;
564
+ const double right_velocity = twist_from_joint_position_ ? right_velocity_estimated_average : right_velocity_average;
565
+
566
+ // Update odometry:
567
+ if (open_loop_)
568
+ {
569
+ odometry_.updateOpenLoop (last0_cmd_.lin , last0_cmd_.ang , time);
570
+ }
571
+ else
572
+ {
573
+ odometry_.updateCloseLoop (left_position, right_position, left_velocity, right_velocity, time);
574
+ }
575
+
550
576
// Publish odometry message
551
577
const ros::Duration half_period (0.5 * period.toSec ());
552
578
if (last_odom_publish_time_ + publish_period_ < time + half_period)
553
579
{
580
+ // @todo should be after the trylock
581
+ // and duplicate the condition for the odom and odom_tf!
554
582
last_odom_publish_time_ = time;
555
583
556
584
// Compute and store orientation info
@@ -602,6 +630,7 @@ namespace diff_drive_controller
602
630
// Limit velocities and accelerations:
603
631
const double cmd_dt (period.toSec ());
604
632
633
+ // @todo add an option to limit the velocity considering the actual velocity
605
634
limiter_lin_.limit (curr_cmd.lin , last0_cmd_.lin , last1_cmd_.lin , cmd_dt);
606
635
limiter_ang_.limit (curr_cmd.ang , last0_cmd_.ang , last1_cmd_.ang , cmd_dt);
607
636
@@ -620,7 +649,7 @@ namespace diff_drive_controller
620
649
}
621
650
622
651
// Publish limited velocity command:
623
- if (dynamic_params. publish_cmd_vel_limited && cmd_vel_limited_pub_->trylock ())
652
+ if (publish_cmd_vel_limited_ && cmd_vel_limited_pub_->trylock ())
624
653
{
625
654
cmd_vel_limited_pub_->msg_ .header .stamp = time;
626
655
@@ -854,6 +883,9 @@ namespace diff_drive_controller
854
883
void DiffDriveController::reconfigureCallback (
855
884
DiffDriveControllerConfig& config, uint32_t level)
856
885
{
886
+ dynamic_params_struct_.pose_from_joint_position = config.pose_from_joint_position ;
887
+ dynamic_params_struct_.twist_from_joint_position = config.twist_from_joint_position ;
888
+
857
889
dynamic_params_struct_.wheel_separation_multiplier = config.wheel_separation_multiplier ;
858
890
859
891
dynamic_params_struct_.left_wheel_radius_multiplier = config.left_wheel_radius_multiplier ;
@@ -869,6 +901,8 @@ namespace diff_drive_controller
869
901
870
902
ROS_DEBUG_STREAM_NAMED (name_,
871
903
" Reconfigured Odometry params. "
904
+ << " pose odometry computed from: " << (dynamic_params_struct_.pose_from_joint_position ? " position" : " velocity" ) << " , "
905
+ << " twist odometry computed from: " << (dynamic_params_struct_.twist_from_joint_position ? " position" : " velocity" ) << " , "
872
906
<< " wheel separation: " << dynamic_params_struct_.wheel_separation_multiplier << " , "
873
907
<< " left wheel radius: " << dynamic_params_struct_.left_wheel_radius_multiplier << " , "
874
908
<< " right wheel radius: " << dynamic_params_struct_.left_wheel_radius_multiplier );
0 commit comments