GazeboRosVelodyneLaser.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2016, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef GAZEBO_ROS_VELODYNE_LASER_H_
36 #define GAZEBO_ROS_VELODYNE_LASER_H_
37 
38 // Custom Callback Queue
39 #include <ros/ros.h>
40 #include <ros/callback_queue.h>
41 #include <ros/advertise_options.h>
42 
43 #include <sdf/Param.hh>
44 #include <gazebo/physics/physics.hh>
45 #include <gazebo/transport/TransportTypes.hh>
46 #include <gazebo/msgs/MessageTypes.hh>
47 #include <gazebo/common/Time.hh>
48 #include <gazebo/common/Plugin.hh>
49 #include <gazebo/sensors/SensorTypes.hh>
50 #include <gazebo/plugins/RayPlugin.hh>
51 
52 #include <boost/bind.hpp>
53 #include <boost/thread.hpp>
54 #include <boost/thread/mutex.hpp>
55 
56 namespace gazebo
57 {
58 
59  class GazeboRosVelodyneLaser : public RayPlugin
60  {
63  public: GazeboRosVelodyneLaser();
64 
66  public: ~GazeboRosVelodyneLaser();
67 
70  public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
71 
73  protected: virtual void OnNewLaserScans();
74 
76  private: void putLaserData(common::Time &_updateTime);
77 
78  private: common::Time last_update_time_;
79 
81  private: int laser_connect_count_;
82  private: void laserConnect();
83  private: void laserDisconnect();
84 
85  // Pointer to the model
86  private: physics::WorldPtr world_;
88  private: sensors::SensorPtr parent_sensor_;
89  private: sensors::RaySensorPtr parent_ray_sensor_;
90 
93  private: ros::Publisher pub_;
94 
96  private: std::string topic_name_;
97 
99  private: std::string frame_name_;
100 
102  private: double min_range_;
103 
105  private: double max_range_;
106 
108  private: double gaussian_noise_;
109 
111  private: static double gaussianKernel(double mu, double sigma)
112  {
113  // using Box-Muller transform to generate two independent standard normally distributed normal variables
114  // see wikipedia
115  double U = (double)rand() / (double)RAND_MAX; // normalized uniform random variable
116  double V = (double)rand() / (double)RAND_MAX; // normalized uniform random variable
117  return sigma * (sqrt(-2.0 * ::log(U)) * cos(2.0 * M_PI * V)) + mu;
118  }
119 
121  private: boost::mutex lock_;
122 
124  private: std::string robot_namespace_;
125 
126  // Custom Callback Queue
128  private: void laserQueueThread();
129  private: boost::thread callback_laser_queue_thread_;
130 
131  // subscribe to world stats
132  private: transport::NodePtr node_;
133  private: common::Time sim_time_;
134  public: void onStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg);
135 
136  };
137 
138 }
139 
140 #endif /* GAZEBO_ROS_VELODYNE_LASER_H_ */
ros::NodeHandle * rosnode_
pointer to ros node
int laser_connect_count_
Keep track of number of connections.
sensors::RaySensorPtr parent_ray_sensor_
static double gaussianKernel(double mu, double sigma)
Gaussian noise generator.
void putLaserData(common::Time &_updateTime)
Put laser data to the ROS topic.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
sensors::SensorPtr parent_sensor_
The parent sensor.
double gaussian_noise_
Gaussian noise.
double min_range_
Minimum range to publish.
std::string robot_namespace_
for setting ROS name space
double max_range_
Maximum range to publish.
void onStats(const boost::shared_ptr< msgs::WorldStatistics const > &_msg)
std::string frame_name_
frame transform name, should match link name
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
virtual void OnNewLaserScans()
Update the controller.


velodyne_gazebo_plugin
Author(s): Kevin Hallenbeck
autogenerated on Fri Jan 15 2021 03:26:48