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