$search
00001 /* 00002 * stageros 00003 * Copyright (c) 2008, Willow Garage, Inc. 00004 * 00005 * This program is free software; you can redistribute it and/or modify 00006 * it under the terms of the GNU General Public License as published by 00007 * the Free Software Foundation; either version 2 of the License, or 00008 * (at your option) any later version. 00009 * 00010 * This program is distributed in the hope that it will be useful, 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 * GNU General Public License for more details. 00014 * 00015 * You should have received a copy of the GNU General Public License 00016 * along with this program; if not, write to the Free Software 00017 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00018 */ 00019 00027 #include <stdio.h> 00028 #include <stdlib.h> 00029 #include <string.h> 00030 00031 #include <sys/types.h> 00032 #include <sys/stat.h> 00033 #include <unistd.h> 00034 #include <signal.h> 00035 00036 00037 // libstage 00038 #include <stage.hh> 00039 00040 // roscpp 00041 #include <ros/ros.h> 00042 #include <boost/thread/mutex.hpp> 00043 #include <boost/thread/thread.hpp> 00044 #include <sensor_msgs/LaserScan.h> 00045 #include <nav_msgs/Odometry.h> 00046 #include <geometry_msgs/Twist.h> 00047 #include <rosgraph_msgs/Clock.h> 00048 00049 #include "tf/transform_broadcaster.h" 00050 00051 #define USAGE "stageros <worldfile>" 00052 #define ODOM "odom" 00053 #define BASE_SCAN "base_scan" 00054 #define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth" 00055 #define CMD_VEL "cmd_vel" 00056 00057 // Our node 00058 class StageNode 00059 { 00060 private: 00061 // Messages that we'll send or receive 00062 sensor_msgs::LaserScan *laserMsgs; 00063 nav_msgs::Odometry *odomMsgs; 00064 nav_msgs::Odometry *groundTruthMsgs; 00065 rosgraph_msgs::Clock clockMsg; 00066 00067 // roscpp-related bookkeeping 00068 ros::NodeHandle n_; 00069 00070 // A mutex to lock access to fields that are used in message callbacks 00071 boost::mutex msg_lock; 00072 00073 // The models that we're interested in 00074 std::vector<Stg::ModelLaser *> lasermodels; 00075 std::vector<Stg::ModelPosition *> positionmodels; 00076 std::vector<ros::Publisher> laser_pubs_; 00077 std::vector<ros::Publisher> odom_pubs_; 00078 std::vector<ros::Publisher> ground_truth_pubs_; 00079 std::vector<ros::Subscriber> cmdvel_subs_; 00080 ros::Publisher clock_pub_; 00081 00082 // A helper function that is executed for each stage model. We use it 00083 // to search for models of interest. 00084 static void ghfunc(Stg::Model* mod, StageNode* node); 00085 00086 static bool s_update(Stg::World* world, StageNode* node) 00087 { 00088 node->WorldCallback(); 00089 // We return false to indicate that we want to be called again (an 00090 // odd convention, but that's the way that Stage works). 00091 return false; 00092 } 00093 00094 // Appends the given robot ID to the given message name. If omitRobotID 00095 // is true, an unaltered copy of the name is returned. 00096 const char *mapName(const char *name, size_t robotID); 00097 00098 tf::TransformBroadcaster tf; 00099 00100 // Last time that we received a velocity command 00101 ros::Time base_last_cmd; 00102 ros::Duration base_watchdog_timeout; 00103 00104 // Current simulation time 00105 ros::Time sim_time; 00106 00107 public: 00108 // Constructor; stage itself needs argc/argv. fname is the .world file 00109 // that stage should load. 00110 StageNode(int argc, char** argv, bool gui, const char* fname); 00111 ~StageNode(); 00112 00113 // Subscribe to models of interest. Currently, we find and subscribe 00114 // to the first 'laser' model and the first 'position' model. Returns 00115 // 0 on success (both models subscribed), -1 otherwise. 00116 int SubscribeModels(); 00117 00118 // Our callback 00119 void WorldCallback(); 00120 00121 // Do one update of the world. May pause if the next update time 00122 // has not yet arrived. 00123 bool UpdateWorld(); 00124 00125 // Message callback for a MsgBaseVel message, which set velocities. 00126 void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg); 00127 00128 // The main simulator object 00129 Stg::World* world; 00130 }; 00131 00132 // since stageros is single-threaded, this is OK. revisit if that changes! 00133 const char * 00134 StageNode::mapName(const char *name, size_t robotID) 00135 { 00136 if (positionmodels.size() > 1) 00137 { 00138 static char buf[100]; 00139 snprintf(buf, sizeof(buf), "/robot_%u/%s", (unsigned int)robotID, name); 00140 return buf; 00141 } 00142 else 00143 return name; 00144 } 00145 00146 void 00147 StageNode::ghfunc(Stg::Model* mod, StageNode* node) 00148 { 00149 if (dynamic_cast<Stg::ModelLaser *>(mod)) 00150 node->lasermodels.push_back(dynamic_cast<Stg::ModelLaser *>(mod)); 00151 if (dynamic_cast<Stg::ModelPosition *>(mod)) 00152 node->positionmodels.push_back(dynamic_cast<Stg::ModelPosition *>(mod)); 00153 } 00154 00155 void 00156 StageNode::cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg) 00157 { 00158 boost::mutex::scoped_lock lock(msg_lock); 00159 this->positionmodels[idx]->SetSpeed(msg->linear.x, 00160 msg->linear.y, 00161 msg->angular.z); 00162 this->base_last_cmd = this->sim_time; 00163 } 00164 00165 StageNode::StageNode(int argc, char** argv, bool gui, const char* fname) 00166 { 00167 this->sim_time.fromSec(0.0); 00168 this->base_last_cmd.fromSec(0.0); 00169 double t; 00170 ros::NodeHandle localn("~"); 00171 if(!localn.getParam("base_watchdog_timeout", t)) 00172 t = 0.2; 00173 this->base_watchdog_timeout.fromSec(t); 00174 00175 // We'll check the existence of the world file, because libstage doesn't 00176 // expose its failure to open it. Could go further with checks (e.g., is 00177 // it readable by this user). 00178 struct stat s; 00179 if(stat(fname, &s) != 0) 00180 { 00181 ROS_FATAL("The world file %s does not exist.", fname); 00182 ROS_BREAK(); 00183 } 00184 00185 // initialize libstage 00186 Stg::Init( &argc, &argv ); 00187 00188 if(gui) 00189 this->world = new Stg::WorldGui(800, 700, "Stage (ROS)"); 00190 else 00191 this->world = new Stg::World(); 00192 00193 // Apparently an Update is needed before the Load to avoid crashes on 00194 // startup on some systems. 00195 this->UpdateWorld(); 00196 this->world->Load(fname); 00197 00198 // We add our callback here, after the Update, so avoid our callback 00199 // being invoked before we're ready. 00200 this->world->AddUpdateCallback((Stg::stg_world_callback_t)s_update, this); 00201 00202 this->world->ForEachDescendant((Stg::stg_model_callback_t)ghfunc, this); 00203 if (lasermodels.size() != positionmodels.size()) 00204 { 00205 ROS_FATAL("number of position models and laser models must be equal in " 00206 "the world file."); 00207 ROS_BREAK(); 00208 } 00209 size_t numRobots = positionmodels.size(); 00210 ROS_INFO("found %u position/laser pair%s in the file", 00211 (unsigned int)numRobots, (numRobots==1) ? "" : "s"); 00212 00213 this->laserMsgs = new sensor_msgs::LaserScan[numRobots]; 00214 this->odomMsgs = new nav_msgs::Odometry[numRobots]; 00215 this->groundTruthMsgs = new nav_msgs::Odometry[numRobots]; 00216 } 00217 00218 00219 // Subscribe to models of interest. Currently, we find and subscribe 00220 // to the first 'laser' model and the first 'position' model. Returns 00221 // 0 on success (both models subscribed), -1 otherwise. 00222 // 00223 // Eventually, we should provide a general way to map stage models onto ROS 00224 // topics, similar to Player .cfg files. 00225 int 00226 StageNode::SubscribeModels() 00227 { 00228 n_.setParam("/use_sim_time", true); 00229 00230 for (size_t r = 0; r < this->positionmodels.size(); r++) 00231 { 00232 if(this->lasermodels[r]) 00233 { 00234 this->lasermodels[r]->Subscribe(); 00235 } 00236 else 00237 { 00238 ROS_ERROR("no laser"); 00239 return(-1); 00240 } 00241 if(this->positionmodels[r]) 00242 { 00243 this->positionmodels[r]->Subscribe(); 00244 } 00245 else 00246 { 00247 ROS_ERROR("no position"); 00248 return(-1); 00249 } 00250 laser_pubs_.push_back(n_.advertise<sensor_msgs::LaserScan>(mapName(BASE_SCAN,r), 10)); 00251 odom_pubs_.push_back(n_.advertise<nav_msgs::Odometry>(mapName(ODOM,r), 10)); 00252 ground_truth_pubs_.push_back(n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH,r), 10)); 00253 cmdvel_subs_.push_back(n_.subscribe<geometry_msgs::Twist>(mapName(CMD_VEL,r), 10, boost::bind(&StageNode::cmdvelReceived, this, r, _1))); 00254 } 00255 clock_pub_ = n_.advertise<rosgraph_msgs::Clock>("/clock",10); 00256 return(0); 00257 } 00258 00259 StageNode::~StageNode() 00260 { 00261 delete[] laserMsgs; 00262 delete[] odomMsgs; 00263 delete[] groundTruthMsgs; 00264 } 00265 00266 bool 00267 StageNode::UpdateWorld() 00268 { 00269 return this->world->UpdateAll(); 00270 } 00271 00272 void 00273 StageNode::WorldCallback() 00274 { 00275 boost::mutex::scoped_lock lock(msg_lock); 00276 00277 this->sim_time.fromSec(world->SimTimeNow() / 1e6); 00278 // We're not allowed to publish clock==0, because it used as a special 00279 // value in parts of ROS, #4027. 00280 if(this->sim_time.sec == 0 && this->sim_time.nsec == 0) 00281 { 00282 ROS_DEBUG("Skipping initial simulation step, to avoid publishing clock==0"); 00283 return; 00284 } 00285 00286 // TODO make this only affect one robot if necessary 00287 if((this->base_watchdog_timeout.toSec() > 0.0) && 00288 ((this->sim_time - this->base_last_cmd) >= this->base_watchdog_timeout)) 00289 { 00290 for (size_t r = 0; r < this->positionmodels.size(); r++) 00291 this->positionmodels[r]->SetSpeed(0.0, 0.0, 0.0); 00292 } 00293 00294 // Get latest laser data 00295 for (size_t r = 0; r < this->lasermodels.size(); r++) 00296 { 00297 std::vector<Stg::ModelLaser::Sample> samples = this->lasermodels[r]->GetSamples(); 00298 if(samples.size()) 00299 { 00300 // Translate into ROS message format and publish 00301 Stg::ModelLaser::Config cfg = this->lasermodels[r]->GetConfig(); 00302 this->laserMsgs[r].angle_min = -cfg.fov/2.0; 00303 this->laserMsgs[r].angle_max = +cfg.fov/2.0; 00304 this->laserMsgs[r].angle_increment = cfg.fov/(double)(cfg.sample_count-1); 00305 this->laserMsgs[r].range_min = 0.0; 00306 this->laserMsgs[r].range_max = cfg.range_bounds.max; 00307 this->laserMsgs[r].ranges.resize(cfg.sample_count); 00308 this->laserMsgs[r].intensities.resize(cfg.sample_count); 00309 for(unsigned int i=0;i<cfg.sample_count;i++) 00310 { 00311 this->laserMsgs[r].ranges[i] = samples[i].range; 00312 this->laserMsgs[r].intensities[i] = (uint8_t)samples[i].reflectance; 00313 } 00314 00315 this->laserMsgs[r].header.frame_id = mapName("base_laser_link", r); 00316 this->laserMsgs[r].header.stamp = sim_time; 00317 this->laser_pubs_[r].publish(this->laserMsgs[r]); 00318 } 00319 00320 // Also publish the base->base_laser_link Tx. This could eventually move 00321 // into being retrieved from the param server as a static Tx. 00322 Stg::Pose lp = this->lasermodels[r]->GetPose(); 00323 tf::Quaternion laserQ; 00324 laserQ.setRPY(0.0, 0.0, lp.a); 00325 tf::Transform txLaser = tf::Transform(laserQ, 00326 tf::Point(lp.x, lp.y, 0.15)); 00327 tf.sendTransform(tf::StampedTransform(txLaser, sim_time, 00328 mapName("base_link", r), 00329 mapName("base_laser_link", r))); 00330 00331 // Send the identity transform between base_footprint and base_link 00332 tf::Transform txIdentity(tf::createIdentityQuaternion(), 00333 tf::Point(0, 0, 0)); 00334 tf.sendTransform(tf::StampedTransform(txIdentity, 00335 sim_time, 00336 mapName("base_footprint", r), 00337 mapName("base_link", r))); 00338 00339 // Get latest odometry data 00340 // Translate into ROS message format and publish 00341 this->odomMsgs[r].pose.pose.position.x = this->positionmodels[r]->est_pose.x; 00342 this->odomMsgs[r].pose.pose.position.y = this->positionmodels[r]->est_pose.y; 00343 this->odomMsgs[r].pose.pose.orientation = tf::createQuaternionMsgFromYaw(this->positionmodels[r]->est_pose.a); 00344 Stg::Velocity v = this->positionmodels[r]->GetVelocity(); 00345 this->odomMsgs[r].twist.twist.linear.x = v.x; 00346 this->odomMsgs[r].twist.twist.linear.y = v.y; 00347 this->odomMsgs[r].twist.twist.angular.z = v.a; 00348 00349 //@todo Publish stall on a separate topic when one becomes available 00350 //this->odomMsgs[r].stall = this->positionmodels[r]->Stall(); 00351 // 00352 this->odomMsgs[r].header.frame_id = mapName("odom", r); 00353 this->odomMsgs[r].header.stamp = sim_time; 00354 00355 this->odom_pubs_[r].publish(this->odomMsgs[r]); 00356 00357 // broadcast odometry transform 00358 tf::Quaternion odomQ; 00359 tf::quaternionMsgToTF(odomMsgs[r].pose.pose.orientation, odomQ); 00360 tf::Transform txOdom(odomQ, 00361 tf::Point(odomMsgs[r].pose.pose.position.x, 00362 odomMsgs[r].pose.pose.position.y, 0.0)); 00363 tf.sendTransform(tf::StampedTransform(txOdom, sim_time, 00364 mapName("odom", r), 00365 mapName("base_footprint", r))); 00366 00367 // Also publish the ground truth pose and velocity 00368 Stg::Pose gpose = this->positionmodels[r]->GetGlobalPose(); 00369 Stg::Velocity gvel = this->positionmodels[r]->GetGlobalVelocity(); 00370 // Note that we correct for Stage's screwed-up coord system. 00371 tf::Quaternion q_gpose; 00372 q_gpose.setRPY(0.0, 0.0, gpose.a-M_PI/2.0); 00373 tf::Transform gt(q_gpose, tf::Point(gpose.y, -gpose.x, 0.0)); 00374 tf::Quaternion q_gvel; 00375 q_gvel.setRPY(0.0, 0.0, gvel.a-M_PI/2.0); 00376 tf::Transform gv(q_gvel, tf::Point(gvel.y, -gvel.x, 0.0)); 00377 00378 this->groundTruthMsgs[r].pose.pose.position.x = gt.getOrigin().x(); 00379 this->groundTruthMsgs[r].pose.pose.position.y = gt.getOrigin().y(); 00380 this->groundTruthMsgs[r].pose.pose.position.z = gt.getOrigin().z(); 00381 this->groundTruthMsgs[r].pose.pose.orientation.x = gt.getRotation().x(); 00382 this->groundTruthMsgs[r].pose.pose.orientation.y = gt.getRotation().y(); 00383 this->groundTruthMsgs[r].pose.pose.orientation.z = gt.getRotation().z(); 00384 this->groundTruthMsgs[r].pose.pose.orientation.w = gt.getRotation().w(); 00385 this->groundTruthMsgs[r].twist.twist.linear.x = gv.getOrigin().x(); 00386 this->groundTruthMsgs[r].twist.twist.linear.y = gv.getOrigin().y(); 00387 //this->groundTruthMsgs[r].twist.twist.angular.z = tf::getYaw(gv.getRotation()); 00388 //this->groundTruthMsgs[r].twist.twist.linear.x = gvel.x; 00389 //this->groundTruthMsgs[r].twist.twist.linear.y = gvel.y; 00390 this->groundTruthMsgs[r].twist.twist.angular.z = gvel.a; 00391 00392 this->groundTruthMsgs[r].header.frame_id = mapName("odom", r); 00393 this->groundTruthMsgs[r].header.stamp = sim_time; 00394 00395 this->ground_truth_pubs_[r].publish(this->groundTruthMsgs[r]); 00396 } 00397 00398 this->clockMsg.clock = sim_time; 00399 this->clock_pub_.publish(this->clockMsg); 00400 } 00401 00402 static bool quit = false; 00403 void 00404 sigint_handler(int num) 00405 { 00406 quit = true; 00407 } 00408 00409 int 00410 main(int argc, char** argv) 00411 { 00412 if( argc < 2 ) 00413 { 00414 puts(USAGE); 00415 exit(-1); 00416 } 00417 00418 ros::init(argc, argv, "stageros"); 00419 00420 bool gui = true; 00421 for(int i=0;i<(argc-1);i++) 00422 { 00423 if(!strcmp(argv[i], "-g")) 00424 gui = false; 00425 } 00426 00427 StageNode sn(argc-1,argv,gui,argv[argc-1]); 00428 00429 if(sn.SubscribeModels() != 0) 00430 exit(-1); 00431 00432 boost::thread t = boost::thread(boost::bind(&ros::spin)); 00433 00434 // TODO: get rid of this fixed-duration sleep, using some Stage builtin 00435 // PauseUntilNextUpdate() functionality. 00436 ros::WallRate r(10.0); 00437 while(ros::ok() && !sn.world->TestQuit()) 00438 { 00439 if(gui) 00440 Fl::wait(r.expectedCycleTime().toSec()); 00441 else 00442 { 00443 sn.UpdateWorld(); 00444 r.sleep(); 00445 } 00446 } 00447 t.join(); 00448 00449 exit(0); 00450 } 00451