Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include <algorithm>
00024 #include <assert.h>
00025
00026 #include <gazebo_plugins/gazebo_ros_block_laser.h>
00027
00028 #include <gazebo/physics/World.hh>
00029 #include <gazebo/physics/HingeJoint.hh>
00030 #include <gazebo/sensors/Sensor.hh>
00031 #include <sdf/sdf.hh>
00032 #include <sdf/Param.hh>
00033 #include <gazebo/common/Exception.hh>
00034 #include <gazebo/sensors/RaySensor.hh>
00035 #include <gazebo/sensors/SensorTypes.hh>
00036 #include <gazebo/transport/Node.hh>
00037
00038 #include <geometry_msgs/Point32.h>
00039 #include <sensor_msgs/ChannelFloat32.h>
00040
00041 #include <tf/tf.h>
00042
00043 #define EPSILON_DIFF 0.000001
00044
00045 namespace gazebo
00046 {
00047
00048 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosBlockLaser)
00049
00050
00051
00052 GazeboRosBlockLaser::GazeboRosBlockLaser()
00053 {
00054 }
00055
00057
00058 GazeboRosBlockLaser::~GazeboRosBlockLaser()
00059 {
00061
00062 this->laser_queue_.clear();
00063 this->laser_queue_.disable();
00064 this->rosnode_->shutdown();
00065 this->callback_laser_queue_thread_.join();
00066
00067 delete this->rosnode_;
00068 }
00069
00071
00072 void GazeboRosBlockLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00073 {
00074
00075 RayPlugin::Load(_parent, _sdf);
00076
00077
00078 this->parent_sensor_ = _parent;
00079
00080
00081 std::string worldName = _parent->GetWorldName();
00082 this->world_ = physics::get_world(worldName);
00083
00084 last_update_time_ = this->world_->GetSimTime();
00085
00086 this->node_ = transport::NodePtr(new transport::Node());
00087 this->node_->Init(worldName);
00088
00089 this->parent_ray_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(this->parent_sensor_);
00090
00091 if (!this->parent_ray_sensor_)
00092 gzthrow("GazeboRosBlockLaser controller requires a Ray Sensor as its parent");
00093
00094 this->robot_namespace_ = "";
00095 if (_sdf->HasElement("robotNamespace"))
00096 this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
00097
00098 if (!_sdf->HasElement("frameName"))
00099 {
00100 ROS_INFO("Block laser plugin missing <frameName>, defaults to /world");
00101 this->frame_name_ = "/world";
00102 }
00103 else
00104 this->frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
00105
00106 if (!_sdf->HasElement("topicName"))
00107 {
00108 ROS_INFO("Block laser plugin missing <topicName>, defaults to /world");
00109 this->topic_name_ = "/world";
00110 }
00111 else
00112 this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
00113
00114 if (!_sdf->HasElement("gaussianNoise"))
00115 {
00116 ROS_INFO("Block laser plugin missing <gaussianNoise>, defaults to 0.0");
00117 this->gaussian_noise_ = 0;
00118 }
00119 else
00120 this->gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();
00121
00122 if (!_sdf->HasElement("hokuyoMinIntensity"))
00123 {
00124 ROS_INFO("Block laser plugin missing <hokuyoMinIntensity>, defaults to 101");
00125 this->hokuyo_min_intensity_ = 101;
00126 }
00127 else
00128 this->hokuyo_min_intensity_ = _sdf->GetElement("hokuyoMinIntensity")->Get<double>();
00129
00130 ROS_INFO("INFO: gazebo_ros_laser plugin should set minimum intensity to %f due to cutoff in hokuyo filters." , this->hokuyo_min_intensity_);
00131
00132 if (!_sdf->GetElement("updateRate"))
00133 {
00134 ROS_INFO("Block laser plugin missing <updateRate>, defaults to 0");
00135 this->update_rate_ = 0;
00136 }
00137 else
00138 this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
00139
00140
00141
00142 this->laser_connect_count_ = 0;
00143
00144
00145 if (!ros::isInitialized())
00146 {
00147 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00148 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00149 return;
00150 }
00151
00152 this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00153
00154
00155 std::string prefix;
00156 this->rosnode_->getParam(std::string("tf_prefix"), prefix);
00157 this->frame_name_ = tf::resolve(prefix, this->frame_name_);
00158
00159
00160 this->cloud_msg_.points.clear();
00161 this->cloud_msg_.channels.clear();
00162 this->cloud_msg_.channels.push_back(sensor_msgs::ChannelFloat32());
00163
00164 if (this->topic_name_ != "")
00165 {
00166
00167 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::PointCloud>(
00168 this->topic_name_,1,
00169 boost::bind( &GazeboRosBlockLaser::LaserConnect,this),
00170 boost::bind( &GazeboRosBlockLaser::LaserDisconnect,this), ros::VoidPtr(), &this->laser_queue_);
00171 this->pub_ = this->rosnode_->advertise(ao);
00172 }
00173
00174
00175
00176
00177
00178 this->parent_ray_sensor_->SetActive(false);
00179
00180 this->callback_laser_queue_thread_ = boost::thread( boost::bind( &GazeboRosBlockLaser::LaserQueueThread,this ) );
00181
00182 }
00183
00185
00186 void GazeboRosBlockLaser::LaserConnect()
00187 {
00188 this->laser_connect_count_++;
00189 this->parent_ray_sensor_->SetActive(true);
00190 }
00192
00193 void GazeboRosBlockLaser::LaserDisconnect()
00194 {
00195 this->laser_connect_count_--;
00196
00197 if (this->laser_connect_count_ == 0)
00198 this->parent_ray_sensor_->SetActive(false);
00199 }
00200
00202
00203 void GazeboRosBlockLaser::OnNewLaserScans()
00204 {
00205 if (this->topic_name_ != "")
00206 {
00207 common::Time sensor_update_time = this->parent_sensor_->GetLastUpdateTime();
00208 if (last_update_time_ < sensor_update_time)
00209 {
00210 this->PutLaserData(sensor_update_time);
00211 last_update_time_ = sensor_update_time;
00212 }
00213 }
00214 else
00215 {
00216 ROS_INFO("gazebo_ros_block_laser topic name not set");
00217 }
00218 }
00219
00221
00222 void GazeboRosBlockLaser::PutLaserData(common::Time &_updateTime)
00223 {
00224 int i, hja, hjb;
00225 int j, vja, vjb;
00226 double vb, hb;
00227 int j1, j2, j3, j4;
00228 double r1, r2, r3, r4, r;
00229 double intensity;
00230
00231 this->parent_ray_sensor_->SetActive(false);
00232
00233 math::Angle maxAngle = this->parent_ray_sensor_->GetAngleMax();
00234 math::Angle minAngle = this->parent_ray_sensor_->GetAngleMin();
00235
00236 double maxRange = this->parent_ray_sensor_->GetRangeMax();
00237 double minRange = this->parent_ray_sensor_->GetRangeMin();
00238 int rayCount = this->parent_ray_sensor_->GetRayCount();
00239 int rangeCount = this->parent_ray_sensor_->GetRangeCount();
00240
00241 int verticalRayCount = this->parent_ray_sensor_->GetVerticalRayCount();
00242 int verticalRangeCount = this->parent_ray_sensor_->GetVerticalRangeCount();
00243 math::Angle verticalMaxAngle = this->parent_ray_sensor_->GetVerticalAngleMax();
00244 math::Angle verticalMinAngle = this->parent_ray_sensor_->GetVerticalAngleMin();
00245
00246 double yDiff = maxAngle.Radian() - minAngle.Radian();
00247 double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
00248
00249
00250
00251
00252 this->cloud_msg_.points.clear();
00253 this->cloud_msg_.channels.clear();
00254 this->cloud_msg_.channels.push_back(sensor_msgs::ChannelFloat32());
00255
00256
00257
00258
00259
00260
00261 boost::mutex::scoped_lock sclock(this->lock);
00262
00263 this->cloud_msg_.header.frame_id = this->frame_name_;
00264 this->cloud_msg_.header.stamp.sec = _updateTime.sec;
00265 this->cloud_msg_.header.stamp.nsec = _updateTime.nsec;
00266
00267 for (j = 0; j<verticalRangeCount; j++)
00268 {
00269
00270 vb = (verticalRangeCount == 1) ? 0 : (double) j * (verticalRayCount - 1) / (verticalRangeCount - 1);
00271 vja = (int) floor(vb);
00272 vjb = std::min(vja + 1, verticalRayCount - 1);
00273 vb = vb - floor(vb);
00274
00275 assert(vja >= 0 && vja < verticalRayCount);
00276 assert(vjb >= 0 && vjb < verticalRayCount);
00277
00278 for (i = 0; i<rangeCount; i++)
00279 {
00280
00281 hb = (rangeCount == 1)? 0 : (double) i * (rayCount - 1) / (rangeCount - 1);
00282 hja = (int) floor(hb);
00283 hjb = std::min(hja + 1, rayCount - 1);
00284 hb = hb - floor(hb);
00285
00286 assert(hja >= 0 && hja < rayCount);
00287 assert(hjb >= 0 && hjb < rayCount);
00288
00289
00290 j1 = hja + vja * rayCount;
00291 j2 = hjb + vja * rayCount;
00292 j3 = hja + vjb * rayCount;
00293 j4 = hjb + vjb * rayCount;
00294
00295 r1 = std::min(this->parent_ray_sensor_->GetLaserShape()->GetRange(j1) , maxRange-minRange);
00296 r2 = std::min(this->parent_ray_sensor_->GetLaserShape()->GetRange(j2) , maxRange-minRange);
00297 r3 = std::min(this->parent_ray_sensor_->GetLaserShape()->GetRange(j3) , maxRange-minRange);
00298 r4 = std::min(this->parent_ray_sensor_->GetLaserShape()->GetRange(j4) , maxRange-minRange);
00299
00300
00301
00302 r = (1-vb)*((1 - hb) * r1 + hb * r2)
00303 + vb *((1 - hb) * r3 + hb * r4);
00304
00305
00306 intensity = 0.25*(this->parent_ray_sensor_->GetLaserShape()->GetRetro(j1) +
00307 this->parent_ray_sensor_->GetLaserShape()->GetRetro(j2) +
00308 this->parent_ray_sensor_->GetLaserShape()->GetRetro(j3) +
00309 this->parent_ray_sensor_->GetLaserShape()->GetRetro(j4));
00310
00311
00312
00313
00314
00315
00316
00317
00318 double yAngle = 0.5*(hja+hjb) * yDiff / (rayCount -1) + minAngle.Radian();
00319 double pAngle = 0.5*(vja+vjb) * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();
00320
00321
00322
00323
00324
00325
00326
00327 double diffRange = maxRange - minRange;
00328 double diff = diffRange - r;
00329 if (fabs(diff) < EPSILON_DIFF)
00330 {
00331
00332 geometry_msgs::Point32 point;
00333
00334 point.x = r * cos(pAngle) * cos(yAngle);
00335 point.y = r * cos(pAngle) * sin(yAngle);
00336 point.z = -r * sin(pAngle);
00337
00338 this->cloud_msg_.points.push_back(point);
00339 }
00340 else
00341 {
00342 geometry_msgs::Point32 point;
00343
00344 point.x = r * cos(pAngle) * cos(yAngle) + this->GaussianKernel(0,this->gaussian_noise_);
00345 point.y = r * cos(pAngle) * sin(yAngle) + this->GaussianKernel(0,this->gaussian_noise_);
00346 point.z = -r * sin(pAngle) + this->GaussianKernel(0,this->gaussian_noise_);
00347 this->cloud_msg_.points.push_back(point);
00348 }
00349
00350 this->cloud_msg_.channels[0].values.push_back(intensity + this->GaussianKernel(0,this->gaussian_noise_)) ;
00351 }
00352 }
00353 this->parent_ray_sensor_->SetActive(true);
00354
00355
00356 this->pub_.publish(this->cloud_msg_);
00357
00358
00359
00360 }
00361
00362
00364
00365 double GazeboRosBlockLaser::GaussianKernel(double mu,double sigma)
00366 {
00367
00368
00369 double U = (double)rand()/(double)RAND_MAX;
00370 double V = (double)rand()/(double)RAND_MAX;
00371 double X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
00372
00373
00374
00375 X = sigma * X + mu;
00376 return X;
00377 }
00378
00379
00381
00382 void GazeboRosBlockLaser::LaserQueueThread()
00383 {
00384 static const double timeout = 0.01;
00385
00386 while (this->rosnode_->ok())
00387 {
00388 this->laser_queue_.callAvailable(ros::WallDuration(timeout));
00389 }
00390 }
00391
00392 void GazeboRosBlockLaser::OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg)
00393 {
00394 this->sim_time_ = msgs::Convert( _msg->sim_time() );
00395
00396 math::Pose pose;
00397 pose.pos.x = 0.5*sin(0.01*this->sim_time_.Double());
00398 gzdbg << "plugin simTime [" << this->sim_time_.Double() << "] update pose [" << pose.pos.x << "]\n";
00399 }
00400
00401
00402 }
00403