Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include <algorithm>
00030 #include <assert.h>
00031
00032 #include <erratic_gazebo_plugins/diffdrive_plugin.h>
00033
00034 #include <common/common.hh>
00035 #include <math/gzmath.hh>
00036 #include <physics/physics.hh>
00037 #include <sdf/sdf.hh>
00038
00039 #include <ros/ros.h>
00040 #include <tf/tf.h>
00041 #include <tf/transform_broadcaster.h>
00042 #include <tf/transform_listener.h>
00043 #include <geometry_msgs/Twist.h>
00044 #include <nav_msgs/Odometry.h>
00045 #include <boost/bind.hpp>
00046
00047 namespace gazebo
00048 {
00049
00050 enum
00051 {
00052 RIGHT,
00053 LEFT,
00054 };
00055
00056
00057 DiffDrivePlugin::DiffDrivePlugin()
00058 {
00059 }
00060
00061
00062 DiffDrivePlugin::~DiffDrivePlugin()
00063 {
00064 delete rosnode_;
00065 delete transform_broadcaster_;
00066 }
00067
00068
00069 void DiffDrivePlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
00070 {
00071 this->parent = _parent;
00072 this->world = _parent->GetWorld();
00073
00074 gzdbg << "plugin parent sensor name: " << parent->GetName() << "\n";
00075
00076 if (!this->parent) { gzthrow("Differential_Position2d controller requires a Model as its parent"); }
00077
00078 this->robotNamespace = "";
00079 if (_sdf->HasElement("robotNamespace"))
00080 {
00081 this->robotNamespace = _sdf->GetElement("robotNamespace")->GetValueString() + "/";
00082 }
00083
00084 if (!_sdf->HasElement("leftJoint"))
00085 {
00086 ROS_WARN("Differential Drive plugin missing <leftJoint>, defaults to left_joint");
00087 this->leftJointName = "left_joint";
00088 }
00089 else
00090 {
00091 this->leftJointName = _sdf->GetElement("leftJoint")->GetValueString();
00092 }
00093
00094 if (!_sdf->HasElement("rightJoint"))
00095 {
00096 ROS_WARN("Differential Drive plugin missing <rightJoint>, defaults to right_joint");
00097 this->rightJointName = "right_joint";
00098 }
00099 else
00100 {
00101 this->rightJointName = _sdf->GetElement("rightJoint")->GetValueString();
00102 }
00103
00104 if (!_sdf->HasElement("wheelSeparation"))
00105 {
00106 ROS_WARN("Differential Drive plugin missing <wheelSeparation>, defaults to 0.34");
00107 this->wheelSeparation = 0.34;
00108 }
00109 else
00110 {
00111 this->wheelSeparation = _sdf->GetElement("wheelSeparation")->GetValueDouble();
00112 }
00113
00114 if (!_sdf->HasElement("wheelDiameter"))
00115 {
00116 ROS_WARN("Differential Drive plugin missing <wheelDiameter>, defaults to 0.15");
00117 this->wheelDiameter = 0.15;
00118 }
00119 else
00120 {
00121 this->wheelDiameter = _sdf->GetElement("wheelDiameter")->GetValueDouble();
00122 }
00123
00124 if (!_sdf->HasElement("torque"))
00125 {
00126 ROS_WARN("Differential Drive plugin missing <torque>, defaults to 5.0");
00127 this->torque = 5.0;
00128 }
00129 else
00130 {
00131 this->torque = _sdf->GetElement("torque")->GetValueDouble();
00132 }
00133
00134 if (!_sdf->HasElement("topicName"))
00135 {
00136 ROS_WARN("Differential Drive plugin missing <topicName>, defaults to cmd_vel");
00137 this->topicName = "cmd_vel";
00138 }
00139 else
00140 {
00141 this->topicName = _sdf->GetElement("topicName")->GetValueString();
00142 }
00143
00144 wheelSpeed[RIGHT] = 0;
00145 wheelSpeed[LEFT] = 0;
00146
00147 x_ = 0;
00148 rot_ = 0;
00149 alive_ = true;
00150
00151 joints[LEFT] = this->parent->GetJoint(leftJointName);
00152 joints[RIGHT] = this->parent->GetJoint(rightJointName);
00153
00154 if (!joints[LEFT]) { gzthrow("The controller couldn't get left hinge joint"); }
00155 if (!joints[RIGHT]) { gzthrow("The controller couldn't get right hinge joint"); }
00156
00157
00158 int argc = 0;
00159 char** argv = NULL;
00160 ros::init(argc, argv, "diff_drive_plugin", ros::init_options::NoSigintHandler | ros::init_options::AnonymousName);
00161 rosnode_ = new ros::NodeHandle(this->robotNamespace);
00162
00163 ROS_INFO("starting diffdrive plugin in ns: %s", this->robotNamespace.c_str());
00164
00165 tf_prefix_ = tf::getPrefixParam(*rosnode_);
00166 transform_broadcaster_ = new tf::TransformBroadcaster();
00167
00168
00169 ros::SubscribeOptions so =
00170 ros::SubscribeOptions::create<geometry_msgs::Twist>(topicName, 1,
00171 boost::bind(&DiffDrivePlugin::cmdVelCallback, this, _1),
00172 ros::VoidPtr(), &queue_);
00173 sub_ = rosnode_->subscribe(so);
00174 pub_ = rosnode_->advertise<nav_msgs::Odometry>("odom", 1);
00175
00176
00177
00178 odomPose[0] = 0.0;
00179 odomPose[1] = 0.0;
00180 odomPose[2] = 0.0;
00181
00182 odomVel[0] = 0.0;
00183 odomVel[1] = 0.0;
00184 odomVel[2] = 0.0;
00185
00186
00187 this->callback_queue_thread_ = boost::thread(boost::bind(&DiffDrivePlugin::QueueThread, this));
00188
00189
00190 this->updateConnection = event::Events::ConnectWorldUpdateStart(boost::bind(&DiffDrivePlugin::UpdateChild, this));
00191 }
00192
00193
00194 void DiffDrivePlugin::UpdateChild()
00195 {
00196
00197 double wd, ws;
00198 double d1, d2;
00199 double dr, da;
00200 double stepTime = this->world->GetPhysicsEngine()->GetStepTime();
00201
00202 GetPositionCmd();
00203
00204 wd = wheelDiameter;
00205 ws = wheelSeparation;
00206
00207
00208 d1 = stepTime * wd / 2 * joints[LEFT]->GetVelocity(0);
00209 d2 = stepTime * wd / 2 * joints[RIGHT]->GetVelocity(0);
00210
00211 dr = (d1 + d2) / 2;
00212 da = (d1 - d2) / ws;
00213
00214
00215 odomPose[0] += dr * cos(odomPose[2]);
00216 odomPose[1] += dr * sin(odomPose[2]);
00217 odomPose[2] += da;
00218
00219
00220 odomVel[0] = dr / stepTime;
00221 odomVel[1] = 0.0;
00222 odomVel[2] = da / stepTime;
00223
00224 joints[LEFT]->SetVelocity(0, wheelSpeed[LEFT] / (wheelDiameter / 2.0));
00225 joints[RIGHT]->SetVelocity(0, wheelSpeed[RIGHT] / (wheelDiameter / 2.0));
00226
00227 joints[LEFT]->SetMaxForce(0, torque);
00228 joints[RIGHT]->SetMaxForce(0, torque);
00229
00230 write_position_data();
00231 publish_odometry();
00232 }
00233
00234
00235 void DiffDrivePlugin::FiniChild()
00236 {
00237 alive_ = false;
00238 queue_.clear();
00239 queue_.disable();
00240 rosnode_->shutdown();
00241 callback_queue_thread_.join();
00242 }
00243
00244 void DiffDrivePlugin::GetPositionCmd()
00245 {
00246 lock.lock();
00247
00248 double vr, va;
00249
00250 vr = x_;
00251 va = rot_;
00252
00253
00254
00255 wheelSpeed[LEFT] = vr + va * wheelSeparation / 2.0;
00256 wheelSpeed[RIGHT] = vr - va * wheelSeparation / 2.0;
00257
00258 lock.unlock();
00259 }
00260
00261 void DiffDrivePlugin::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg)
00262 {
00263 lock.lock();
00264
00265 x_ = cmd_msg->linear.x;
00266 rot_ = cmd_msg->angular.z;
00267
00268 lock.unlock();
00269 }
00270
00271 void DiffDrivePlugin::QueueThread()
00272 {
00273 static const double timeout = 0.01;
00274
00275 while (alive_ && rosnode_->ok())
00276 {
00277 queue_.callAvailable(ros::WallDuration(timeout));
00278 }
00279 }
00280
00281 void DiffDrivePlugin::publish_odometry()
00282 {
00283 ros::Time current_time = ros::Time::now();
00284 std::string odom_frame = tf::resolve(tf_prefix_, "odom");
00285 std::string base_footprint_frame = tf::resolve(tf_prefix_, "base_footprint");
00286
00287
00288 gazebo::physics::ModelState state(this->parent);
00289 math::Pose pose = state.GetPose();
00290
00291 tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
00292 tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
00293
00294 tf::Transform base_footprint_to_odom(qt, vt);
00295 transform_broadcaster_->sendTransform(tf::StampedTransform(base_footprint_to_odom,
00296 current_time,
00297 odom_frame,
00298 base_footprint_frame));
00299
00300
00301 odom_.pose.pose.position.x = pose.pos.x;
00302 odom_.pose.pose.position.y = pose.pos.y;
00303
00304 odom_.pose.pose.orientation.x = pose.rot.x;
00305 odom_.pose.pose.orientation.y = pose.rot.y;
00306 odom_.pose.pose.orientation.z = pose.rot.z;
00307 odom_.pose.pose.orientation.w = pose.rot.w;
00308
00309 math::Vector3 linear = this->parent->GetWorldLinearVel();
00310 odom_.twist.twist.linear.x = linear.x;
00311 odom_.twist.twist.linear.y = linear.y;
00312 odom_.twist.twist.angular.z = this->parent->GetWorldAngularVel().z;
00313
00314 odom_.header.stamp = current_time;
00315 odom_.header.frame_id = odom_frame;
00316 odom_.child_frame_id = base_footprint_frame;
00317
00318 pub_.publish(odom_);
00319 }
00320
00321
00322 void DiffDrivePlugin::write_position_data()
00323 {
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333
00334 math::Pose orig_pose = this->parent->GetWorldPose();
00335
00336 math::Pose new_pose = orig_pose;
00337 new_pose.pos.x = odomPose[0];
00338 new_pose.pos.y = odomPose[1];
00339 new_pose.rot.SetFromEuler(math::Vector3(0,0,odomPose[2]));
00340
00341 this->parent->SetWorldPose( new_pose );
00342 }
00343
00344 GZ_REGISTER_MODEL_PLUGIN(DiffDrivePlugin)
00345 }