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