gazebo_ros_gpu_laser.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 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 /*
19  Desc: GazeboRosGpuLaser plugin for simulating ray sensors in Gazebo
20  Author: Mihai Emanuel Dolha
21  Date: 29 March 2012
22  */
23 
24 #include <algorithm>
25 #include <string>
26 #include <assert.h>
27 
28 #include <sdf/sdf.hh>
29 
30 #include <gazebo/physics/World.hh>
31 #include <gazebo/physics/HingeJoint.hh>
32 #include <gazebo/sensors/Sensor.hh>
33 #include <gazebo/common/Exception.hh>
34 #include <gazebo/sensors/GpuRaySensor.hh>
35 #include <gazebo/sensors/SensorTypes.hh>
36 #include <gazebo/transport/transport.hh>
37 
38 #ifdef ENABLE_PROFILER
39 #include <ignition/common/Profiler.hh>
40 #endif
41 
42 #include <tf/tf.h>
43 #include <tf/transform_listener.h>
44 
47 #include <ignition/math/Rand.hh>
48 
49 namespace gazebo
50 {
51 // Register this plugin with the simulator
52 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosLaser)
53 
54 // Constructor
57 {
58 }
59 
61 // Destructor
63 {
64  ROS_DEBUG_STREAM_NAMED("gpu_laser","Shutting down GPU Laser");
65  this->rosnode_->shutdown();
66  delete this->rosnode_;
67  ROS_DEBUG_STREAM_NAMED("gpu_laser","Unloaded");
68 }
69 
71 // Load the controller
72 void GazeboRosLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
73 {
74  // load plugin
75  GpuRayPlugin::Load(_parent, this->sdf);
76  // Get the world name.
77  std::string worldName = _parent->WorldName();
78  this->world_ = physics::get_world(worldName);
79  // save pointers
80  this->sdf = _sdf;
81 
83  this->parent_ray_sensor_ =
84  dynamic_pointer_cast<sensors::GpuRaySensor>(_parent);
85 
86  if (!this->parent_ray_sensor_)
87  gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent");
88 
89  this->robot_namespace_ = GetRobotNamespace(_parent, _sdf, "Laser");
90 
91  if (!this->sdf->HasElement("frameName"))
92  {
93  ROS_INFO_NAMED("gpu_laser", "GazeboRosLaser plugin missing <frameName>, defaults to /world");
94  this->frame_name_ = "/world";
95  }
96  else
97  this->frame_name_ = this->sdf->Get<std::string>("frameName");
98 
99  if (!this->sdf->HasElement("topicName"))
100  {
101  ROS_INFO_NAMED("gpu_laser", "GazeboRosLaser plugin missing <topicName>, defaults to /world");
102  this->topic_name_ = "/world";
103  }
104  else
105  this->topic_name_ = this->sdf->Get<std::string>("topicName");
106 
107  this->laser_connect_count_ = 0;
108 
109 
110  // Make sure the ROS node for Gazebo has already been initialized
111  if (!ros::isInitialized())
112  {
113  ROS_FATAL_STREAM_NAMED("gpu_laser", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
114  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
115  return;
116  }
117 
118  ROS_INFO_NAMED("gpu_laser", "Starting GazeboRosLaser Plugin (ns = %s)", this->robot_namespace_.c_str() );
119  // ros callback queue for processing subscription
120  this->deferred_load_thread_ = boost::thread(
121  boost::bind(&GazeboRosLaser::LoadThread, this));
122 
123 }
124 
126 // Load the controller
128 {
129  this->gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
130  this->gazebo_node_->Init(this->world_name_);
131 
132  this->pmq.startServiceThread();
133 
134  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
135 
136  this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
137  ROS_INFO_NAMED("gpu_laser", "GPU Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
138  this->robot_namespace_.c_str(), this->tf_prefix_.c_str());
139 
140  // resolve tf prefix
141  this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
142 
143  if (this->topic_name_ != "")
144  {
146  ros::AdvertiseOptions::create<sensor_msgs::LaserScan>(
147  this->topic_name_, 1,
148  boost::bind(&GazeboRosLaser::LaserConnect, this),
149  boost::bind(&GazeboRosLaser::LaserDisconnect, this),
150  ros::VoidPtr(), NULL);
151  this->pub_ = this->rosnode_->advertise(ao);
152  this->pub_queue_ = this->pmq.addPub<sensor_msgs::LaserScan>();
153  }
154 
155  // Initialize the controller
156 
157  // sensor generation off by default
158  this->parent_ray_sensor_->SetActive(false);
159 
160  ROS_INFO_STREAM_NAMED("gpu_laser","LoadThread function completed");
161 }
162 
164 // Increment count
166 {
167  this->laser_connect_count_++;
168  if (this->laser_connect_count_ == 1)
169  this->laser_scan_sub_ =
170  this->gazebo_node_->Subscribe(this->parent_ray_sensor_->Topic(),
171  &GazeboRosLaser::OnScan, this);
172 }
173 
175 // Decrement count
177 {
178  this->laser_connect_count_--;
179  if (this->laser_connect_count_ == 0)
180  this->laser_scan_sub_.reset();
181 }
182 
184 // Convert new Gazebo message to ROS message and publish it
185 void GazeboRosLaser::OnScan(ConstLaserScanStampedPtr &_msg)
186 {
187 #ifdef ENABLE_PROFILER
188  IGN_PROFILE("GazeboRosLaser::OnScan");
189  IGN_PROFILE_BEGIN("fill ROS message");
190 #endif
191  // We got a new message from the Gazebo sensor. Stuff a
192  // corresponding ROS message and publish it.
193  sensor_msgs::LaserScan laser_msg;
194  laser_msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
195  laser_msg.header.frame_id = this->frame_name_;
196  laser_msg.angle_min = _msg->scan().angle_min();
197  laser_msg.angle_max = _msg->scan().angle_max();
198  laser_msg.angle_increment = _msg->scan().angle_step();
199  laser_msg.time_increment = 0; // instantaneous simulator scan
200  laser_msg.scan_time = 0; // not sure whether this is correct
201  laser_msg.range_min = _msg->scan().range_min();
202  laser_msg.range_max = _msg->scan().range_max();
203  laser_msg.ranges.resize(_msg->scan().ranges_size());
204  std::copy(_msg->scan().ranges().begin(),
205  _msg->scan().ranges().end(),
206  laser_msg.ranges.begin());
207  laser_msg.intensities.resize(_msg->scan().intensities_size());
208  std::copy(_msg->scan().intensities().begin(),
209  _msg->scan().intensities().end(),
210  laser_msg.intensities.begin());
211  this->pub_queue_->push(laser_msg, this->pub_);
212 #ifdef ENABLE_PROFILER
213  IGN_PROFILE_END();
214 #endif
215 }
216 }
gazebo::GazeboRosLaser::LoadThread
void LoadThread()
Definition: gazebo_ros_gpu_laser.cpp:127
PubQueue::push
void push(T &msg, ros::Publisher &pub)
Push a new message onto the queue.
Definition: PubQueue.h:73
boost::shared_ptr< void >
gazebo
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
gazebo::GazeboRosLaser::LaserDisconnect
void LaserDisconnect()
Definition: gazebo_ros_gpu_laser.cpp:176
gazebo_ros_gpu_laser.h
gazebo::GazeboRosLaser
Definition: gazebo_ros_gpu_laser.h:45
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosLaser::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_gpu_laser.h:74
gazebo::GazeboRosLaser::frame_name_
std::string frame_name_
frame transform name, should match link name
Definition: gazebo_ros_gpu_laser.h:77
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::AdvertiseOptions
gazebo::GazeboRosLaser::~GazeboRosLaser
~GazeboRosLaser()
Destructor.
Definition: gazebo_ros_gpu_laser.cpp:62
gazebo::GazeboRosLaser::gazebo_node_
gazebo::transport::NodePtr gazebo_node_
Definition: gazebo_ros_gpu_laser.h:90
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
gazebo::GazeboRosLaser::pmq
PubMultiQueue pmq
prevents blocking
Definition: gazebo_ros_gpu_laser.h:95
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
gazebo::GazeboRosLaser::pub_queue_
PubQueue< sensor_msgs::LaserScan >::Ptr pub_queue_
Definition: gazebo_ros_gpu_laser.h:71
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosLaser::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_gpu_laser.cpp:72
PubMultiQueue::addPub
boost::shared_ptr< PubQueue< T > > addPub()
Add a new queue. Call this once for each published topic (or at least each type of publish message).
Definition: PubQueue.h:143
gazebo::GazeboRosLaser::world_
physics::WorldPtr world_
Definition: gazebo_ros_gpu_laser.h:64
gazebo::GazeboRosLaser::parent_ray_sensor_
sensors::GpuRaySensorPtr parent_ray_sensor_
The parent sensor.
Definition: gazebo_ros_gpu_laser.h:66
transform_listener.h
tf.h
PubMultiQueue::startServiceThread
void startServiceThread()
Start a thread to call spin().
Definition: PubQueue.h:181
gazebo::GazeboRosLaser::laser_scan_sub_
gazebo::transport::SubscriberPtr laser_scan_sub_
Definition: gazebo_ros_gpu_laser.h:91
ros::Time
gazebo::GazeboRosLaser::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_gpu_laser.h:69
gazebo::GazeboRosLaser::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_gpu_laser.h:83
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
gazebo::GazeboRosLaser::LaserConnect
void LaserConnect()
Definition: gazebo_ros_gpu_laser.cpp:165
gazebo_ros_utils.h
gazebo::GazeboRosLaser::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_gpu_laser.h:86
gazebo::GazeboRosLaser::world_name_
std::string world_name_
Definition: gazebo_ros_gpu_laser.h:63
gazebo::GazeboRosLaser::tf_prefix_
std::string tf_prefix_
tf prefix
Definition: gazebo_ros_gpu_laser.h:80
assert.h
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosLaser::OnScan
void OnScan(ConstLaserScanStampedPtr &_msg)
Definition: gazebo_ros_gpu_laser.cpp:185
gazebo::GetRobotNamespace
std::string GetRobotNamespace(const sensors::SensorPtr &parent, const sdf::ElementPtr &sdf, const char *pInfo=NULL)
Reads the name space tag of a sensor plugin.
Definition: gazebo_ros_utils.h:83
gazebo::GazeboRosLaser::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_gpu_laser.h:88
gazebo::GazeboRosLaser::pub_
ros::Publisher pub_
Definition: gazebo_ros_gpu_laser.h:70
GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
#define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
Definition: gazebo_ros_utils.h:49
ros::NodeHandle
gazebo::GazeboRosLaser::laser_connect_count_
int laser_connect_count_
Keep track of number of connctions.
Definition: gazebo_ros_gpu_laser.h:58


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