gazebo_ros_gpu_laser.h
Go to the documentation of this file.
1 /*
2  * Copyright 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GAZEBO_ROS_LASER_HH
19 #define GAZEBO_ROS_LASER_HH
20 
21 #include <string>
22 
23 #include <boost/bind.hpp>
24 #include <boost/thread.hpp>
25 
26 #include <ros/ros.h>
27 #include <ros/advertise_options.h>
28 #include <sensor_msgs/LaserScan.h>
29 
30 #include <gazebo/physics/physics.hh>
31 #include <gazebo/transport/TransportTypes.hh>
32 #include <gazebo/msgs/MessageTypes.hh>
33 #include <gazebo/common/Time.hh>
34 #include <gazebo/common/Plugin.hh>
35 #include <gazebo/common/Events.hh>
36 #include <gazebo/sensors/SensorTypes.hh>
37 #include <gazebo/plugins/GpuRayPlugin.hh>
38 
39 #include <sdf/sdf.hh>
40 
42 
43 namespace gazebo
44 {
45  class GazeboRosLaser : public GpuRayPlugin
46  {
48  public: GazeboRosLaser();
49 
51  public: ~GazeboRosLaser();
52 
55  public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
56 
58  private: int laser_connect_count_;
59  private: void LaserConnect();
60  private: void LaserDisconnect();
61 
62  // Pointer to the model
63  private: std::string world_name_;
64  private: physics::WorldPtr world_;
66  private: sensors::GpuRaySensorPtr parent_ray_sensor_;
67 
70  private: ros::Publisher pub_;
72 
74  private: std::string topic_name_;
75 
77  private: std::string frame_name_;
78 
80  private: std::string tf_prefix_;
81 
83  private: std::string robot_namespace_;
84 
85  // deferred load in case ros is blocking
86  private: sdf::ElementPtr sdf;
87  private: void LoadThread();
88  private: boost::thread deferred_load_thread_;
89  private: unsigned int seed;
90 
91  private: gazebo::transport::NodePtr gazebo_node_;
92  private: gazebo::transport::SubscriberPtr laser_scan_sub_;
93  private: void OnScan(ConstLaserScanStampedPtr &_msg);
94 
96  private: PubMultiQueue pmq;
97  };
98 }
99 #endif
ros::NodeHandle * rosnode_
pointer to ros node
A collection of PubQueue objects, potentially of different types. This class is the programmer&#39;s inte...
Definition: PubQueue.h:96
std::string tf_prefix_
tf prefix
gazebo::transport::SubscriberPtr laser_scan_sub_
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
boost::thread deferred_load_thread_
A queue of outgoing messages. Instead of calling publish() directly, you can push() messages here to ...
Definition: PubQueue.h:48
PubQueue< sensor_msgs::LaserScan >::Ptr pub_queue_
std::string frame_name_
frame transform name, should match link name
std::string robot_namespace_
for setting ROS name space
gazebo::transport::NodePtr gazebo_node_
PubMultiQueue pmq
prevents blocking
void OnScan(ConstLaserScanStampedPtr &_msg)
std::string topic_name_
topic name
sensors::GpuRaySensorPtr parent_ray_sensor_
The parent sensor.
int laser_connect_count_
Keep track of number of connctions.


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27