$search
00001 /* 00002 * Gazebo - Outdoor Multi-Robot Simulator 00003 * Copyright (C) 2003 00004 * Nate Koenig & Andrew Howard 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 of the License, or 00009 * (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 * 00020 */ 00021 00022 /* 00023 * Desc: ROS interface to a Position2d controller for a Differential drive with covariance information in odom message 00024 * Author: Jose Capriles (adapted from Daniel Hewlett and Nathan Koenig) 00025 */ 00026 00027 00028 #include <algorithm> 00029 #include <assert.h> 00030 00031 #include <reem_diffdrive_plugin/reem_diffdrive_plugin.h> 00032 00033 #include <gazebo/gazebo.h> 00034 #include <gazebo/GazeboError.hh> 00035 #include <gazebo/Quatern.hh> 00036 #include <gazebo/Controller.hh> 00037 #include <gazebo/Body.hh> 00038 #include <gazebo/World.hh> 00039 #include <gazebo/Simulator.hh> 00040 #include <gazebo/Global.hh> 00041 #include <gazebo/XMLConfig.hh> 00042 #include <gazebo/ControllerFactory.hh> 00043 #include <gazebo/PhysicsEngine.hh> 00044 00045 #include <ros/ros.h> 00046 #include <tf/transform_broadcaster.h> 00047 #include <tf/transform_listener.h> 00048 #include <geometry_msgs/Twist.h> 00049 #include <nav_msgs/Odometry.h> 00050 #include <boost/bind.hpp> 00051 #include <boost/assign/list_of.hpp> 00052 00053 using namespace gazebo; 00054 00055 GZ_REGISTER_DYNAMIC_CONTROLLER("reem_diffdrive_plugin", reemDiffdrivePlugin); 00056 00057 enum 00058 { 00059 RIGHT, LEFT 00060 }; 00061 00062 // Constructor 00063 reemDiffdrivePlugin::reemDiffdrivePlugin(Entity *parent) : 00064 Controller(parent) 00065 { 00066 parent_ = dynamic_cast<Model*> (parent); 00067 00068 if (!parent_) 00069 gzthrow("Differential_Position2d controller requires a Model as its parent"); 00070 00071 enableMotors = true; 00072 00073 wheelSpeed[RIGHT] = 0; 00074 wheelSpeed[LEFT] = 0; 00075 00076 prevUpdateTime = Simulator::Instance()->GetSimTime(); 00077 00078 Param::Begin(¶meters); 00079 leftJointNameP = new ParamT<std::string> ("leftJoint", "", 1); 00080 rightJointNameP = new ParamT<std::string> ("rightJoint", "", 1); 00081 wheelSepP = new ParamT<float> ("wheelSeparation", 0.34, 1); 00082 wheelDiamP = new ParamT<float> ("wheelDiameter", 0.15, 1); 00083 torqueP = new ParamT<float> ("torque", 10.0, 1); 00084 robotNamespaceP = new ParamT<std::string> ("robotNamespace", "/", 0); 00085 topicNameP = new ParamT<std::string> ("topicName", "", 1); 00086 Param::End(); 00087 00088 x_ = 0; 00089 rot_ = 0; 00090 alive_ = true; 00091 } 00092 00093 // Destructor 00094 reemDiffdrivePlugin::~reemDiffdrivePlugin() 00095 { 00096 delete leftJointNameP; 00097 delete rightJointNameP; 00098 delete wheelSepP; 00099 delete wheelDiamP; 00100 delete torqueP; 00101 delete robotNamespaceP; 00102 delete topicNameP; 00103 delete callback_queue_thread_; 00104 delete rosnode_; 00105 delete transform_broadcaster_; 00106 } 00107 00108 // Load the controller 00109 void reemDiffdrivePlugin::LoadChild(XMLConfigNode *node) 00110 { 00111 pos_iface_ = dynamic_cast<libgazebo::PositionIface*> (GetIface("position")); 00112 00113 // the defaults are from pioneer2dx 00114 wheelSepP->Load(node); 00115 wheelDiamP->Load(node); 00116 torqueP->Load(node); 00117 00118 leftJointNameP->Load(node); 00119 rightJointNameP->Load(node); 00120 00121 joints[LEFT] = parent_->GetJoint(**leftJointNameP); 00122 joints[RIGHT] = parent_->GetJoint(**rightJointNameP); 00123 00124 if (!joints[LEFT]) 00125 gzthrow("The controller couldn't get left hinge joint"); 00126 00127 if (!joints[RIGHT]) 00128 gzthrow("The controller couldn't get right hinge joint"); 00129 00130 // Initialize the ROS node and subscribe to cmd_vel 00131 00132 robotNamespaceP->Load(node); 00133 robotNamespace = robotNamespaceP->GetValue(); 00134 00135 int argc = 0; 00136 char** argv = NULL; 00137 ros::init(argc, argv, "reem_diffdrive_plugin", ros::init_options::NoSigintHandler | ros::init_options::AnonymousName); 00138 rosnode_ = new ros::NodeHandle(robotNamespace); 00139 00140 tf_prefix_ = tf::getPrefixParam(*rosnode_); 00141 transform_broadcaster_ = new tf::TransformBroadcaster(); 00142 00143 topicNameP->Load(node); 00144 topicName = topicNameP->GetValue(); 00145 00146 // ROS: Subscribe to the velocity command topic (usually "cmd_vel") 00147 ros::SubscribeOptions so = 00148 ros::SubscribeOptions::create<geometry_msgs::Twist>("/cmd_vel", 1, 00149 boost::bind(&reemDiffdrivePlugin::cmdVelCallback, this, _1), 00150 ros::VoidPtr(), &queue_); 00151 sub_ = rosnode_->subscribe(so); 00152 pub_ = rosnode_->advertise<nav_msgs::Odometry>("/erratic_odometry/odom", 1); 00153 } 00154 00155 // Initialize the controller 00156 void reemDiffdrivePlugin::InitChild() 00157 { 00158 // Reset odometric pose 00159 odomPose[0] = 0.0; 00160 odomPose[1] = 0.0; 00161 odomPose[2] = 0.0; 00162 00163 odomVel[0] = 0.0; 00164 odomVel[1] = 0.0; 00165 odomVel[2] = 0.0; 00166 00167 callback_queue_thread_ = new boost::thread(boost::bind(&reemDiffdrivePlugin::QueueThread, this)); 00168 } 00169 00170 // Load the controller 00171 void reemDiffdrivePlugin::SaveChild(std::string &prefix, std::ostream &stream) 00172 { 00173 stream << prefix << *(leftJointNameP) << "\n"; 00174 stream << prefix << *(rightJointNameP) << "\n"; 00175 stream << prefix << *(torqueP) << "\n"; 00176 stream << prefix << *(wheelDiamP) << "\n"; 00177 stream << prefix << *(wheelSepP) << "\n"; 00178 } 00179 00180 // Reset 00181 void reemDiffdrivePlugin::ResetChild() 00182 { 00183 // Reset odometric pose 00184 odomPose[0] = 0.0; 00185 odomPose[1] = 0.0; 00186 odomPose[2] = 0.0; 00187 00188 odomVel[0] = 0.0; 00189 odomVel[1] = 0.0; 00190 odomVel[2] = 0.0; 00191 } 00192 00193 // Update the controller 00194 void reemDiffdrivePlugin::UpdateChild() 00195 { 00196 // TODO: Step should be in a parameter of this function 00197 double wd, ws; 00198 double d1, d2; 00199 double dr, da; 00200 Time stepTime; 00201 00202 //myIface->Lock(1); 00203 00204 GetPositionCmd(); 00205 00206 wd = **(wheelDiamP); 00207 ws = **(wheelSepP); 00208 00209 //stepTime = World::Instance()->GetPhysicsEngine()->GetStepTime(); 00210 stepTime = Simulator::Instance()->GetSimTime() - prevUpdateTime; 00211 prevUpdateTime = Simulator::Instance()->GetSimTime(); 00212 00213 // Distance travelled by front wheels 00214 d1 = stepTime.Double() * wd / 2 * joints[LEFT]->GetVelocity(0); 00215 d2 = stepTime.Double() * wd / 2 * joints[RIGHT]->GetVelocity(0); 00216 00217 dr = (d1 + d2) / 2; 00218 da = (d1 - d2) / ws; 00219 00220 // Compute odometric pose 00221 odomPose[0] += dr * cos(odomPose[2]); 00222 odomPose[1] += dr * sin(odomPose[2]); 00223 odomPose[2] += da; 00224 00225 // Compute odometric instantaneous velocity 00226 odomVel[0] = dr / stepTime.Double(); 00227 odomVel[1] = 0.0; 00228 odomVel[2] = da / stepTime.Double(); 00229 00230 if (enableMotors) 00231 { 00232 joints[LEFT]->SetVelocity(0, wheelSpeed[LEFT] / (**(wheelDiamP) / 2.0)); 00233 00234 joints[RIGHT]->SetVelocity(0, wheelSpeed[RIGHT] / (**(wheelDiamP) / 2.0)); 00235 00236 joints[LEFT]->SetMaxForce(0, **(torqueP)); 00237 joints[RIGHT]->SetMaxForce(0, **(torqueP)); 00238 } 00239 00240 write_position_data(); 00241 publish_odometry(); 00242 00243 //myIface->Unlock(); 00244 } 00245 00246 // Finalize the controller 00247 void reemDiffdrivePlugin::FiniChild() 00248 { 00249 //std::cout << "ENTERING FINALIZE\n"; 00250 alive_ = false; 00251 // Custom Callback Queue 00252 queue_.clear(); 00253 queue_.disable(); 00254 rosnode_->shutdown(); 00255 callback_queue_thread_->join(); 00256 //std::cout << "EXITING FINALIZE\n"; 00257 } 00258 00259 // NEW: Now uses the target velocities from the ROS message, not the Iface 00260 void reemDiffdrivePlugin::GetPositionCmd() 00261 { 00262 lock.lock(); 00263 00264 double vr, va; 00265 00266 vr = x_; //myIface->data->cmdVelocity.pos.x; 00267 va = rot_; //myIface->data->cmdVelocity.yaw; 00268 00269 //std::cout << "X: [" << x_ << "] ROT: [" << rot_ << "]" << std::endl; 00270 00271 // Changed motors to be always on, which is probably what we want anyway 00272 enableMotors = true; //myIface->data->cmdEnableMotors > 0; 00273 00274 //std::cout << enableMotors << std::endl; 00275 00276 wheelSpeed[LEFT] = vr + va * **(wheelSepP) / 2; 00277 wheelSpeed[RIGHT] = vr - va * **(wheelSepP) / 2; 00278 00279 lock.unlock(); 00280 } 00281 00282 // NEW: Store the velocities from the ROS message 00283 void reemDiffdrivePlugin::cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg) 00284 { 00285 //std::cout << "BEGIN CALLBACK\n"; 00286 00287 lock.lock(); 00288 00289 x_ = cmd_msg->linear.x; 00290 rot_ = cmd_msg->angular.z; 00291 00292 lock.unlock(); 00293 00294 //std::cout << "END CALLBACK\n"; 00295 } 00296 00297 // NEW: custom callback queue thread 00298 void reemDiffdrivePlugin::QueueThread() 00299 { 00300 static const double timeout = 0.01; 00301 00302 while (alive_ && rosnode_->ok()) 00303 { 00304 // std::cout << "CALLING STUFF\n"; 00305 queue_.callAvailable(ros::WallDuration(timeout)); 00306 } 00307 } 00308 00309 // NEW: Update this to publish odometry topic 00310 void reemDiffdrivePlugin::publish_odometry() 00311 { 00312 // get current time 00313 ros::Time current_time_((Simulator::Instance()->GetSimTime()).sec, (Simulator::Instance()->GetSimTime()).nsec); 00314 00315 // getting data for base_footprint to odom transform 00316 btQuaternion qt; 00317 // TODO: Is there something wrong here? RVIZ has a problem? 00318 qt.setEulerZYX(pos_iface_->data->pose.yaw, pos_iface_->data->pose.pitch, pos_iface_->data->pose.roll); 00319 btVector3 vt(pos_iface_->data->pose.pos.x, pos_iface_->data->pose.pos.y, pos_iface_->data->pose.pos.z); 00320 tf::Transform base_footprint_to_odom(qt, vt); 00321 00322 transform_broadcaster_->sendTransform(tf::StampedTransform(base_footprint_to_odom, 00323 current_time_, 00324 "odom", 00325 "base_footprint")); 00326 00327 // publish odom topic 00328 odom_.pose.pose.position.x = pos_iface_->data->pose.pos.x; 00329 odom_.pose.pose.position.y = pos_iface_->data->pose.pos.y; 00330 00331 gazebo::Quatern rot; 00332 rot.SetFromEuler(gazebo::Vector3(pos_iface_->data->pose.roll, pos_iface_->data->pose.pitch, pos_iface_->data->pose.yaw)); 00333 00334 odom_.pose.pose.orientation.x = rot.x; 00335 odom_.pose.pose.orientation.y = rot.y; 00336 odom_.pose.pose.orientation.z = rot.z; 00337 odom_.pose.pose.orientation.w = rot.u; 00338 00339 odom_.pose.covariance = boost::assign::list_of(1e-3) (0) (0) (0) (0) (0) 00340 (0) (1e-3) (0) (0) (0) (0) 00341 (0) (0) (1e6) (0) (0) (0) 00342 (0) (0) (0) (1e6) (0) (0) 00343 (0) (0) (0) (0) (1e6) (0) 00344 (0) (0) (0) (0) (0) (1e3) ; 00345 00346 odom_.twist.twist.linear.x = pos_iface_->data->velocity.pos.x; 00347 odom_.twist.twist.linear.y = pos_iface_->data->velocity.pos.y; 00348 odom_.twist.twist.angular.z = pos_iface_->data->velocity.yaw; 00349 00350 odom_.twist.covariance = boost::assign::list_of(1e-3) (0) (0) (0) (0) (0) 00351 (0) (1e-3) (0) (0) (0) (0) 00352 (0) (0) (1e6) (0) (0) (0) 00353 (0) (0) (0) (1e6) (0) (0) 00354 (0) (0) (0) (0) (1e6) (0) 00355 (0) (0) (0) (0) (0) (1e3) ; 00356 00357 odom_.header.frame_id = tf::resolve(tf_prefix_, "odom"); 00358 odom_.child_frame_id = "base_footprint"; 00359 00360 //odom_.header.stamp = current_time_; 00361 odom_.header.stamp.sec = (Simulator::Instance()->GetSimTime()).sec; 00362 odom_.header.stamp.nsec = (Simulator::Instance()->GetSimTime()).nsec; 00363 00364 pub_.publish(odom_); 00365 } 00366 00367 // Update the data in the interface 00368 void reemDiffdrivePlugin::write_position_data() 00369 { 00370 // TODO: Data timestamp 00371 pos_iface_->data->head.time = Simulator::Instance()->GetSimTime().Double(); 00372 00373 pos_iface_->data->pose.pos.x = odomPose[0]; 00374 pos_iface_->data->pose.pos.y = odomPose[1]; 00375 pos_iface_->data->pose.yaw = NORMALIZE(odomPose[2]); 00376 00377 pos_iface_->data->velocity.pos.x = odomVel[0]; 00378 pos_iface_->data->velocity.yaw = odomVel[2]; 00379 00380 // TODO 00381 pos_iface_->data->stall = 0; 00382 } 00383