$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 Block Laser controller. 00023 * Author: Nathan Koenig 00024 * Date: 01 Feb 2007 00025 * SVN info: $Id: gazebo_ros_block_laser.cc 6683 2008-06-25 19:12:30Z natepak $ 00026 */ 00027 00028 #include <algorithm> 00029 #include <assert.h> 00030 00031 #include <gazebo_plugins/gazebo_ros_block_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 #include <geometry_msgs/Point32.h> 00045 #include <sensor_msgs/ChannelFloat32.h> 00046 00047 using namespace gazebo; 00048 00049 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_block_laser", GazeboRosBlockLaser); 00050 00052 // Constructor 00053 GazeboRosBlockLaser::GazeboRosBlockLaser(Entity *parent) 00054 : Controller(parent) 00055 { 00056 this->myParent = dynamic_cast<RaySensor*>(this->parent); 00057 00058 if (!this->myParent) 00059 gzthrow("GazeboRosBlockLaser controller requires a Ray Sensor as its parent"); 00060 00061 Param::Begin(&this->parameters); 00062 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00063 this->gaussianNoiseP = new ParamT<double>("gaussianNoise", 0.0, 0); 00064 this->topicNameP = new ParamT<std::string>("topicName", "", 1); 00065 this->frameNameP = new ParamT<std::string>("frameName", "default_ros_laser_frame", 0); 00066 Param::End(); 00067 } 00068 00070 // Destructor 00071 GazeboRosBlockLaser::~GazeboRosBlockLaser() 00072 { 00073 delete this->robotNamespaceP; 00074 delete this->gaussianNoiseP; 00075 delete this->topicNameP; 00076 delete this->frameNameP; 00077 delete this->rosnode_; 00078 } 00079 00081 // Load the controller 00082 void GazeboRosBlockLaser::LoadChild(XMLConfigNode *node) 00083 { 00084 this->robotNamespaceP->Load(node); 00085 this->robotNamespace = this->robotNamespaceP->GetValue(); 00086 00087 if (!ros::isInitialized()) 00088 { 00089 int argc = 0; 00090 char** argv = NULL; 00091 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00092 } 00093 00094 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00095 00096 this->topicNameP->Load(node); 00097 this->topicName = this->topicNameP->GetValue(); 00098 this->frameNameP->Load(node); 00099 this->frameName = this->frameNameP->GetValue(); 00100 this->gaussianNoiseP->Load(node); 00101 this->gaussianNoise = this->gaussianNoiseP->GetValue(); 00102 00103 // set size of cloud message, starts at 0!! FIXME: not necessary 00104 this->cloudMsg.points.clear(); 00105 this->cloudMsg.channels.clear(); 00106 this->cloudMsg.channels.push_back(sensor_msgs::ChannelFloat32()); 00107 00108 // Custom Callback Queue 00109 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::PointCloud>( 00110 this->topicName,1, 00111 boost::bind( &GazeboRosBlockLaser::LaserConnect,this), 00112 boost::bind( &GazeboRosBlockLaser::LaserDisconnect,this), ros::VoidPtr(), &this->queue_); 00113 this->pub_ = this->rosnode_->advertise(ao); 00114 00115 } 00116 00118 // Increment count 00119 void GazeboRosBlockLaser::LaserConnect() 00120 { 00121 this->laserConnectCount++; 00122 } 00124 // Decrement count 00125 void GazeboRosBlockLaser::LaserDisconnect() 00126 { 00127 this->laserConnectCount--; 00128 00129 if (this->laserConnectCount == 0) 00130 this->myParent->SetActive(false); 00131 } 00133 // Initialize the controller 00134 void GazeboRosBlockLaser::InitChild() 00135 { 00136 // set parent sensor to inactive automatically 00137 this->myParent->SetActive(false); 00138 // Custom Callback Queue 00139 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosBlockLaser::QueueThread,this ) ); 00140 } 00141 00143 // Update the controller 00144 void GazeboRosBlockLaser::UpdateChild() 00145 { 00146 // as long as ros is connected, parent is active 00147 //ROS_ERROR("debug laser count %d",this->laserConnectCount); 00148 if (!this->myParent->IsActive()) 00149 { 00150 // do this first so there's chance for sensor to run 1 frame after activate 00151 if (this->laserConnectCount > 0) 00152 this->myParent->SetActive(true); 00153 } 00154 else 00155 { 00156 this->PutLaserData(); 00157 } 00158 } 00159 00161 // Finalize the controller 00162 void GazeboRosBlockLaser::FiniChild() 00163 { 00164 // Custom Callback Queue 00165 this->queue_.clear(); 00166 this->queue_.disable(); 00167 this->rosnode_->shutdown(); 00168 this->callback_queue_thread_.join(); 00169 } 00170 00172 // Put laser data to the interface 00173 void GazeboRosBlockLaser::PutLaserData() 00174 { 00175 int i, hja, hjb; 00176 int j, vja, vjb; 00177 double vb, hb; 00178 int j1, j2, j3, j4; // four corners indices 00179 double r1, r2, r3, r4, r; // four corner values + interpolated range 00180 double intensity; 00181 00182 Angle maxAngle = this->myParent->GetMaxAngle(); 00183 Angle minAngle = this->myParent->GetMinAngle(); 00184 00185 double maxRange = this->myParent->GetMaxRange(); 00186 double minRange = this->myParent->GetMinRange(); 00187 int rayCount = this->myParent->GetRayCount(); 00188 int rangeCount = this->myParent->GetRangeCount(); 00189 00190 int verticalRayCount = this->myParent->GetVerticalRayCount(); 00191 int verticalRangeCount = this->myParent->GetVerticalRangeCount(); 00192 Angle verticalMaxAngle = this->myParent->GetVerticalMaxAngle(); 00193 Angle verticalMinAngle = this->myParent->GetVerticalMinAngle(); 00194 00195 double yDiff = maxAngle.GetAsRadian() - minAngle.GetAsRadian(); 00196 double pDiff = verticalMaxAngle.GetAsRadian() - verticalMinAngle.GetAsRadian(); 00197 00198 00199 // set size of cloud message everytime! 00200 //int r_size = rangeCount * verticalRangeCount; 00201 this->cloudMsg.points.clear(); 00202 this->cloudMsg.channels.clear(); 00203 this->cloudMsg.channels.push_back(sensor_msgs::ChannelFloat32()); 00204 00205 /***************************************************************/ 00206 /* */ 00207 /* point scan from laser */ 00208 /* */ 00209 /***************************************************************/ 00210 boost::mutex::scoped_lock sclock(this->lock); 00211 // Add Frame Name 00212 this->cloudMsg.header.frame_id = this->frameName; 00213 this->cloudMsg.header.stamp.sec = (Simulator::Instance()->GetSimTime()).sec; 00214 this->cloudMsg.header.stamp.nsec = (Simulator::Instance()->GetSimTime()).nsec; 00215 00216 for (j = 0; j<verticalRangeCount; j++) 00217 { 00218 // interpolating in vertical direction 00219 vb = (verticalRangeCount == 1) ? 0 : (double) j * (verticalRayCount - 1) / (verticalRangeCount - 1); 00220 vja = (int) floor(vb); 00221 vjb = std::min(vja + 1, verticalRayCount - 1); 00222 vb = vb - floor(vb); // fraction from min 00223 00224 assert(vja >= 0 && vja < verticalRayCount); 00225 assert(vjb >= 0 && vjb < verticalRayCount); 00226 00227 for (i = 0; i<rangeCount; i++) 00228 { 00229 // Interpolate the range readings from the rays in horizontal direction 00230 hb = (rangeCount == 1)? 0 : (double) i * (rayCount - 1) / (rangeCount - 1); 00231 hja = (int) floor(hb); 00232 hjb = std::min(hja + 1, rayCount - 1); 00233 hb = hb - floor(hb); // fraction from min 00234 00235 assert(hja >= 0 && hja < rayCount); 00236 assert(hjb >= 0 && hjb < rayCount); 00237 00238 // indices of 4 corners 00239 j1 = hja + vja * rayCount; 00240 j2 = hjb + vja * rayCount; 00241 j3 = hja + vjb * rayCount; 00242 j4 = hjb + vjb * rayCount; 00243 // range readings of 4 corners 00244 r1 = std::min(this->myParent->GetRange(j1) , maxRange-minRange); 00245 r2 = std::min(this->myParent->GetRange(j2) , maxRange-minRange); 00246 r3 = std::min(this->myParent->GetRange(j3) , maxRange-minRange); 00247 r4 = std::min(this->myParent->GetRange(j4) , maxRange-minRange); 00248 00249 // Range is linear interpolation if values are close, 00250 // and min if they are very different 00251 r = (1-vb)*((1 - hb) * r1 + hb * r2) 00252 + vb *((1 - hb) * r3 + hb * r4); 00253 00254 // Intensity is averaged 00255 intensity = 0.25*(this->myParent->GetRetro(j1) + (int) this->myParent->GetRetro(j2) + 00256 this->myParent->GetRetro(j3) + (int) this->myParent->GetRetro(j4)); 00257 00258 // std::cout << " block debug " 00259 // << " ij("<<i<<","<<j<<")" 00260 // << " j1234("<<j1<<","<<j2<<","<<j3<<","<<j4<<")" 00261 // << " r1234("<<r1<<","<<r2<<","<<r3<<","<<r4<<")" 00262 // << std::endl; 00263 00264 // get angles of ray to get xyz for point 00265 double yAngle = 0.5*(hja+hjb) * yDiff / (rayCount -1) + minAngle.GetAsRadian(); 00266 double pAngle = 0.5*(vja+vjb) * pDiff / (verticalRayCount -1) + verticalMinAngle.GetAsRadian(); 00267 00268 /***************************************************************/ 00269 /* */ 00270 /* point scan from laser */ 00271 /* */ 00272 /***************************************************************/ 00273 if (r == maxRange - minRange) 00274 { 00275 // no noise if at max range 00276 geometry_msgs::Point32 point; 00277 point.x = (r+minRange) * cos(pAngle)*cos(yAngle); 00278 point.y = (r+minRange) * sin(yAngle); 00279 point.z = (r+minRange) * sin(pAngle)*cos(yAngle); 00280 this->cloudMsg.points.push_back(point); 00281 } 00282 else 00283 { 00284 geometry_msgs::Point32 point; 00285 point.x = (r+minRange) * cos(pAngle)*cos(yAngle) + this->GaussianKernel(0,this->gaussianNoise) ; 00286 point.y = (r+minRange) * sin(yAngle) + this->GaussianKernel(0,this->gaussianNoise) ; 00287 point.z = (r+minRange) * sin(pAngle)*cos(yAngle) + this->GaussianKernel(0,this->gaussianNoise) ; 00288 this->cloudMsg.points.push_back(point); 00289 } 00290 // only 1 channel 00291 this->cloudMsg.channels[0].values.push_back(intensity + this->GaussianKernel(0,this->gaussianNoise)) ; 00292 } 00293 } 00294 00295 // send data out via ros message 00296 this->pub_.publish(this->cloudMsg); 00297 00298 00299 00300 } 00301 00302 00304 // Utility for adding noise 00305 double GazeboRosBlockLaser::GaussianKernel(double mu,double sigma) 00306 { 00307 // using Box-Muller transform to generate two independent standard normally disbributed normal variables 00308 // see wikipedia 00309 double U = (double)rand()/(double)RAND_MAX; // normalized uniform random variable 00310 double V = (double)rand()/(double)RAND_MAX; // normalized uniform random variable 00311 double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V); 00312 //double Y = sqrt(-2.0 * ::log(U)) * sin( 2.0*M_PI * V); // the other indep. normal variable 00313 // we'll just use X 00314 // scale to our mu and sigma 00315 X = sigma * X + mu; 00316 return X; 00317 } 00318 00319 // Custom Callback Queue 00321 // custom callback queue thread 00322 void GazeboRosBlockLaser::QueueThread() 00323 { 00324 static const double timeout = 0.01; 00325 00326 while (this->rosnode_->ok()) 00327 { 00328 this->queue_.callAvailable(ros::WallDuration(timeout)); 00329 } 00330 } 00331 00332 00333 00334 00335