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> 58 #define RaySensor GpuRaySensor 60 #define STR_GPU_ "GPU " 69 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosVelodyneLaser)
98 RayPlugin::Load(_parent, _sdf);
101 gazebo_node_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
105 #if GAZEBO_MAJOR_VERSION >= 7 110 if (!parent_ray_sensor_) {
111 gzthrow(
"GazeboRosVelodyne" <<
STR_Gpu <<
"Laser controller requires a " <<
STR_Gpu <<
"Ray Sensor as its parent");
115 if (_sdf->HasElement(
"robotNamespace")) {
119 if (!_sdf->HasElement(
"frameName")) {
120 ROS_INFO(
"Velodyne laser plugin missing <frameName>, defaults to /world");
123 frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
126 if (!_sdf->HasElement(
"min_range")) {
127 ROS_INFO(
"Velodyne laser plugin missing <min_range>, defaults to 0");
130 min_range_ = _sdf->GetElement(
"min_range")->Get<
double>();
133 if (!_sdf->HasElement(
"max_range")) {
134 ROS_INFO(
"Velodyne laser plugin missing <max_range>, defaults to infinity");
137 max_range_ = _sdf->GetElement(
"max_range")->Get<
double>();
141 if (!_sdf->HasElement(
"min_intensity")) {
142 ROS_INFO(
"Velodyne laser plugin missing <min_intensity>, defaults to no clipping");
144 min_intensity_ = _sdf->GetElement(
"min_intensity")->Get<
double>();
147 if (!_sdf->HasElement(
"topicName")) {
148 ROS_INFO(
"Velodyne laser plugin missing <topicName>, defaults to /points");
151 topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
154 if (!_sdf->HasElement(
"gaussianNoise")) {
155 ROS_INFO(
"Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0");
163 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 164 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
177 boost::trim_right_if(prefix, boost::is_any_of(
"/"));
191 parent_ray_sensor_->SetActive(
false);
196 #if GAZEBO_MAJOR_VERSION >= 7 197 ROS_INFO(
"Velodyne %slaser plugin ready, %i lasers",
STR_GPU_, parent_ray_sensor_->VerticalRangeCount());
199 ROS_INFO(
"Velodyne %slaser plugin ready, %i lasers",
STR_GPU_, parent_ray_sensor_->GetVerticalRangeCount());
207 boost::lock_guard<boost::mutex> lock(
lock_);
210 #if GAZEBO_MAJOR_VERSION >= 7 218 #if GAZEBO_MAJOR_VERSION >= 7 230 #if GAZEBO_MAJOR_VERSION >= 7 243 const ignition::math::Angle verticalMaxAngle =
parent_ray_sensor_->VerticalAngleMax();
244 const ignition::math::Angle verticalMinAngle =
parent_ray_sensor_->VerticalAngleMin();
262 const double yDiff = maxAngle.Radian() - minAngle.Radian();
263 const double pDiff = verticalMaxAngle.Radian() - verticalMinAngle.Radian();
265 const double MIN_RANGE = std::max(
min_range_, minRange);
266 const double MAX_RANGE = std::min(
max_range_, maxRange);
270 const uint32_t POINT_STEP = 32;
271 sensor_msgs::PointCloud2 msg;
273 msg.header.stamp =
ros::Time(_msg->time().sec(), _msg->time().nsec());
274 msg.fields.resize(5);
275 msg.fields[0].name =
"x";
276 msg.fields[0].offset = 0;
277 msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
278 msg.fields[0].count = 1;
279 msg.fields[1].name =
"y";
280 msg.fields[1].offset = 4;
281 msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
282 msg.fields[1].count = 1;
283 msg.fields[2].name =
"z";
284 msg.fields[2].offset = 8;
285 msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
286 msg.fields[2].count = 1;
287 msg.fields[3].name =
"intensity";
288 msg.fields[3].offset = 16;
289 msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
290 msg.fields[3].count = 1;
291 msg.fields[4].name =
"ring";
292 msg.fields[4].offset = 20;
293 msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
294 msg.fields[4].count = 1;
295 msg.data.resize(verticalRangeCount * rangeCount * POINT_STEP);
298 uint8_t *ptr = msg.data.data();
299 for (i = 0; i < rangeCount; i++) {
300 for (j = 0; j < verticalRangeCount; j++) {
303 double r = _msg->scan().ranges(i + j * rangeCount);
305 double intensity = _msg->scan().intensities(i + j * rangeCount);
308 if ((MIN_RANGE >= r) || (r >= MAX_RANGE) || (intensity < MIN_INTENSITY) ) {
321 if (rangeCount > 1) {
322 yAngle = i * yDiff / (rangeCount -1) + minAngle.Radian();
324 yAngle = minAngle.Radian();
327 if (verticalRayCount > 1) {
328 pAngle = j * pDiff / (verticalRangeCount -1) + verticalMinAngle.Radian();
330 pAngle = verticalMinAngle.Radian();
334 if ((MIN_RANGE < r) && (r < MAX_RANGE)) {
335 *((
float*)(ptr + 0)) = r * cos(pAngle) * cos(yAngle);
336 *((
float*)(ptr + 4)) = r * cos(pAngle) * sin(yAngle);
337 #if GAZEBO_MAJOR_VERSION > 2 338 *((
float*)(ptr + 8)) = r * sin(pAngle);
340 *((
float*)(ptr + 8)) = -r * sin(pAngle);
342 *((
float*)(ptr + 16)) = intensity;
343 #if GAZEBO_MAJOR_VERSION > 2 344 *((uint16_t*)(ptr + 20)) = j;
346 *((uint16_t*)(ptr + 20)) = verticalRangeCount - 1 - j;
354 msg.point_step = POINT_STEP;
355 msg.row_step = ptr - msg.data.data();
357 msg.width = msg.row_step / POINT_STEP;
358 msg.is_bigendian =
false;
360 msg.data.resize(msg.row_step);
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)
#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