$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 * Desc: Ros Laser controller. 00023 * Author: Nathan Koenig 00024 * Date: 01 Feb 2007 00025 * SVN info: $Id: gazebo_ros_laser.cpp 6683 2008-06-25 19:12:30Z natepak $ 00026 */ 00027 00028 #include <algorithm> 00029 #include <assert.h> 00030 00031 #include <gazebo_plugins/gazebo_ros_laser.h> 00032 00033 #include <gazebo/Sensor.hh> 00034 #include <gazebo/Global.hh> 00035 #include <gazebo/XMLConfig.hh> 00036 #include <gazebo/HingeJoint.hh> 00037 #include <gazebo/World.hh> 00038 #include <gazebo/Simulator.hh> 00039 #include <gazebo/gazebo.h> 00040 #include <gazebo/GazeboError.hh> 00041 #include <gazebo/ControllerFactory.hh> 00042 #include <gazebo/RaySensor.hh> 00043 00044 namespace gazebo 00045 { 00046 00047 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_laser", GazeboRosLaser); 00048 00050 // Constructor 00051 GazeboRosLaser::GazeboRosLaser(Entity *parent) 00052 : Controller(parent) 00053 { 00054 this->myParent = dynamic_cast<RaySensor*>(this->parent); 00055 00056 if (!this->myParent) 00057 gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent"); 00058 00059 Param::Begin(&this->parameters); 00060 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00061 this->hokuyoMinIntensityP = new ParamT<double>("hokuyoMinIntensity", 101.0, 0); 00062 this->gaussianNoiseP = new ParamT<double>("gaussianNoise", 0.0, 0); 00063 this->topicNameP = new ParamT<std::string>("topicName", "", 1); 00064 this->deprecatedTopicNameP = new ParamT<std::string>("deprecatedTopicName", "", 0); 00065 this->frameNameP = new ParamT<std::string>("frameName", "default_gazebo_ros_laser_frame", 0); 00066 Param::End(); 00067 00068 this->laserConnectCount = 0; 00069 this->deprecatedLaserConnectCount = 0; 00070 } 00071 00073 // Destructor 00074 GazeboRosLaser::~GazeboRosLaser() 00075 { 00076 delete this->robotNamespaceP; 00077 delete this->hokuyoMinIntensityP; 00078 delete this->gaussianNoiseP; 00079 delete this->topicNameP; 00080 delete this->deprecatedTopicNameP; 00081 delete this->frameNameP; 00082 delete this->rosnode_; 00083 } 00084 00086 // Load the controller 00087 void GazeboRosLaser::LoadChild(XMLConfigNode *node) 00088 { 00089 this->robotNamespaceP->Load(node); 00090 this->robotNamespace = this->robotNamespaceP->GetValue(); 00091 00092 if (!ros::isInitialized()) 00093 { 00094 int argc = 0; 00095 char** argv = NULL; 00096 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00097 } 00098 00099 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00100 00101 this->hokuyoMinIntensityP->Load(node); 00102 this->hokuyoMinIntensity = this->hokuyoMinIntensityP->GetValue(); 00103 ROS_INFO("INFO: gazebo_ros_laser plugin artifically sets minimum intensity to %f due to cutoff in hokuyo filters." , this->hokuyoMinIntensity); 00104 00105 this->topicNameP->Load(node); 00106 this->topicName = this->topicNameP->GetValue(); 00107 this->deprecatedTopicNameP->Load(node); 00108 this->deprecatedTopicName = this->deprecatedTopicNameP->GetValue(); 00109 this->frameNameP->Load(node); 00110 this->frameName = this->frameNameP->GetValue(); 00111 this->gaussianNoiseP->Load(node); 00112 this->gaussianNoise = this->gaussianNoiseP->GetValue(); 00113 00114 if (this->topicName != "") 00115 { 00116 #ifdef USE_CBQ 00117 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::LaserScan>( 00118 this->topicName,1, 00119 boost::bind( &GazeboRosLaser::LaserConnect,this), 00120 boost::bind( &GazeboRosLaser::LaserDisconnect,this), ros::VoidPtr(), &this->laser_queue_); 00121 this->pub_ = this->rosnode_->advertise(ao); 00122 #else 00123 this->pub_ = this->rosnode_->advertise<sensor_msgs::LaserScan>(this->topicName,1, 00124 boost::bind( &GazeboRosLaser::LaserConnect, this), 00125 boost::bind( &GazeboRosLaser::LaserDisconnect, this)); 00126 #endif 00127 } 00128 00129 if (this->deprecatedTopicName != "") 00130 { 00131 #ifdef USE_CBQ 00132 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::LaserScan>( 00133 this->deprecatedTopicName,1, 00134 boost::bind( &GazeboRosLaser::DeprecatedLaserConnect,this), 00135 boost::bind( &GazeboRosLaser::DeprecatedLaserDisconnect,this), ros::VoidPtr(), &this->laser_queue_); 00136 this->deprecated_pub_ = this->rosnode_->advertise(ao); 00137 #else 00138 this->deprecated_pub_ = this->rosnode_->advertise<sensor_msgs::LaserScan>(this->deprecatedTopicName,1, 00139 boost::bind( &GazeboRosLaser::DeprecatedLaserConnect, this), 00140 boost::bind( &GazeboRosLaser::DeprecatedLaserDisconnect, this)); 00141 #endif 00142 } 00143 } 00144 00146 // Initialize the controller 00147 void GazeboRosLaser::InitChild() 00148 { 00149 // sensor generation off by default 00150 this->myParent->SetActive(false); 00151 #ifdef USE_CBQ 00152 // start custom queue for laser 00153 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosLaser::LaserQueueThread,this ) ); 00154 #endif 00155 } 00156 00158 // Increment count 00159 void GazeboRosLaser::LaserConnect() 00160 { 00161 this->laserConnectCount++; 00162 } 00164 // Decrement count 00165 void GazeboRosLaser::LaserDisconnect() 00166 { 00167 this->laserConnectCount--; 00168 00169 if (this->laserConnectCount == 0 && this->deprecatedLaserConnectCount == 0) 00170 this->myParent->SetActive(false); 00171 } 00172 00174 // Increment count 00175 void GazeboRosLaser::DeprecatedLaserConnect() 00176 { 00177 ROS_WARN("you are subscribing to a deprecated ROS topic %s, please change your code/launch script to use new ROS topic %s", 00178 this->deprecatedTopicName.c_str(), this->topicName.c_str()); 00179 this->deprecatedLaserConnectCount++; 00180 } 00182 // Decrement count 00183 void GazeboRosLaser::DeprecatedLaserDisconnect() 00184 { 00185 this->deprecatedLaserConnectCount--; 00186 00187 if (this->laserConnectCount == 0 && this->deprecatedLaserConnectCount == 0) 00188 this->myParent->SetActive(false); 00189 } 00190 00192 // Update the controller 00193 void GazeboRosLaser::UpdateChild() 00194 { 00195 // as long as ros is connected, parent is active 00196 //ROS_ERROR("debug laser count %d",this->laserConnectCount); 00197 if (!this->myParent->IsActive()) 00198 { 00199 // do this first so there's chance for sensor to run 1 frame after activate 00200 if ((this->laserConnectCount > 0 && this->topicName != "") || 00201 (this->deprecatedLaserConnectCount > 0 && this->deprecatedTopicName != "")) 00202 this->myParent->SetActive(true); 00203 } 00204 else 00205 { 00206 this->PutLaserData(); 00207 } 00208 } 00209 00211 // Finalize the controller 00212 void GazeboRosLaser::FiniChild() 00213 { 00214 this->laser_queue_.clear(); 00215 this->laser_queue_.disable(); 00216 this->rosnode_->shutdown(); 00217 sleep(1); 00218 #ifdef USE_CBQ 00219 this->callback_queue_thread_.join(); 00220 #endif 00221 } 00222 00224 // Put laser data to the interface 00225 void GazeboRosLaser::PutLaserData() 00226 { 00227 int i, ja, jb; 00228 double ra, rb, r, b; 00229 double intensity; 00230 00231 Angle maxAngle = this->myParent->GetMaxAngle(); 00232 Angle minAngle = this->myParent->GetMinAngle(); 00233 00234 double maxRange = this->myParent->GetMaxRange(); 00235 double minRange = this->myParent->GetMinRange(); 00236 int rayCount = this->myParent->GetRayCount(); 00237 int rangeCount = this->myParent->GetRangeCount(); 00238 00239 /***************************************************************/ 00240 /* */ 00241 /* point scan from laser */ 00242 /* */ 00243 /***************************************************************/ 00244 this->lock.lock(); 00245 // Add Frame Name 00246 this->laserMsg.header.frame_id = this->frameName; 00247 this->laserMsg.header.stamp.sec = (Simulator::Instance()->GetSimTime()).sec; 00248 this->laserMsg.header.stamp.nsec = (Simulator::Instance()->GetSimTime()).nsec; 00249 00250 00251 double tmp_res_angle = (maxAngle.GetAsRadian() - minAngle.GetAsRadian())/((double)(rangeCount -1)); // for computing yaw 00252 this->laserMsg.angle_min = minAngle.GetAsRadian(); 00253 this->laserMsg.angle_max = maxAngle.GetAsRadian(); 00254 this->laserMsg.angle_increment = tmp_res_angle; 00255 this->laserMsg.time_increment = 0; // instantaneous simulator scan 00256 this->laserMsg.scan_time = 0; // FIXME: what's this? 00257 this->laserMsg.range_min = minRange; 00258 this->laserMsg.range_max = maxRange; 00259 this->laserMsg.ranges.clear(); 00260 this->laserMsg.intensities.clear(); 00261 00262 // Interpolate the range readings from the rays 00263 for (i = 0; i<rangeCount; i++) 00264 { 00265 b = (double) i * (rayCount - 1) / (rangeCount - 1); 00266 ja = (int) floor(b); 00267 jb = std::min(ja + 1, rayCount - 1); 00268 b = b - floor(b); 00269 00270 assert(ja >= 0 && ja < rayCount); 00271 assert(jb >= 0 && jb < rayCount); 00272 00273 ra = std::min(this->myParent->GetRange(ja) , maxRange-minRange); // length of ray 00274 rb = std::min(this->myParent->GetRange(jb) , maxRange-minRange); // length of ray 00275 00276 // Range is linear interpolation if values are close, 00277 // and min if they are very different 00278 //if (fabs(ra - rb) < 0.10) 00279 r = (1 - b) * ra + b * rb; 00280 //else r = std::min(ra, rb); 00281 00282 // Intensity is averaged 00283 intensity = 0.5*( this->myParent->GetRetro(ja) + (int) this->myParent->GetRetro(jb)); 00284 00285 /***************************************************************/ 00286 /* */ 00287 /* point scan from laser */ 00288 /* */ 00289 /***************************************************************/ 00290 this->laserMsg.ranges.push_back(std::min(r + minRange + this->GaussianKernel(0,this->gaussianNoise), maxRange)); 00291 this->laserMsg.intensities.push_back(std::max(this->hokuyoMinIntensity,intensity + this->GaussianKernel(0,this->gaussianNoise))); 00292 } 00293 00294 // send data out via ros message 00295 if (this->laserConnectCount > 0 && this->topicName != "") 00296 this->pub_.publish(this->laserMsg); 00297 00298 if (this->deprecatedLaserConnectCount > 0 && this->deprecatedTopicName != "") 00299 this->deprecated_pub_.publish(this->laserMsg); 00300 00301 this->lock.unlock(); 00302 00303 } 00304 00306 // Utility for adding noise 00307 double GazeboRosLaser::GaussianKernel(double mu,double sigma) 00308 { 00309 // using Box-Muller transform to generate two independent standard normally disbributed normal variables 00310 // see wikipedia 00311 double U = (double)rand()/(double)RAND_MAX; // normalized uniform random variable 00312 double V = (double)rand()/(double)RAND_MAX; // normalized uniform random variable 00313 double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V); 00314 //double Y = sqrt(-2.0 * ::log(U)) * sin( 2.0*M_PI * V); // the other indep. normal variable 00315 // we'll just use X 00316 // scale to our mu and sigma 00317 X = sigma * X + mu; 00318 return X; 00319 } 00320 00321 #ifdef USE_CBQ 00322 00323 // Put laser data to the interface 00324 void GazeboRosLaser::LaserQueueThread() 00325 { 00326 static const double timeout = 0.01; 00327 00328 while (this->rosnode_->ok()) 00329 { 00330 this->laser_queue_.callAvailable(ros::WallDuration(timeout)); 00331 } 00332 } 00333 #endif 00334 00335 }