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