$search
00001 /* 00002 Copyright (c) 2010, Daniel Hewlett, Antons Rebguns 00003 All rights reserved. 00004 00005 Redistribution and use in source and binary forms, with or without 00006 modification, are permitted provided that the following conditions are met: 00007 * Redistributions of source code must retain the above copyright 00008 notice, this list of conditions and the following disclaimer. 00009 * Redistributions in binary form must reproduce the above copyright 00010 notice, this list of conditions and the following disclaimer in the 00011 documentation and/or other materials provided with the distribution. 00012 * Neither the name of the <organization> nor the 00013 names of its contributors may be used to endorse or promote products 00014 derived from this software without specific prior written permission. 00015 00016 THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY 00017 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00019 DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY 00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 00029 #include <algorithm> 00030 #include <assert.h> 00031 00032 #include <erratic_gazebo_plugins/diffdrive_plugin.h> 00033 00034 #include <common/common.h> 00035 #include <math/gzmath.h> 00036 #include <physics/physics.h> 00037 #include <sdf/sdf.h> 00038 00039 #include <ros/ros.h> 00040 #include <tf/transform_broadcaster.h> 00041 #include <tf/transform_listener.h> 00042 #include <geometry_msgs/Twist.h> 00043 #include <nav_msgs/Odometry.h> 00044 #include <boost/bind.hpp> 00045 00046 namespace gazebo 00047 { 00048 00049 enum 00050 { 00051 RIGHT, 00052 LEFT, 00053 }; 00054 00055 // Constructor 00056 DiffDrivePlugin::DiffDrivePlugin() 00057 { 00058 } 00059 00060 // Destructor 00061 DiffDrivePlugin::~DiffDrivePlugin() 00062 { 00063 delete rosnode_; 00064 delete transform_broadcaster_; 00065 } 00066 00067 // Load the controller 00068 void DiffDrivePlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) 00069 { 00070 this->parent = _parent; 00071 this->world = _parent->GetWorld(); 00072 00073 gzdbg << "plugin parent sensor name: " << parent->GetName() << "\n"; 00074 00075 if (!this->parent) { gzthrow("Differential_Position2d controller requires a Model as its parent"); } 00076 00077 this->robotNamespace = ""; 00078 if (_sdf->HasElement("robotNamespace")) 00079 { 00080 this->robotNamespace = _sdf->GetElement("robotNamespace")->GetValueString() + "/"; 00081 } 00082 00083 if (!_sdf->HasElement("leftJoint")) 00084 { 00085 ROS_WARN("Differential Drive plugin missing <leftJoint>, defaults to left_joint"); 00086 this->leftJointName = "left_joint"; 00087 } 00088 else 00089 { 00090 this->leftJointName = _sdf->GetElement("leftJoint")->GetValueString(); 00091 } 00092 00093 if (!_sdf->HasElement("rightJoint")) 00094 { 00095 ROS_WARN("Differential Drive plugin missing <rightJoint>, defaults to right_joint"); 00096 this->rightJointName = "right_joint"; 00097 } 00098 else 00099 { 00100 this->rightJointName = _sdf->GetElement("rightJoint")->GetValueString(); 00101 } 00102 00103 if (!_sdf->HasElement("wheelSeparation")) 00104 { 00105 ROS_WARN("Differential Drive plugin missing <wheelSeparation>, defaults to 0.34"); 00106 this->wheelSeparation = 0.34; 00107 } 00108 else 00109 { 00110 this->wheelSeparation = _sdf->GetElement("wheelSeparation")->GetValueDouble(); 00111 } 00112 00113 if (!_sdf->HasElement("wheelDiameter")) 00114 { 00115 ROS_WARN("Differential Drive plugin missing <wheelDiameter>, defaults to 0.15"); 00116 this->wheelDiameter = 0.15; 00117 } 00118 else 00119 { 00120 this->wheelDiameter = _sdf->GetElement("wheelDiameter")->GetValueDouble(); 00121 } 00122 00123 if (!_sdf->HasElement("torque")) 00124 { 00125 ROS_WARN("Differential Drive plugin missing <torque>, defaults to 5.0"); 00126 this->torque = 5.0; 00127 } 00128 else 00129 { 00130 this->torque = _sdf->GetElement("torque")->GetValueDouble(); 00131 } 00132 00133 if (!_sdf->HasElement("topicName")) 00134 { 00135 ROS_WARN("Differential Drive plugin missing <topicName>, defaults to cmd_vel"); 00136 this->topicName = "cmd_vel"; 00137 } 00138 else 00139 { 00140 this->topicName = _sdf->GetElement("topicName")->GetValueString(); 00141 } 00142 00143 wheelSpeed[RIGHT] = 0; 00144 wheelSpeed[LEFT] = 0; 00145 00146 x_ = 0; 00147 rot_ = 0; 00148 alive_ = true; 00149 00150 joints[LEFT] = this->parent->GetJoint(leftJointName); 00151 joints[RIGHT] = this->parent->GetJoint(rightJointName); 00152 00153 if (!joints[LEFT]) { gzthrow("The controller couldn't get left hinge joint"); } 00154 if (!joints[RIGHT]) { gzthrow("The controller couldn't get right hinge joint"); } 00155 00156 // Initialize the ROS node and subscribe to cmd_vel 00157 int argc = 0; 00158 char** argv = NULL; 00159 ros::init(argc, argv, "diff_drive_plugin", ros::init_options::NoSigintHandler | ros::init_options::AnonymousName); 00160 rosnode_ = new ros::NodeHandle(this->robotNamespace); 00161 00162 ROS_INFO("starting diffdrive plugin in ns: %s", this->robotNamespace.c_str()); 00163 00164 tf_prefix_ = tf::getPrefixParam(*rosnode_); 00165 transform_broadcaster_ = new tf::TransformBroadcaster(); 00166 00167 // ROS: Subscribe to the velocity command topic (usually "cmd_vel") 00168 ros::SubscribeOptions so = 00169 ros::SubscribeOptions::create<geometry_msgs::Twist>(topicName, 1, 00170 boost::bind(&DiffDrivePlugin::cmdVelCallback, this, _1), 00171 ros::VoidPtr(), &queue_); 00172 sub_ = rosnode_->subscribe(so); 00173 pub_ = rosnode_->advertise<nav_msgs::Odometry>("odom", 1); 00174 00175 // Initialize the controller 00176 // Reset odometric pose 00177 odomPose[0] = 0.0; 00178 odomPose[1] = 0.0; 00179 odomPose[2] = 0.0; 00180 00181 odomVel[0] = 0.0; 00182 odomVel[1] = 0.0; 00183 odomVel[2] = 0.0; 00184 00185 // start custom queue for diff drive 00186 this->callback_queue_thread_ = boost::thread(boost::bind(&DiffDrivePlugin::QueueThread, this)); 00187 00188 // listen to the update event (broadcast every simulation iteration) 00189 this->updateConnection = event::Events::ConnectWorldUpdateStart(boost::bind(&DiffDrivePlugin::UpdateChild, this)); 00190 } 00191 00192 // Update the controller 00193 void DiffDrivePlugin::UpdateChild() 00194 { 00195 // TODO: Step should be in a parameter of this function 00196 double wd, ws; 00197 double d1, d2; 00198 double dr, da; 00199 double stepTime = this->world->GetPhysicsEngine()->GetStepTime(); 00200 00201 GetPositionCmd(); 00202 00203 wd = wheelDiameter; 00204 ws = wheelSeparation; 00205 00206 // Distance travelled by front wheels 00207 d1 = stepTime * wd / 2 * joints[LEFT]->GetVelocity(0); 00208 d2 = stepTime * wd / 2 * joints[RIGHT]->GetVelocity(0); 00209 00210 dr = (d1 + d2) / 2; 00211 da = (d1 - d2) / ws; 00212 00213 // Compute odometric pose 00214 odomPose[0] += dr * cos(odomPose[2]); 00215 odomPose[1] += dr * sin(odomPose[2]); 00216 odomPose[2] += da; 00217 00218 // Compute odometric instantaneous velocity 00219 odomVel[0] = dr / stepTime; 00220 odomVel[1] = 0.0; 00221 odomVel[2] = da / stepTime; 00222 00223 joints[LEFT]->SetVelocity(0, wheelSpeed[LEFT] / (wheelDiameter / 2.0)); 00224 joints[RIGHT]->SetVelocity(0, wheelSpeed[RIGHT] / (wheelDiameter / 2.0)); 00225 00226 joints[LEFT]->SetMaxForce(0, torque); 00227 joints[RIGHT]->SetMaxForce(0, torque); 00228 00229 write_position_data(); 00230 publish_odometry(); 00231 } 00232 00233 // Finalize the controller 00234 void DiffDrivePlugin::FiniChild() 00235 { 00236 alive_ = false; 00237 queue_.clear(); 00238 queue_.disable(); 00239 rosnode_->shutdown(); 00240 callback_queue_thread_.join(); 00241 } 00242 00243 void DiffDrivePlugin::GetPositionCmd() 00244 { 00245 lock.lock(); 00246 00247 double vr, va; 00248 00249 vr = x_; //myIface->data->cmdVelocity.pos.x; 00250 va = rot_; //myIface->data->cmdVelocity.yaw; 00251 00252 //std::cout << "X: [" << x_ << "] ROT: [" << rot_ << "]" << std::endl; 00253 00254 wheelSpeed[LEFT] = vr + va * wheelSeparation / 2.0; 00255 wheelSpeed[RIGHT] = vr - va * wheelSeparation / 2.0; 00256 00257 lock.unlock(); 00258 } 00259 00260 void DiffDrivePlugin::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg) 00261 { 00262 lock.lock(); 00263 00264 x_ = cmd_msg->linear.x; 00265 rot_ = cmd_msg->angular.z; 00266 00267 lock.unlock(); 00268 } 00269 00270 void DiffDrivePlugin::QueueThread() 00271 { 00272 static const double timeout = 0.01; 00273 00274 while (alive_ && rosnode_->ok()) 00275 { 00276 queue_.callAvailable(ros::WallDuration(timeout)); 00277 } 00278 } 00279 00280 void DiffDrivePlugin::publish_odometry() 00281 { 00282 ros::Time current_time = ros::Time::now(); 00283 std::string odom_frame = tf::resolve(tf_prefix_, "odom"); 00284 std::string base_footprint_frame = tf::resolve(tf_prefix_, "base_footprint"); 00285 00286 // getting data for base_footprint to odom transform 00287 math::Pose pose = this->parent->GetState().GetPose(); 00288 00289 btQuaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w); 00290 btVector3 vt(pose.pos.x, pose.pos.y, pose.pos.z); 00291 00292 tf::Transform base_footprint_to_odom(qt, vt); 00293 transform_broadcaster_->sendTransform(tf::StampedTransform(base_footprint_to_odom, 00294 current_time, 00295 odom_frame, 00296 base_footprint_frame)); 00297 00298 // publish odom topic 00299 odom_.pose.pose.position.x = pose.pos.x; 00300 odom_.pose.pose.position.y = pose.pos.y; 00301 00302 odom_.pose.pose.orientation.x = pose.rot.x; 00303 odom_.pose.pose.orientation.y = pose.rot.y; 00304 odom_.pose.pose.orientation.z = pose.rot.z; 00305 odom_.pose.pose.orientation.w = pose.rot.w; 00306 00307 math::Vector3 linear = this->parent->GetWorldLinearVel(); 00308 odom_.twist.twist.linear.x = linear.x; 00309 odom_.twist.twist.linear.y = linear.y; 00310 odom_.twist.twist.angular.z = this->parent->GetWorldAngularVel().z; 00311 00312 odom_.header.stamp = current_time; 00313 odom_.header.frame_id = odom_frame; 00314 odom_.child_frame_id = base_footprint_frame; 00315 00316 pub_.publish(odom_); 00317 } 00318 00319 // Update the data in the interface 00320 void DiffDrivePlugin::write_position_data() 00321 { 00322 // // TODO: Data timestamp 00323 // pos_iface_->data->head.time = Simulator::Instance()->GetSimTime().Double(); 00324 00325 // pose.pos.x = odomPose[0]; 00326 // pose.pos.y = odomPose[1]; 00327 // pose.rot.GetYaw() = NORMALIZE(odomPose[2]); 00328 00329 // pos_iface_->data->velocity.pos.x = odomVel[0]; 00330 // pos_iface_->data->velocity.yaw = odomVel[2]; 00331 00332 math::Pose orig_pose = this->parent->GetWorldPose(); 00333 00334 math::Pose new_pose = orig_pose; 00335 new_pose.pos.x = odomPose[0]; 00336 new_pose.pos.y = odomPose[1]; 00337 new_pose.rot.SetFromEuler(math::Vector3(0,0,odomPose[2])); 00338 00339 this->parent->SetWorldPose( new_pose ); 00340 } 00341 00342 GZ_REGISTER_MODEL_PLUGIN(DiffDrivePlugin) 00343 }