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
00033 #include <algorithm>
00034 #include <assert.h>
00035
00036 #include <hector_gazebo_plugins/diffdrive_plugin_6w.h>
00037 #include <gazebo/common/Events.hh>
00038 #include <gazebo/physics/physics.hh>
00039
00040 #include <ros/ros.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 enum
00050 {
00051 FRONT_LEFT,
00052 FRONT_RIGHT,
00053 MID_LEFT,
00054 MID_RIGHT,
00055 REAR_LEFT,
00056 REAR_RIGHT,
00057 NUM_WHEELS
00058 };
00059
00060
00061 DiffDrivePlugin6W::DiffDrivePlugin6W()
00062 {
00063 }
00064
00065
00066 DiffDrivePlugin6W::~DiffDrivePlugin6W()
00067 {
00068 event::Events::DisconnectWorldUpdateBegin(updateConnection);
00069 delete transform_broadcaster_;
00070 rosnode_->shutdown();
00071 callback_queue_thread_.join();
00072 delete rosnode_;
00073 }
00074
00075
00076 void DiffDrivePlugin6W::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00077 {
00078 world = _model->GetWorld();
00079
00080
00081 namespace_.clear();
00082 topic_ = "cmd_vel";
00083 wheelSep = 0.34;
00084 wheelDiam = 0.15;
00085 torque = 10.0;
00086
00087
00088 if (_sdf->HasElement("robotNamespace"))
00089 namespace_ = _sdf->GetElement("robotNamespace")->GetValue()->GetAsString();
00090
00091 if (_sdf->HasElement("topicName"))
00092 topic_ = _sdf->GetElement("topicName")->GetValue()->GetAsString();
00093
00094 if (_sdf->HasElement("bodyName"))
00095 {
00096 link_name_ = _sdf->GetElement("bodyName")->GetValue()->GetAsString();
00097 link = _model->GetLink(link_name_);
00098 } else {
00099 link = _model->GetLink();
00100 link_name_ = link->GetName();
00101 }
00102
00103
00104 if (!link)
00105 {
00106 ROS_FATAL("DiffDrivePlugin6W plugin error: bodyName: %s does not exist\n", link_name_.c_str());
00107 return;
00108 }
00109
00110 if (_sdf->HasElement("frontLeftJoint")) joints[FRONT_LEFT] = _model->GetJoint(_sdf->GetElement("frontLeftJoint")->GetValue()->GetAsString());
00111 if (_sdf->HasElement("frontRightJoint")) joints[FRONT_RIGHT] = _model->GetJoint(_sdf->GetElement("frontRightJoint")->GetValue()->GetAsString());
00112 if (_sdf->HasElement("midLeftJoint")) joints[MID_LEFT] = _model->GetJoint(_sdf->GetElement("midLeftJoint")->GetValue()->GetAsString());
00113 if (_sdf->HasElement("midRightJoint")) joints[MID_RIGHT] = _model->GetJoint(_sdf->GetElement("midRightJoint")->GetValue()->GetAsString());
00114 if (_sdf->HasElement("rearLeftJoint")) joints[REAR_LEFT] = _model->GetJoint(_sdf->GetElement("rearLeftJoint")->GetValue()->GetAsString());
00115 if (_sdf->HasElement("rearRightJoint")) joints[REAR_RIGHT] = _model->GetJoint(_sdf->GetElement("rearRightJoint")->GetValue()->GetAsString());
00116
00117 if (!joints[FRONT_LEFT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get front left joint");
00118 if (!joints[FRONT_RIGHT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get front right joint");
00119 if (!joints[MID_LEFT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get mid left joint");
00120 if (!joints[MID_RIGHT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get mid right joint");
00121 if (!joints[REAR_LEFT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get rear left joint");
00122 if (!joints[REAR_RIGHT]) ROS_FATAL("diffdrive_plugin_6w error: The controller couldn't get rear right joint");
00123
00124 if (_sdf->HasElement("wheelSeparation"))
00125 _sdf->GetElement("wheelSeparation")->GetValue()->Get(wheelSep);
00126
00127 if (_sdf->HasElement("wheelDiameter"))
00128 _sdf->GetElement("wheelDiameter")->GetValue()->Get(wheelDiam);
00129
00130 if (_sdf->HasElement("torque"))
00131 _sdf->GetElement("torque")->GetValue()->Get(torque);
00132
00133
00134 if (!ros::isInitialized())
00135 {
00136 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00137 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00138 return;
00139 }
00140
00141 rosnode_ = new ros::NodeHandle(namespace_);
00142
00143 tf_prefix_ = tf::getPrefixParam(*rosnode_);
00144 transform_broadcaster_ = new tf::TransformBroadcaster();
00145
00146
00147 ros::SubscribeOptions so =
00148 ros::SubscribeOptions::create<geometry_msgs::Twist>(topic_, 1,
00149 boost::bind(&DiffDrivePlugin6W::cmdVelCallback, this, _1),
00150 ros::VoidPtr(), &queue_);
00151 sub_ = rosnode_->subscribe(so);
00152 pub_ = rosnode_->advertise<nav_msgs::Odometry>("odom", 1);
00153
00154 callback_queue_thread_ = boost::thread(boost::bind(&DiffDrivePlugin6W::QueueThread, this));
00155
00156 Reset();
00157
00158
00159
00160
00161 updateConnection = event::Events::ConnectWorldUpdateBegin(
00162 boost::bind(&DiffDrivePlugin6W::Update, this));
00163 }
00164
00165
00166 void DiffDrivePlugin6W::Reset()
00167 {
00168 enableMotors = true;
00169
00170 for (size_t i = 0; i < 2; ++i){
00171 wheelSpeed[i] = 0;
00172 }
00173
00174 prevUpdateTime = world->GetSimTime();
00175
00176 x_ = 0;
00177 rot_ = 0;
00178 alive_ = true;
00179
00180
00181 odomPose[0] = 0.0;
00182 odomPose[1] = 0.0;
00183 odomPose[2] = 0.0;
00184
00185 odomVel[0] = 0.0;
00186 odomVel[1] = 0.0;
00187 odomVel[2] = 0.0;
00188 }
00189
00190
00191 void DiffDrivePlugin6W::Update()
00192 {
00193
00194 double d1, d2;
00195 double dr, da;
00196 common::Time stepTime;
00197
00198 GetPositionCmd();
00199
00200
00201 stepTime = world->GetSimTime() - prevUpdateTime;
00202 prevUpdateTime = world->GetSimTime();
00203
00204
00205 d1 = stepTime.Double() * wheelDiam / 2 * joints[MID_LEFT]->GetVelocity(0);
00206 d2 = stepTime.Double() * wheelDiam / 2 * joints[MID_RIGHT]->GetVelocity(0);
00207
00208 dr = (d1 + d2) / 2;
00209 da = (d1 - d2) / wheelSep;
00210
00211
00212 odomPose[0] += dr * cos(odomPose[2]);
00213 odomPose[1] += dr * sin(odomPose[2]);
00214 odomPose[2] += da;
00215
00216
00217 odomVel[0] = dr / stepTime.Double();
00218 odomVel[1] = 0.0;
00219 odomVel[2] = da / stepTime.Double();
00220
00221 if (enableMotors)
00222 {
00223 joints[FRONT_LEFT]->SetVelocity(0, wheelSpeed[0] / (wheelDiam / 2.0));
00224 joints[MID_LEFT]->SetVelocity(0, wheelSpeed[0] / (wheelDiam / 2.0));
00225 joints[REAR_LEFT]->SetVelocity(0, wheelSpeed[0] / (wheelDiam / 2.0));
00226
00227 joints[FRONT_RIGHT]->SetVelocity(0, wheelSpeed[1] / (wheelDiam / 2.0));
00228 joints[MID_RIGHT]->SetVelocity(0, wheelSpeed[1] / (wheelDiam / 2.0));
00229 joints[REAR_RIGHT]->SetVelocity(0, wheelSpeed[1] / (wheelDiam / 2.0));
00230
00231 joints[FRONT_LEFT]->SetMaxForce(0, torque);
00232 joints[MID_LEFT]->SetMaxForce(0, torque);
00233 joints[REAR_LEFT]->SetMaxForce(0, torque);
00234
00235 joints[FRONT_RIGHT]->SetMaxForce(0, torque);
00236 joints[MID_RIGHT]->SetMaxForce(0, torque);
00237 joints[REAR_RIGHT]->SetMaxForce(0, torque);
00238 }
00239
00240
00241 }
00242
00243
00244 void DiffDrivePlugin6W::GetPositionCmd()
00245 {
00246 lock.lock();
00247
00248 double vr, va;
00249
00250 vr = x_;
00251 va = -rot_;
00252
00253
00254
00255
00256 enableMotors = true;
00257
00258
00259
00260 wheelSpeed[0] = vr + va * wheelSep / 2;
00261 wheelSpeed[1] = vr - va * wheelSep / 2;
00262
00263 lock.unlock();
00264 }
00265
00266
00267 void DiffDrivePlugin6W::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg)
00268 {
00269
00270
00271 lock.lock();
00272
00273 x_ = cmd_msg->linear.x;
00274 rot_ = cmd_msg->angular.z;
00275
00276 lock.unlock();
00277
00278
00279 }
00280
00281
00282 void DiffDrivePlugin6W::QueueThread()
00283 {
00284 static const double timeout = 0.01;
00285
00286 while (alive_ && rosnode_->ok())
00287 {
00288
00289 queue_.callAvailable(ros::WallDuration(timeout));
00290 }
00291 }
00292
00293
00294 void DiffDrivePlugin6W::publish_odometry()
00295 {
00296
00297 ros::Time current_time_((world->GetSimTime()).sec, (world->GetSimTime()).nsec);
00298
00299
00300 math::Pose pose = link->GetWorldPose();
00301 math::Vector3 velocity = link->GetWorldLinearVel();
00302 math::Vector3 angular_velocity = link->GetWorldAngularVel();
00303
00304 tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
00305 tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
00306 tf::Transform base_footprint_to_odom(qt, vt);
00307
00308 transform_broadcaster_->sendTransform(tf::StampedTransform(base_footprint_to_odom,
00309 current_time_,
00310 "odom",
00311 "base_footprint"));
00312
00313
00314 odom_.pose.pose.position.x = pose.pos.x;
00315 odom_.pose.pose.position.y = pose.pos.y;
00316
00317 odom_.pose.pose.orientation.x = pose.rot.x;
00318 odom_.pose.pose.orientation.y = pose.rot.y;
00319 odom_.pose.pose.orientation.z = pose.rot.z;
00320 odom_.pose.pose.orientation.w = pose.rot.w;
00321
00322 odom_.twist.twist.linear.x = velocity.x;
00323 odom_.twist.twist.linear.y = velocity.y;
00324 odom_.twist.twist.angular.z = angular_velocity.z;
00325
00326 odom_.header.frame_id = tf::resolve(tf_prefix_, "odom");
00327 odom_.child_frame_id = "base_footprint";
00328 odom_.header.stamp = current_time_;
00329
00330 pub_.publish(odom_);
00331 }
00332
00333 GZ_REGISTER_MODEL_PLUGIN(DiffDrivePlugin6W)
00334
00335 }