gazebo_ros_range.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (Modified BSD License)
3  *
4  * Copyright (c) 2013, PAL Robotics, S.L.
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 PAL Robotics, S.L. 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 
37 #ifndef GAZEBO_ROS_RANGE_H
38 #define GAZEBO_ROS_RANGE_H
39 
40 
41 #include <string>
42 
43 #include <boost/bind.hpp>
44 #include <boost/thread.hpp>
45 #include <boost/thread/mutex.hpp>
46 
47 #include <ros/ros.h>
48 #include <ros/callback_queue.h>
49 #include <ros/advertise_options.h>
50 #include <sensor_msgs/Range.h>
51 
52 #include <gazebo/physics/physics.hh>
53 #include <gazebo/transport/TransportTypes.hh>
54 #include <gazebo/msgs/MessageTypes.hh>
55 #include <gazebo/common/Time.hh>
56 #include <gazebo/common/Plugin.hh>
57 #include <gazebo/common/Events.hh>
58 #include <gazebo/sensors/SensorTypes.hh>
59 #include <gazebo/plugins/RayPlugin.hh>
60 
61 #include <sdf/Param.hh>
62 
63 namespace gazebo
64 {
65 
66 class GazeboRosRange : public RayPlugin
67 {
68 
70  public: GazeboRosRange();
71 
73  public: ~GazeboRosRange();
74 
77  public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
78 
80  protected: virtual void OnNewLaserScans();
81 
83  private: void PutRangeData(common::Time &_updateTime);
84 
86  private: int range_connect_count_;
87  private: void RangeConnect();
88  private: void RangeDisconnect();
89 
90  // Pointer to the model
91  private: physics::WorldPtr world_;
93  private: sensors::SensorPtr parent_sensor_;
94  private: sensors::RaySensorPtr parent_ray_sensor_;
95 
98  private: ros::Publisher pub_;
99 
101  private: sensor_msgs::Range range_msg_;
102 
104  private: std::string topic_name_;
105 
107  private: std::string frame_name_;
108 
110  private: std::string radiation_;
111 
113  private: double fov_;
115  private: double gaussian_noise_;
116 
118  private: double GaussianKernel(double mu, double sigma);
119 
121  private: boost::mutex lock_;
122 
124  private: double hokuyo_min_intensity_;
125 
127  private: double update_rate_;
128  private: double update_period_;
129  private: common::Time last_update_time_;
130 
132  private: std::string robot_namespace_;
133 
135  private: void RangeQueueThread();
136  private: boost::thread callback_queue_thread_;
137 
138  // deferred load in case ros is blocking
139  private: sdf::ElementPtr sdf;
140  private: void LoadThread();
141  private: boost::thread deferred_load_thread_;
142 };
143 }
144 #endif // GAZEBO_ROS_RANGE_H
gazebo::GazeboRosRange::parent_sensor_
sensors::SensorPtr parent_sensor_
The parent sensor.
Definition: gazebo_ros_range.h:93
gazebo::GazeboRosRange::pub_
ros::Publisher pub_
Definition: gazebo_ros_range.h:98
gazebo::GazeboRosRange::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_range.h:104
ros::Publisher
gazebo::GazeboRosRange::frame_name_
std::string frame_name_
frame transform name, should match link name
Definition: gazebo_ros_range.h:107
gazebo
gazebo::GazeboRosRange::PutRangeData
void PutRangeData(common::Time &_updateTime)
Put range data to the ROS topic.
Definition: gazebo_ros_range.cpp:286
gazebo::GazeboRosRange::range_connect_count_
int range_connect_count_
Keep track of number of connctions.
Definition: gazebo_ros_range.h:86
gazebo::GazeboRosRange::OnNewLaserScans
virtual void OnNewLaserScans()
Update the controller.
Definition: gazebo_ros_range.cpp:246
ros.h
gazebo::GazeboRosRange::fov_
double fov_
sensor field of view
Definition: gazebo_ros_range.h:113
gazebo::GazeboRosRange::range_msg_
sensor_msgs::Range range_msg_
ros message
Definition: gazebo_ros_range.h:101
gazebo::GazeboRosRange::RangeDisconnect
void RangeDisconnect()
Definition: gazebo_ros_range.cpp:235
gazebo::GazeboRosRange::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_range.cpp:328
gazebo::GazeboRosRange::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_range.h:97
gazebo::GazeboRosRange::radiation_
std::string radiation_
radiation type : ultrasound or infrared
Definition: gazebo_ros_range.h:110
gazebo::GazeboRosRange
Definition: gazebo_ros_range.h:66
gazebo::GazeboRosRange::LoadThread
void LoadThread()
Definition: gazebo_ros_range.cpp:196
gazebo::GazeboRosRange::hokuyo_min_intensity_
double hokuyo_min_intensity_
hack to mimic hokuyo intensity cutoff of 100
Definition: gazebo_ros_range.h:124
gazebo::GazeboRosRange::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_range.h:141
ros::CallbackQueue
gazebo::GazeboRosRange::lock_
boost::mutex lock_
mutex to lock access to fields that are used in message callbacks
Definition: gazebo_ros_range.h:121
gazebo::GazeboRosRange::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_range.h:136
gazebo::GazeboRosRange::RangeConnect
void RangeConnect()
Definition: gazebo_ros_range.cpp:228
gazebo::GazeboRosRange::RangeQueueThread
void RangeQueueThread()
Definition: gazebo_ros_range.cpp:350
gazebo::GazeboRosRange::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_range.h:132
gazebo::GazeboRosRange::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_range.cpp:86
callback_queue.h
gazebo::GazeboRosRange::~GazeboRosRange
~GazeboRosRange()
Destructor.
Definition: gazebo_ros_range.cpp:74
gazebo::GazeboRosRange::range_queue_
ros::CallbackQueue range_queue_
Definition: gazebo_ros_range.h:134
gazebo::GazeboRosRange::update_period_
double update_period_
Definition: gazebo_ros_range.h:128
advertise_options.h
gazebo::GazeboRosRange::update_rate_
double update_rate_
update rate of this sensor
Definition: gazebo_ros_range.h:127
gazebo::GazeboRosRange::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_range.h:139
gazebo::GazeboRosRange::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_range.h:129
gazebo::GazeboRosRange::GazeboRosRange
GazeboRosRange()
Constructor.
Definition: gazebo_ros_range.cpp:68
gazebo::GazeboRosRange::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_range.h:115
gazebo::GazeboRosRange::world_
physics::WorldPtr world_
Definition: gazebo_ros_range.h:91
gazebo::GazeboRosRange::parent_ray_sensor_
sensors::RaySensorPtr parent_ray_sensor_
Definition: gazebo_ros_range.h:94
ros::NodeHandle


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28