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
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <velodyne_gazebo_plugins/GazeboRosVelodyneLaser.h>
00036
00037 #include <algorithm>
00038 #include <assert.h>
00039
00040 #include <gazebo/physics/World.hh>
00041 #include <gazebo/sensors/Sensor.hh>
00042 #include <sdf/sdf.hh>
00043 #include <sdf/Param.hh>
00044 #include <gazebo/common/Exception.hh>
00045 #include <gazebo/sensors/RaySensor.hh>
00046 #include <gazebo/sensors/SensorTypes.hh>
00047 #include <gazebo/transport/Node.hh>
00048
00049 #include <sensor_msgs/PointCloud2.h>
00050
00051 #include <tf/tf.h>
00052
00053 namespace gazebo
00054 {
00055
00056 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosVelodyneLaser)
00057
00058
00059
00060 GazeboRosVelodyneLaser::GazeboRosVelodyneLaser() : nh_(NULL), gaussian_noise_(0), min_range_(0), max_range_(0)
00061 {
00062 }
00063
00065
00066 GazeboRosVelodyneLaser::~GazeboRosVelodyneLaser()
00067 {
00069
00070 laser_queue_.clear();
00071 laser_queue_.disable();
00072 if (nh_) {
00073 nh_->shutdown();
00074 delete nh_;
00075 nh_ = NULL;
00076 }
00077 callback_laser_queue_thread_.join();
00078 }
00079
00081
00082 void GazeboRosVelodyneLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00083 {
00084
00085 RayPlugin::Load(_parent, _sdf);
00086
00087
00088 gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
00089 gazebo_node_->Init();
00090
00091
00092 #if GAZEBO_MAJOR_VERSION >= 7
00093 parent_ray_sensor_ = std::dynamic_pointer_cast<sensors::RaySensor>(_parent);
00094 #else
00095 parent_ray_sensor_ = boost::dynamic_pointer_cast<sensors::RaySensor>(_parent);
00096 #endif
00097 if (!parent_ray_sensor_) {
00098 gzthrow("GazeboRosVelodyneLaser controller requires a Ray Sensor as its parent");
00099 }
00100
00101 robot_namespace_ = "";
00102 if (_sdf->HasElement("robotNamespace")) {
00103 robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
00104 }
00105
00106 if (!_sdf->HasElement("frameName")) {
00107 ROS_INFO("Velodyne laser plugin missing <frameName>, defaults to /world");
00108 frame_name_ = "/world";
00109 } else {
00110 frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
00111 }
00112
00113 if (!_sdf->HasElement("min_range")) {
00114 ROS_INFO("Velodyne laser plugin missing <min_range>, defaults to 0");
00115 min_range_ = 0;
00116 } else {
00117 min_range_ = _sdf->GetElement("min_range")->Get<double>();
00118 }
00119
00120 if (!_sdf->HasElement("max_range")) {
00121 ROS_INFO("Velodyne laser plugin missing <max_range>, defaults to infinity");
00122 max_range_ = INFINITY;
00123 } else {
00124 max_range_ = _sdf->GetElement("max_range")->Get<double>();
00125 }
00126
00127 if (!_sdf->HasElement("topicName")) {
00128 ROS_INFO("Velodyne laser plugin missing <topicName>, defaults to /points");
00129 topic_name_ = "/points";
00130 } else {
00131 topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
00132 }
00133
00134 if (!_sdf->HasElement("gaussianNoise")) {
00135 ROS_INFO("Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0");
00136 gaussian_noise_ = 0;
00137 } else {
00138 gaussian_noise_ = _sdf->GetElement("gaussianNoise")->Get<double>();
00139 }
00140
00141
00142 if (!ros::isInitialized()) {
00143 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00144 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00145 return;
00146 }
00147
00148
00149 nh_ = new ros::NodeHandle(robot_namespace_);
00150
00151
00152 std::string prefix;
00153 nh_->getParam(std::string("tf_prefix"), prefix);
00154 frame_name_ = tf::resolve(prefix, frame_name_);
00155
00156
00157 if (topic_name_ != "") {
00158 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<sensor_msgs::PointCloud2>(
00159 topic_name_, 1,
00160 boost::bind(&GazeboRosVelodyneLaser::ConnectCb, this),
00161 boost::bind(&GazeboRosVelodyneLaser::ConnectCb, this),
00162 ros::VoidPtr(), &laser_queue_);
00163 pub_ = nh_->advertise(ao);
00164 }
00165
00166
00167 parent_ray_sensor_->SetActive(false);
00168
00169
00170 callback_laser_queue_thread_ = boost::thread( boost::bind( &GazeboRosVelodyneLaser::laserQueueThread,this ) );
00171
00172 #if GAZEBO_MAJOR_VERSION >= 7
00173 ROS_INFO("Velodyne laser plugin ready, %i lasers", parent_ray_sensor_->VerticalRangeCount());
00174 #else
00175 ROS_INFO("Velodyne laser plugin ready, %i lasers", parent_ray_sensor_->GetVerticalRangeCount());
00176 #endif
00177 }
00178
00180
00181 void GazeboRosVelodyneLaser::ConnectCb()
00182 {
00183 boost::lock_guard<boost::mutex> lock(lock_);
00184 if (pub_.getNumSubscribers()) {
00185 if (!sub_) {
00186 #if GAZEBO_MAJOR_VERSION >= 7
00187 sub_ = gazebo_node_->Subscribe(this->parent_ray_sensor_->Topic(), &GazeboRosVelodyneLaser::OnScan, this);
00188 #else
00189 sub_ = gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(), &GazeboRosVelodyneLaser::OnScan, this);
00190 #endif
00191 }
00192 parent_ray_sensor_->SetActive(true);
00193 } else {
00194 #if GAZEBO_MAJOR_VERSION >= 7
00195 if (sub_) {
00196 sub_->Unsubscribe();
00197 sub_.reset();
00198 }
00199 #endif
00200 parent_ray_sensor_->SetActive(false);
00201 }
00202 }
00203
00204 void GazeboRosVelodyneLaser::OnScan(ConstLaserScanStampedPtr& _msg)
00205 {
00206 #if GAZEBO_MAJOR_VERSION >= 7
00207 const math::Angle maxAngle = parent_ray_sensor_->AngleMax();
00208 const math::Angle minAngle = parent_ray_sensor_->AngleMin();
00209
00210 const double maxRange = parent_ray_sensor_->RangeMax();
00211 const double minRange = parent_ray_sensor_->RangeMin();
00212
00213 const int rayCount = parent_ray_sensor_->RayCount();
00214 const int rangeCount = parent_ray_sensor_->RangeCount();
00215 assert(rayCount == rangeCount);
00216
00217 const int verticalRayCount = parent_ray_sensor_->VerticalRayCount();
00218 const int verticalRangeCount = parent_ray_sensor_->VerticalRangeCount();
00219 assert(verticalRayCount == verticalRangeCount);
00220
00221 const math::Angle verticalMaxAngle = parent_ray_sensor_->VerticalAngleMax();
00222 const math::Angle verticalMinAngle = parent_ray_sensor_->VerticalAngleMin();
00223 #else
00224 math::Angle maxAngle = parent_ray_sensor_->GetAngleMax();
00225 math::Angle minAngle = parent_ray_sensor_->GetAngleMin();
00226
00227 const double maxRange = parent_ray_sensor_->GetRangeMax();
00228 const double minRange = parent_ray_sensor_->GetRangeMin();
00229
00230 const int rayCount = parent_ray_sensor_->GetRayCount();
00231 const int rangeCount = parent_ray_sensor_->GetRangeCount();
00232 assert(rayCount == rangeCount);
00233
00234 const int verticalRayCount = parent_ray_sensor_->GetVerticalRayCount();
00235 const int verticalRangeCount = parent_ray_sensor_->GetVerticalRangeCount();
00236 assert(verticalRayCount == verticalRangeCount);
00237
00238 const math::Angle verticalMaxAngle = parent_ray_sensor_->GetVerticalAngleMax();
00239 const math::Angle verticalMinAngle = parent_ray_sensor_->GetVerticalAngleMin();
00240 #endif
00241
00242 const double yDiff = maxAngle.Radian() - minAngle.Radian();
00243 const double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
00244
00245 const double MIN_RANGE = std::max(min_range_, minRange);
00246 const double MAX_RANGE = std::min(max_range_, maxRange - minRange - 0.01);
00247
00248
00249 const uint32_t POINT_STEP = 32;
00250 sensor_msgs::PointCloud2 msg;
00251 msg.header.frame_id = frame_name_;
00252 msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
00253 msg.fields.resize(5);
00254 msg.fields[0].name = "x";
00255 msg.fields[0].offset = 0;
00256 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00257 msg.fields[0].count = 1;
00258 msg.fields[1].name = "y";
00259 msg.fields[1].offset = 4;
00260 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00261 msg.fields[1].count = 1;
00262 msg.fields[2].name = "z";
00263 msg.fields[2].offset = 8;
00264 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00265 msg.fields[2].count = 1;
00266 msg.fields[3].name = "intensity";
00267 msg.fields[3].offset = 16;
00268 msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00269 msg.fields[3].count = 1;
00270 msg.fields[4].name = "ring";
00271 msg.fields[4].offset = 20;
00272 msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
00273 msg.fields[4].count = 1;
00274 msg.data.resize(verticalRangeCount * rangeCount * POINT_STEP);
00275
00276 int i, j;
00277 uint8_t *ptr = msg.data.data();
00278 for (j = 0; j < verticalRangeCount; j++) {
00279 for (i = 0; i < rangeCount; i++) {
00280
00281
00282 double r = std::min(_msg->scan().ranges(i + j * rangeCount), maxRange-minRange);
00283 if (gaussian_noise_ != 0.0) {
00284 r += gaussianKernel(0,gaussian_noise_);
00285 }
00286
00287
00288 double intensity = _msg->scan().intensities(i + j * rangeCount);
00289
00290
00291 double yAngle = i * yDiff / (rayCount -1) + minAngle.Radian();
00292 double pAngle = j * pDiff / (verticalRayCount -1) + verticalMinAngle.Radian();
00293
00294
00295 if ((MIN_RANGE < r) && (r < MAX_RANGE)) {
00296 *((float*)(ptr + 0)) = r * cos(pAngle) * cos(yAngle);
00297 *((float*)(ptr + 4)) = r * cos(pAngle) * sin(yAngle);
00298 #if GAZEBO_MAJOR_VERSION > 2
00299 *((float*)(ptr + 8)) = r * sin(pAngle);
00300 #else
00301 *((float*)(ptr + 8)) = -r * sin(pAngle);
00302 #endif
00303 *((float*)(ptr + 16)) = intensity;
00304 #if GAZEBO_MAJOR_VERSION > 2
00305 *((uint16_t*)(ptr + 20)) = j;
00306 #else
00307 *((uint16_t*)(ptr + 20)) = verticalRangeCount - 1 - j;
00308 #endif
00309 ptr += POINT_STEP;
00310 }
00311 }
00312 }
00313
00314
00315 msg.point_step = POINT_STEP;
00316 msg.row_step = ptr - msg.data.data();
00317 msg.height = 1;
00318 msg.width = msg.row_step / POINT_STEP;
00319 msg.is_bigendian = false;
00320 msg.is_dense = true;
00321 msg.data.resize(msg.row_step);
00322
00323
00324 pub_.publish(msg);
00325 }
00326
00327
00329
00330 void GazeboRosVelodyneLaser::laserQueueThread()
00331 {
00332 while (nh_->ok()) {
00333 laser_queue_.callAvailable(ros::WallDuration(0.01));
00334 }
00335 }
00336
00337 }
00338