Skip to content

Commit 7c90b7b

Browse files
committed
Added loop around angular Velocity
P controller using gyro feedback gain on effort around 6 gain on velocity around 0.8 squashing the commits
1 parent 1e0cb53 commit 7c90b7b

File tree

2 files changed

+48
-10
lines changed

2 files changed

+48
-10
lines changed

robot_controllers/include/robot_controllers/diff_drive_base.h

+10-2
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@
5151
#include <geometry_msgs/Twist.h>
5252
#include <nav_msgs/Odometry.h>
5353
#include <sensor_msgs/LaserScan.h>
54+
#include <sensor_msgs/Imu.h>
5455

5556
namespace robot_controllers
5657
{
@@ -121,6 +122,9 @@ class DiffDriveBaseController : public Controller
121122
/** @brief Command callback from either a ROS topic, or a higher controller. */
122123
void command(const geometry_msgs::TwistConstPtr& msg);
123124

125+
/** @brief Imu callback .*/
126+
void imuCallback(const sensor_msgs::ImuConstPtr& msg);
127+
124128
private:
125129
bool initialized_;
126130
ControllerManager* manager_;
@@ -129,7 +133,7 @@ class DiffDriveBaseController : public Controller
129133
void scanCallback(const sensor_msgs::LaserScanConstPtr& scan);
130134

131135
// Set base wheel speeds in m/s
132-
void setCommand(float left, float right);
136+
void setCommand(float left, float right, double effort_l_, double effort_r_);
133137

134138
JointHandlePtr left_;
135139
JointHandlePtr right_;
@@ -146,6 +150,8 @@ class DiffDriveBaseController : public Controller
146150
double max_velocity_r_;
147151
double max_acceleration_x_;
148152
double max_acceleration_r_;
153+
double gain_effort_;
154+
double gain_velocity_;
149155

150156
// Laser can provide additional safety limits on velocity
151157
double safety_scaling_;
@@ -161,11 +167,13 @@ class DiffDriveBaseController : public Controller
161167
// These are from controller update
162168
float last_sent_x_;
163169
float last_sent_r_;
170+
float gyro_z_;
164171

165172
float left_last_position_;
166173
float right_last_position_;
167174
double left_last_timestamp_;
168175
double right_last_timestamp_;
176+
ros::WallTime last_button_press_time_;
169177

170178
ros::Time last_command_;
171179
ros::Time last_update_;
@@ -175,7 +183,7 @@ class DiffDriveBaseController : public Controller
175183
nav_msgs::Odometry odom_;
176184
ros::Publisher odom_pub_;
177185
ros::Timer odom_timer_;
178-
ros::Subscriber cmd_sub_, scan_sub_;
186+
ros::Subscriber cmd_sub_, scan_sub_, imu_sub_;
179187

180188
boost::shared_ptr<tf::TransformBroadcaster> broadcaster_;
181189
bool publish_tf_;

robot_controllers/src/diff_drive_base.cpp

+38-8
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,12 @@ int DiffDriveBaseController::init(ros::NodeHandle& nh, ControllerManager* manage
108108
nh.param<double>("rotating_threshold", rotating_threshold_, 0.05);
109109
nh.param<double>("moving_threshold", moving_threshold_, 0.05);
110110

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+
111117
double t;
112118
nh.param<double>("timeout", t, 0.25);
113119
timeout_ = ros::Duration(t);
@@ -122,6 +128,10 @@ int DiffDriveBaseController::init(ros::NodeHandle& nh, ControllerManager* manage
122128
cmd_sub_ = nh.subscribe<geometry_msgs::Twist>("command", 1,
123129
boost::bind(&DiffDriveBaseController::command, this, _1));
124130

131+
132+
// Subscribe to imu
133+
imu_sub_ = nh.subscribe<sensor_msgs::Imu>("/imu",1, &DiffDriveBaseController::imuCallback, this);
134+
125135
// Publish odometry & tf
126136
ros::NodeHandle n;
127137
odom_pub_ = n.advertise<nav_msgs::Odometry>("odom", 10);
@@ -172,6 +182,13 @@ void DiffDriveBaseController::command(const geometry_msgs::TwistConstPtr& msg)
172182
manager_->requestStart(getName());
173183
}
174184

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+
175192
bool DiffDriveBaseController::start()
176193
{
177194
if (!initialized_)
@@ -227,8 +244,8 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
227244
safety_scaling_ = 0.1;
228245
}
229246

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;
232249
{
233250
boost::mutex::scoped_lock lock(command_mutex_);
234251
// Limit linear velocity based on obstacles
@@ -240,6 +257,7 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
240257
// Limit angular velocity
241258
// Scale same amount as linear velocity so that robot still follows the same "curvature"
242259
r = std::max(-max_velocity_r_, std::min(actual_scaling * desired_r_, max_velocity_r_));
260+
gyro_z = gyro_z_;
243261
}
244262
if (x > last_sent_x_)
245263
{
@@ -268,13 +286,16 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
268286

269287
double dx = 0.0;
270288
double dr = 0.0;
271-
272289
double left_pos = left_->getPosition();
273290
double right_pos = right_->getPosition();
274291
double left_dx = angles::shortest_angular_distance(left_last_position_, left_pos)/radians_per_meter_;
275292
double right_dx = angles::shortest_angular_distance(right_last_position_, right_pos)/radians_per_meter_;
276293
double left_vel = static_cast<double>(left_->getVelocity())/radians_per_meter_;
277294
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;
278299

279300
// Threshold the odometry to avoid noise (especially in simulation)
280301
if (fabs(left_dx) > wheel_rotating_threshold_ ||
@@ -301,14 +322,23 @@ void DiffDriveBaseController::update(const ros::Time& now, const ros::Duration&
301322
dx = (left_vel + right_vel)/2.0;
302323
dr = (right_vel - left_vel)/track_width_;
303324

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+
304332
// Actually set command
305333
if (fabs(dx) > moving_threshold_ ||
306334
fabs(dr) > rotating_threshold_ ||
307335
last_sent_x_ != 0.0 ||
308336
last_sent_r_ != 0.0)
309337
{
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);
312342
}
313343

314344
// Lock mutex before updating
@@ -401,11 +431,11 @@ void DiffDriveBaseController::scanCallback(
401431
last_laser_scan_ = ros::Time::now();
402432
}
403433

404-
void DiffDriveBaseController::setCommand(float left, float right)
434+
void DiffDriveBaseController::setCommand(float left, float right, double effort_l_, double effort_r_)
405435
{
406436
// 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_);
409439
}
410440

411441
} // namespace robot_controllers

0 commit comments

Comments
 (0)