Skip to content

Commit c05320c

Browse files
author
Enrique Fernandez
committed
Allow computing pose/twist from position/velocity
1 parent 33d4ed4 commit c05320c

File tree

5 files changed

+146
-98
lines changed

5 files changed

+146
-98
lines changed

diff_drive_controller/cfg/DiffDriveController.cfg

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,14 +6,17 @@ from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, b
66

77
gen = ParameterGenerator()
88

9+
gen.add("pose_from_joint_position", bool_t, 0, "Compute odometry pose from wheel joint position.", True)
10+
gen.add("twist_from_joint_position", bool_t, 0, "Compute odometry twist from wheel joint position.", False)
11+
912
gen.add("wheel_separation_multiplier", double_t, 0, "Wheel separation multiplier.", 1.0, 0.5, 1.5)
1013
gen.add("left_wheel_radius_multiplier", double_t, 0, "Left wheel radius multiplier.", 1.0, 0.5, 1.5)
1114
gen.add("right_wheel_radius_multiplier", double_t, 0, "Right wheel radius multiplier.", 1.0, 0.5, 1.5)
1215

1316
gen.add("k_l", double_t, 0, "Covariance model k_l multiplier.", 1.0, 0.0, 10.0)
1417
gen.add("k_r", double_t, 0, "Covariance model k_r multiplier.", 1.0, 0.0, 10.0)
1518

16-
gen.add("publish_state", bool_t, 0, "Publish joint trajectory controller state.", False)
1719
gen.add("publish_cmd_vel_limited", bool_t, 0, "Publish limited velocity command.", False)
20+
gen.add("publish_state", bool_t, 0, "Publish joint trajectory controller state.", False)
1821

1922
exit(gen.generate(PACKAGE, "diff_drive_controller", "DiffDriveController"))

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,12 @@ namespace diff_drive_controller
117117
ros::Duration publish_period_;
118118
ros::Time last_odom_publish_time_;
119119
bool open_loop_;
120-
bool position_feedback_;
120+
121+
bool pose_from_joint_position_;
122+
bool twist_from_joint_position_;
123+
124+
bool use_position_;
125+
bool use_velocity_;
121126

122127
/// Hardware handles:
123128
std::vector<hardware_interface::JointHandle> left_wheel_joints_;
@@ -181,6 +186,9 @@ namespace diff_drive_controller
181186

182187
struct DynamicParams
183188
{
189+
bool pose_from_joint_position;
190+
bool twist_from_joint_position;
191+
184192
double wheel_separation_multiplier;
185193
double left_wheel_radius_multiplier;
186194
double right_wheel_radius_multiplier;
@@ -192,7 +200,9 @@ namespace diff_drive_controller
192200
bool publish_cmd_vel_limited;
193201

194202
DynamicParams()
195-
: wheel_separation_multiplier(1.0)
203+
: pose_from_joint_position(true)
204+
, twist_from_joint_position(false)
205+
, wheel_separation_multiplier(1.0)
196206
, left_wheel_radius_multiplier(1.0)
197207
, right_wheel_radius_multiplier(1.0)
198208
, k_l(1.0)

diff_drive_controller/include/diff_drive_controller/odometry.h

Lines changed: 13 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -115,17 +115,10 @@ namespace diff_drive_controller
115115
* \param time [in] Current time
116116
* \return true if the odometry is actually updated
117117
*/
118-
bool updateCloseLoop(double left_pos, double right_pos, const ros::Time &time);
119-
120-
/**
121-
* \brief Updates the odometry class with latest wheels velocity, i.e. in
122-
* close loop
123-
* \param left_vel [in] Left wheel velocity [rad/s]
124-
* \param right_vel [in] Right wheel velocity [rad/s]
125-
* \param time [in] Current time
126-
* \return true if the odometry is actually updated
127-
*/
128-
bool updateCloseLoopFromVelocity(double left_pos, double right_pos, const ros::Time &time);
118+
bool updateCloseLoop(
119+
const double left_position, const double right_position,
120+
const double left_velocity, const double right_velocity,
121+
const ros::Time &time);
129122

130123
/**
131124
* \brief Updates the odometry class with latest velocity command, i.e. in
@@ -267,12 +260,15 @@ namespace diff_drive_controller
267260
/**
268261
* \brief Updates the odometry class with latest velocity command and wheel
269262
* velocities
270-
* \param v_l [in] Left wheel velocity displacement [rad]
271-
* \param v_r [in] Right wheel velocity displacement [rad]
272-
* \param time [in] Current time
263+
* \param[in] dp_l Left wheel position increment [rad]
264+
* \param[in] dp_r Right wheel position increment [rad]
265+
* \param[in] v_l Left wheel velocity [rad/s]
266+
* \param[in] v_r Right wheel velocity [rad/s]
267+
* \param[in] time Current time
273268
* \return true if the odometry is actually updated
274269
*/
275-
bool update(double v_l, double v_r, const ros::Time& time);
270+
bool update(const double dp_l, const double dp_r,
271+
const double v_l, const double v_r, const ros::Time& time);
276272

277273
/**
278274
* \brief Update the odometry twist with the previous and current odometry
@@ -332,8 +328,8 @@ namespace diff_drive_controller
332328
double k_r_;
333329

334330
/// Previous wheel position/state [rad]:
335-
double left_wheel_old_pos_;
336-
double right_wheel_old_pos_;
331+
double left_position_previous_;
332+
double right_position_previous_;
337333

338334
/// Rolling mean accumulators for the linar and angular velocities:
339335
size_t velocity_rolling_window_size_;

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 75 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,8 @@ namespace diff_drive_controller
123123

124124
DiffDriveController::DiffDriveController()
125125
: open_loop_(false)
126-
, position_feedback_(true)
126+
, pose_from_joint_position_(true)
127+
, twist_from_joint_position_(false)
127128
, command_struct_()
128129
, dynamic_params_struct_()
129130
, wheel_separation_(0.0)
@@ -184,10 +185,18 @@ namespace diff_drive_controller
184185
ROS_INFO_STREAM_NAMED(name_, "Odometry will be computed in "
185186
<< (open_loop_ ? "open" : "close") << " loop.");
186187

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_;
191200

192201
controller_nh.param("wheel_separation_multiplier",
193202
wheel_separation_multiplier_, wheel_separation_multiplier_);
@@ -303,6 +312,9 @@ namespace diff_drive_controller
303312
"Measurement Covariance Model params : k_l " << k_l_
304313
<< ", k_r " << k_r_);
305314

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+
306318
dynamic_params_struct_.wheel_separation_multiplier = wheel_separation_multiplier_;
307319

308320
dynamic_params_struct_.left_wheel_radius_multiplier = left_wheel_radius_multiplier_;
@@ -449,6 +461,9 @@ namespace diff_drive_controller
449461
//
450462
// ...
451463
// }
464+
pose_from_joint_position_ = dynamic_params.pose_from_joint_position;
465+
twist_from_joint_position_ = dynamic_params.twist_from_joint_position;
466+
452467
wheel_separation_multiplier_ = dynamic_params.wheel_separation_multiplier;
453468
left_wheel_radius_multiplier_ = dynamic_params.left_wheel_radius_multiplier;
454469
right_wheel_radius_multiplier_ = dynamic_params.right_wheel_radius_multiplier;
@@ -469,51 +484,44 @@ namespace diff_drive_controller
469484
odometry_.setMeasCovarianceParams(k_l_, k_r_);
470485

471486
// 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)
473489
{
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();
475495
}
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_)
477502
{
478-
if (position_feedback_)
503+
for (size_t i = 0; i < wheel_joints_size_; ++i)
479504
{
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]))
483507
{
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;
491510
}
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);
497511
}
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)
499518
{
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]))
503521
{
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;
511524
}
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);
517525
}
518526
}
519527

@@ -547,10 +555,30 @@ namespace diff_drive_controller
547555
const double left_velocity_estimated_average = std::accumulate(left_velocities_estimated_.begin(), left_velocities_estimated_.end(), 0.0) / wheel_joints_size_;
548556
const double right_velocity_estimated_average = std::accumulate(right_velocities_estimated_.begin(), right_velocities_estimated_.end(), 0.0) / wheel_joints_size_;
549557

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+
550576
// Publish odometry message
551577
const ros::Duration half_period(0.5 * period.toSec());
552578
if (last_odom_publish_time_ + publish_period_ < time + half_period)
553579
{
580+
// @todo should be after the trylock
581+
// and duplicate the condition for the odom and odom_tf!
554582
last_odom_publish_time_ = time;
555583

556584
// Compute and store orientation info
@@ -602,6 +630,7 @@ namespace diff_drive_controller
602630
// Limit velocities and accelerations:
603631
const double cmd_dt(period.toSec());
604632

633+
// @todo add an option to limit the velocity considering the actual velocity
605634
limiter_lin_.limit(curr_cmd.lin, last0_cmd_.lin, last1_cmd_.lin, cmd_dt);
606635
limiter_ang_.limit(curr_cmd.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
607636

@@ -620,7 +649,7 @@ namespace diff_drive_controller
620649
}
621650

622651
// 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())
624653
{
625654
cmd_vel_limited_pub_->msg_.header.stamp = time;
626655

@@ -854,6 +883,9 @@ namespace diff_drive_controller
854883
void DiffDriveController::reconfigureCallback(
855884
DiffDriveControllerConfig& config, uint32_t level)
856885
{
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+
857889
dynamic_params_struct_.wheel_separation_multiplier = config.wheel_separation_multiplier;
858890

859891
dynamic_params_struct_.left_wheel_radius_multiplier = config.left_wheel_radius_multiplier;
@@ -869,6 +901,8 @@ namespace diff_drive_controller
869901

870902
ROS_DEBUG_STREAM_NAMED(name_,
871903
"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") << ", "
872906
<< "wheel separation: " << dynamic_params_struct_.wheel_separation_multiplier << ", "
873907
<< "left wheel radius: " << dynamic_params_struct_.left_wheel_radius_multiplier << ", "
874908
<< "right wheel radius: " << dynamic_params_struct_.left_wheel_radius_multiplier);

0 commit comments

Comments
 (0)