@@ -108,6 +108,12 @@ int DiffDriveBaseController::init(ros::NodeHandle& nh, ControllerManager* manage
108
108
nh.param <double >(" rotating_threshold" , rotating_threshold_, 0.05 );
109
109
nh.param <double >(" moving_threshold" , moving_threshold_, 0.05 );
110
110
111
+ nh.param <double >(" gain_effort" ,gain_effort_, 0.0 );
112
+ ROS_INFO (" The gyro gain on the effort is %f" , gain_effort_);
113
+
114
+ nh.param <double >(" gain_velocity" , gain_velocity_, 0.0 );
115
+ ROS_INFO (" The gyro gain on the velocity is %f" , gain_velocity_);
116
+
111
117
double t;
112
118
nh.param <double >(" timeout" , t, 0.25 );
113
119
timeout_ = ros::Duration (t);
@@ -122,6 +128,10 @@ int DiffDriveBaseController::init(ros::NodeHandle& nh, ControllerManager* manage
122
128
cmd_sub_ = nh.subscribe <geometry_msgs::Twist>(" command" , 1 ,
123
129
boost::bind (&DiffDriveBaseController::command, this , _1));
124
130
131
+
132
+ // Subscribe to imu
133
+ imu_sub_ = nh.subscribe <sensor_msgs::Imu>(" /imu" ,1 , &DiffDriveBaseController::imuCallback, this );
134
+
125
135
// Publish odometry & tf
126
136
ros::NodeHandle n;
127
137
odom_pub_ = n.advertise <nav_msgs::Odometry>(" odom" , 10 );
@@ -172,6 +182,13 @@ void DiffDriveBaseController::command(const geometry_msgs::TwistConstPtr& msg)
172
182
manager_->requestStart (getName ());
173
183
}
174
184
185
+ // callback function for imu
186
+ void DiffDriveBaseController::imuCallback (const sensor_msgs::ImuConstPtr & msg)
187
+ {
188
+ boost::mutex::scoped_lock lock (command_mutex_);
189
+ gyro_z_ = msg->angular_velocity .z ;
190
+ }
191
+
175
192
bool DiffDriveBaseController::start ()
176
193
{
177
194
if (!initialized_)
@@ -227,8 +244,8 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
227
244
safety_scaling_ = 0.1 ;
228
245
}
229
246
230
- // Do velocity acceleration/limiting
231
- double x, r;
247
+ // Do velocity acceleration/limiting, get gyro_z with holding lock
248
+ double x, r, gyro_z ;
232
249
{
233
250
boost::mutex::scoped_lock lock (command_mutex_);
234
251
// Limit linear velocity based on obstacles
@@ -240,6 +257,7 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
240
257
// Limit angular velocity
241
258
// Scale same amount as linear velocity so that robot still follows the same "curvature"
242
259
r = std::max (-max_velocity_r_, std::min (actual_scaling * desired_r_, max_velocity_r_));
260
+ gyro_z = gyro_z_;
243
261
}
244
262
if (x > last_sent_x_)
245
263
{
@@ -268,13 +286,16 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
268
286
269
287
double dx = 0.0 ;
270
288
double dr = 0.0 ;
271
-
272
289
double left_pos = left_->getPosition ();
273
290
double right_pos = right_->getPosition ();
274
291
double left_dx = angles::shortest_angular_distance (left_last_position_, left_pos)/radians_per_meter_;
275
292
double right_dx = angles::shortest_angular_distance (right_last_position_, right_pos)/radians_per_meter_;
276
293
double left_vel = static_cast <double >(left_->getVelocity ())/radians_per_meter_;
277
294
double right_vel = static_cast <double >(right_->getVelocity ())/radians_per_meter_;
295
+ double effort_l;
296
+ double effort_r;
297
+ double ang_err;
298
+ double p_gain_effort, p_gain_velocity;
278
299
279
300
// Threshold the odometry to avoid noise (especially in simulation)
280
301
if (fabs (left_dx) > wheel_rotating_threshold_ ||
@@ -301,14 +322,23 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
301
322
dx = (left_vel + right_vel)/2.0 ;
302
323
dr = (right_vel - left_vel)/track_width_;
303
324
325
+ // add torque along with velocity for stability
326
+ ang_err = dr - gyro_z;
327
+ p_gain_effort = gain_effort_ * ang_err;
328
+ effort_r = p_gain_effort;
329
+ effort_l = -p_gain_effort;
330
+ p_gain_velocity = gain_velocity_ * ang_err;
331
+
304
332
// Actually set command
305
333
if (fabs (dx) > moving_threshold_ ||
306
334
fabs (dr) > rotating_threshold_ ||
307
335
last_sent_x_ != 0.0 ||
308
336
last_sent_r_ != 0.0 )
309
337
{
310
- setCommand (last_sent_x_ - (last_sent_r_/2.0 * track_width_),
311
- last_sent_x_ + (last_sent_r_/2.0 * track_width_));
338
+ double vel_r = last_sent_x_ - ((last_sent_r_ + p_gain_velocity)/2.0 * track_width_);
339
+ double vel_l = last_sent_x_ + ((last_sent_r_ + p_gain_velocity)/2.0 * track_width_);
340
+
341
+ setCommand (vel_r, vel_l, effort_l, effort_r);
312
342
}
313
343
314
344
// Lock mutex before updating
@@ -401,11 +431,11 @@ void DiffDriveBaseController::scanCallback(
401
431
last_laser_scan_ = ros::Time::now ();
402
432
}
403
433
404
- void DiffDriveBaseController::setCommand (float left, float right)
434
+ void DiffDriveBaseController::setCommand (float left, float right, double effort_l_, double effort_r_ )
405
435
{
406
436
// Convert meters/sec into radians/sec
407
- left_->setVelocity (left * radians_per_meter_, 0.0 );
408
- right_->setVelocity (right * radians_per_meter_, 0.0 );
437
+ left_->setVelocity (left * radians_per_meter_, effort_l_ );
438
+ right_->setVelocity (right * radians_per_meter_, effort_r_ );
409
439
}
410
440
411
441
} // namespace robot_controllers
0 commit comments