40 #include <gazebo/physics/World.hh> 41 #include <gazebo/sensors/Sensor.hh> 43 #include <sdf/Param.hh> 44 #include <gazebo/common/Exception.hh> 46 #include <gazebo/sensors/GpuRaySensor.hh> 48 #include <gazebo/sensors/RaySensor.hh> 50 #include <gazebo/sensors/SensorTypes.hh> 51 #include <gazebo/transport/Node.hh> 53 #include <sensor_msgs/PointCloud2.h> 57 static_assert(GAZEBO_MAJOR_VERSION > 2,
"Gazebo version is too old");
60 #define RaySensor GpuRaySensor 62 #define STR_GPU_ "GPU " 71 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosVelodyneLaser)
100 RayPlugin::Load(_parent, _sdf);
103 gazebo_node_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
107 #if GAZEBO_MAJOR_VERSION >= 7 112 if (!parent_ray_sensor_) {
113 gzthrow(
"GazeboRosVelodyne" <<
STR_Gpu <<
"Laser controller requires a " <<
STR_Gpu <<
"Ray Sensor as its parent");
117 if (_sdf->HasElement(
"robotNamespace")) {
121 if (!_sdf->HasElement(
"frameName")) {
122 ROS_INFO(
"Velodyne laser plugin missing <frameName>, defaults to /world");
125 frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
128 if (!_sdf->HasElement(
"organize_cloud")) {
129 ROS_INFO(
"Velodyne laser plugin missing <organize_cloud>, defaults to false");
135 if (!_sdf->HasElement(
"min_range")) {
136 ROS_INFO(
"Velodyne laser plugin missing <min_range>, defaults to 0");
139 min_range_ = _sdf->GetElement(
"min_range")->Get<
double>();
142 if (!_sdf->HasElement(
"max_range")) {
143 ROS_INFO(
"Velodyne laser plugin missing <max_range>, defaults to infinity");
146 max_range_ = _sdf->GetElement(
"max_range")->Get<
double>();
150 if (!_sdf->HasElement(
"min_intensity")) {
151 ROS_INFO(
"Velodyne laser plugin missing <min_intensity>, defaults to no clipping");
153 min_intensity_ = _sdf->GetElement(
"min_intensity")->Get<
double>();
156 if (!_sdf->HasElement(
"topicName")) {
157 ROS_INFO(
"Velodyne laser plugin missing <topicName>, defaults to /points");
160 topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
163 if (!_sdf->HasElement(
"gaussianNoise")) {
164 ROS_INFO(
"Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0");
172 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 173 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
186 boost::trim_right_if(prefix, boost::is_any_of(
"/"));
200 parent_ray_sensor_->SetActive(
false);
205 #if GAZEBO_MAJOR_VERSION >= 7 206 ROS_INFO(
"Velodyne %slaser plugin ready, %i lasers",
STR_GPU_, parent_ray_sensor_->VerticalRangeCount());
208 ROS_INFO(
"Velodyne %slaser plugin ready, %i lasers",
STR_GPU_, parent_ray_sensor_->GetVerticalRangeCount());
216 boost::lock_guard<boost::mutex> lock(
lock_);
219 #if GAZEBO_MAJOR_VERSION >= 7 227 #if GAZEBO_MAJOR_VERSION >= 7 239 #if GAZEBO_MAJOR_VERSION >= 7 252 const ignition::math::Angle verticalMaxAngle =
parent_ray_sensor_->VerticalAngleMax();
253 const ignition::math::Angle verticalMinAngle =
parent_ray_sensor_->VerticalAngleMin();
271 const double yDiff = maxAngle.Radian() - minAngle.Radian();
272 const double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
274 const double MIN_RANGE = std::max(
min_range_, minRange);
275 const double MAX_RANGE = std::min(
max_range_, maxRange);
279 const uint32_t POINT_STEP = 22;
280 sensor_msgs::PointCloud2 msg;
282 msg.header.stamp =
ros::Time(_msg->time().sec(), _msg->time().nsec());
283 msg.fields.resize(6);
284 msg.fields[0].name =
"x";
285 msg.fields[0].offset = 0;
286 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
287 msg.fields[0].count = 1;
288 msg.fields[1].name =
"y";
289 msg.fields[1].offset = 4;
290 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
291 msg.fields[1].count = 1;
292 msg.fields[2].name =
"z";
293 msg.fields[2].offset = 8;
294 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
295 msg.fields[2].count = 1;
296 msg.fields[3].name =
"intensity";
297 msg.fields[3].offset = 12;
298 msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
299 msg.fields[3].count = 1;
300 msg.fields[4].name =
"ring";
301 msg.fields[4].offset = 16;
302 msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
303 msg.fields[4].count = 1;
304 msg.fields[5].name =
"time";
305 msg.fields[5].offset = 18;
306 msg.fields[5].datatype = sensor_msgs::PointField::FLOAT32;
307 msg.fields[5].count = 1;
308 msg.data.resize(verticalRangeCount * rangeCount * POINT_STEP);
311 uint8_t *ptr = msg.data.data();
312 for (i = 0; i < rangeCount; i++) {
313 for (j = 0; j < verticalRangeCount; j++) {
316 double r = _msg->scan().ranges(i + j * rangeCount);
318 double intensity = _msg->scan().intensities(i + j * rangeCount);
321 if ((MIN_RANGE >= r) || (r >= MAX_RANGE) || (intensity < MIN_INTENSITY) ) {
336 if (rangeCount > 1) {
337 yAngle = i * yDiff / (rangeCount -1) + minAngle.Radian();
339 yAngle = minAngle.Radian();
342 if (verticalRayCount > 1) {
343 pAngle = j * pDiff / (verticalRangeCount -1) + verticalMinAngle.Radian();
345 pAngle = verticalMinAngle.Radian();
349 if ((MIN_RANGE < r) && (r < MAX_RANGE)) {
350 *((
float*)(ptr + 0)) = r * cos(pAngle) * cos(yAngle);
351 *((
float*)(ptr + 4)) = r * cos(pAngle) * sin(yAngle);
352 *((
float*)(ptr + 8)) = r * sin(pAngle);
353 *((
float*)(ptr + 12)) = intensity;
354 *((uint16_t*)(ptr + 16)) = j;
355 *((
float*)(ptr + 18)) = 0.0;
358 *((
float*)(ptr + 0)) = nanf(
"");
359 *((
float*)(ptr + 4)) = nanf(
"");
360 *((
float*)(ptr + 8)) = nanf(
"");
361 *((
float*)(ptr + 12)) = nanf(
"");
362 *((uint16_t*)(ptr + 16)) = j;
363 *((
float*)(ptr + 18)) = 0.0;
370 msg.data.resize(ptr - msg.data.data());
371 msg.point_step = POINT_STEP;
372 msg.is_bigendian =
false;
374 msg.width = verticalRangeCount;
375 msg.height = msg.data.size() / POINT_STEP / msg.width;
376 msg.row_step = POINT_STEP * msg.width;
377 msg.is_dense =
false;
379 msg.width = msg.data.size() / POINT_STEP;
381 msg.row_step = msg.data.size();
void publish(const boost::shared_ptr< M > &message) const
void OnScan(const ConstLaserScanStampedPtr &_msg)
ros::NodeHandle * nh_
Pointer to ROS node.
std::string topic_name_
topic name
sensors::RaySensorPtr parent_ray_sensor_
The parent ray sensor.
gazebo::transport::NodePtr gazebo_node_
ROSCPP_DECL bool isInitialized()
static double gaussianKernel(double mu, double sigma)
Gaussian noise generator.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
void ConnectCb()
Subscribe on-demand.
ros::Publisher pub_
ROS publisher.
std::string resolve(const std::string &prefix, const std::string &frame_name)
bool organize_cloud_
organize cloud
#define ROS_FATAL_STREAM(args)
double gaussian_noise_
Gaussian noise.
boost::thread callback_laser_queue_thread_
gazebo::transport::SubscriberPtr sub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double min_range_
Minimum range to publish.
~GazeboRosVelodyneLaser()
Destructor.
uint32_t getNumSubscribers() const
ros::CallbackQueue laser_queue_
std::string robot_namespace_
For setting ROS name space.
bool getParam(const std::string &key, std::string &s) const
double max_range_
Maximum range to publish.
std::string frame_name_
frame transform name, should match link name
double min_intensity_
the intensity beneath which points will be filtered
boost::mutex lock_
A mutex to lock access.
boost::shared_ptr< void > VoidPtr