diffdrive_plugin_6w.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
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 Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 // Constructor
00061 DiffDrivePlugin6W::DiffDrivePlugin6W()
00062 {
00063 }
00064 
00065 // Destructor
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 // Load the controller
00076 void DiffDrivePlugin6W::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00077 {
00078   world = _model->GetWorld();
00079 
00080   // default parameters
00081   namespace_.clear();
00082   topic_ = "cmd_vel";
00083   wheelSep = 0.34;
00084   wheelDiam = 0.15;
00085   torque = 10.0;
00086 
00087   // load parameters
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   // assert that the body by link_name_ exists
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   // Make sure the ROS node for Gazebo has already been initialized
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   // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
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   // New Mechanism for Updating every World Cycle
00159   // Listen to the update event. This event is broadcast every
00160   // simulation iteration.
00161   updateConnection = event::Events::ConnectWorldUpdateBegin(
00162       boost::bind(&DiffDrivePlugin6W::Update, this));
00163 }
00164 
00165 // Initialize the controller
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   // Reset odometric pose
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 // Update the controller
00191 void DiffDrivePlugin6W::Update()
00192 {
00193   // TODO: Step should be in a parameter of this function
00194   double d1, d2;
00195   double dr, da;
00196   common::Time stepTime;
00197 
00198   GetPositionCmd();
00199 
00200   //stepTime = World::Instance()->GetPhysicsEngine()->GetStepTime();
00201   stepTime = world->GetSimTime() - prevUpdateTime;
00202   prevUpdateTime = world->GetSimTime();
00203 
00204   // Distance travelled by front wheels
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   // Compute odometric pose
00212   odomPose[0] += dr * cos(odomPose[2]);
00213   odomPose[1] += dr * sin(odomPose[2]);
00214   odomPose[2] += da;
00215 
00216   // Compute odometric instantaneous velocity
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   //publish_odometry();
00241 }
00242 
00243 // NEW: Now uses the target velocities from the ROS message, not the Iface 
00244 void DiffDrivePlugin6W::GetPositionCmd()
00245 {
00246   lock.lock();
00247 
00248   double vr, va;
00249 
00250   vr = x_; //myIface->data->cmdVelocity.pos.x;
00251   va = -rot_; //myIface->data->cmdVelocity.yaw;
00252 
00253   //std::cout << "X: [" << x_ << "] ROT: [" << rot_ << "]" << std::endl;
00254 
00255   // Changed motors to be always on, which is probably what we want anyway
00256   enableMotors = true; //myIface->data->cmdEnableMotors > 0;
00257 
00258   //std::cout << enableMotors << std::endl;
00259 
00260   wheelSpeed[0] = vr + va * wheelSep / 2;
00261   wheelSpeed[1] = vr - va * wheelSep / 2;
00262 
00263   lock.unlock();
00264 }
00265 
00266 // NEW: Store the velocities from the ROS message
00267 void DiffDrivePlugin6W::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg)
00268 {
00269   //std::cout << "BEGIN CALLBACK\n";
00270 
00271   lock.lock();
00272 
00273   x_ = cmd_msg->linear.x;
00274   rot_ = cmd_msg->angular.z;
00275 
00276   lock.unlock();
00277 
00278   //std::cout << "END CALLBACK\n";
00279 }
00280 
00281 // NEW: custom callback queue thread
00282 void DiffDrivePlugin6W::QueueThread()
00283 {
00284   static const double timeout = 0.01;
00285 
00286   while (alive_ && rosnode_->ok())
00287   {
00288     //    std::cout << "CALLING STUFF\n";
00289     queue_.callAvailable(ros::WallDuration(timeout));
00290   }
00291 }
00292 
00293 // NEW: Update this to publish odometry topic
00294 void DiffDrivePlugin6W::publish_odometry()
00295 {
00296   // get current time
00297   ros::Time current_time_((world->GetSimTime()).sec, (world->GetSimTime()).nsec); 
00298 
00299   // getting data for base_footprint to odom transform
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   // publish odom topic
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 } // namespace gazebo


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Wed Aug 26 2015 11:44:35