gazebo_ros_gpu_laser.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2013 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 /*
00019    Desc: GazeboRosGpuLaser plugin for simulating ray sensors in Gazebo
00020    Author: Mihai Emanuel Dolha
00021    Date: 29 March 2012
00022  */
00023 
00024 #include <algorithm>
00025 #include <string>
00026 #include <assert.h>
00027 
00028 #include <sdf/sdf.hh>
00029 
00030 #include <gazebo/physics/World.hh>
00031 #include <gazebo/physics/HingeJoint.hh>
00032 #include <gazebo/sensors/Sensor.hh>
00033 #include <gazebo/common/Exception.hh>
00034 #include <gazebo/sensors/GpuRaySensor.hh>
00035 #include <gazebo/sensors/SensorTypes.hh>
00036 #include <gazebo/transport/transport.hh>
00037 
00038 #include <tf/tf.h>
00039 #include <tf/transform_listener.h>
00040 
00041 #include "gazebo_plugins/gazebo_ros_gpu_laser.h"
00042 #include <gazebo_plugins/gazebo_ros_utils.h>
00043 
00044 namespace gazebo
00045 {
00046 // Register this plugin with the simulator
00047 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosLaser)
00048 
00049 
00050 // Constructor
00051 GazeboRosLaser::GazeboRosLaser()
00052 {
00053   this->seed = 0;
00054 }
00055 
00057 // Destructor
00058 GazeboRosLaser::~GazeboRosLaser()
00059 {
00060   ROS_DEBUG_STREAM_NAMED("gpu_laser","Shutting down GPU Laser");
00061   this->rosnode_->shutdown();
00062   delete this->rosnode_;
00063   ROS_DEBUG_STREAM_NAMED("gpu_laser","Unloaded");
00064 }
00065 
00067 // Load the controller
00068 void GazeboRosLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00069 {
00070   // load plugin
00071   GpuRayPlugin::Load(_parent, this->sdf);
00072   // Get the world name.
00073   std::string worldName = _parent->GetWorldName();
00074   this->world_ = physics::get_world(worldName);
00075   // save pointers
00076   this->sdf = _sdf;
00077 
00078   this->parent_ray_sensor_ =
00079     boost::dynamic_pointer_cast<sensors::GpuRaySensor>(_parent);
00080 
00081   if (!this->parent_ray_sensor_)
00082     gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent");
00083 
00084   this->robot_namespace_ =  GetRobotNamespace(_parent, _sdf, "Laser");
00085 
00086   if (!this->sdf->HasElement("frameName"))
00087   {
00088     ROS_INFO("GazeboRosLaser plugin missing <frameName>, defaults to /world");
00089     this->frame_name_ = "/world";
00090   }
00091   else
00092     this->frame_name_ = this->sdf->Get<std::string>("frameName");
00093 
00094   if (!this->sdf->HasElement("topicName"))
00095   {
00096     ROS_INFO("GazeboRosLaser plugin missing <topicName>, defaults to /world");
00097     this->topic_name_ = "/world";
00098   }
00099   else
00100     this->topic_name_ = this->sdf->Get<std::string>("topicName");
00101 
00102   this->laser_connect_count_ = 0;
00103 
00104 
00105   // Make sure the ROS node for Gazebo has already been initialized
00106   if (!ros::isInitialized())
00107   {
00108     ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00109       << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00110     return;
00111   }
00112 
00113   ROS_INFO ( "Starting GazeboRosLaser Plugin (ns = %s)!", this->robot_namespace_.c_str() );
00114   // ros callback queue for processing subscription
00115   this->deferred_load_thread_ = boost::thread(
00116     boost::bind(&GazeboRosLaser::LoadThread, this));
00117 
00118 }
00119 
00121 // Load the controller
00122 void GazeboRosLaser::LoadThread()
00123 {
00124   this->gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
00125   this->gazebo_node_->Init(this->world_name_);
00126 
00127   this->pmq.startServiceThread();
00128 
00129   this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00130 
00131   this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
00132   if(this->tf_prefix_.empty()) {
00133       this->tf_prefix_ = this->robot_namespace_;
00134       boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
00135   }
00136   ROS_INFO("GPU Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
00137              this->robot_namespace_.c_str(), this->tf_prefix_.c_str());
00138 
00139   // resolve tf prefix
00140   this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
00141 
00142   if (this->topic_name_ != "")
00143   {
00144     ros::AdvertiseOptions ao =
00145       ros::AdvertiseOptions::create<sensor_msgs::LaserScan>(
00146       this->topic_name_, 1,
00147       boost::bind(&GazeboRosLaser::LaserConnect, this),
00148       boost::bind(&GazeboRosLaser::LaserDisconnect, this),
00149       ros::VoidPtr(), NULL);
00150     this->pub_ = this->rosnode_->advertise(ao);
00151     this->pub_queue_ = this->pmq.addPub<sensor_msgs::LaserScan>();
00152   }
00153 
00154   // Initialize the controller
00155 
00156   // sensor generation off by default
00157   this->parent_ray_sensor_->SetActive(false);
00158 
00159   ROS_INFO_STREAM_NAMED("gpu_laser","LoadThread function completed");
00160 }
00161 
00163 // Increment count
00164 void GazeboRosLaser::LaserConnect()
00165 {
00166   this->laser_connect_count_++;
00167   if (this->laser_connect_count_ == 1)
00168     this->laser_scan_sub_ =
00169       this->gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(),
00170                                     &GazeboRosLaser::OnScan, this);
00171 }
00172 
00174 // Decrement count
00175 void GazeboRosLaser::LaserDisconnect()
00176 {
00177   this->laser_connect_count_--;
00178   if (this->laser_connect_count_ == 0)
00179     this->laser_scan_sub_.reset();
00180 }
00181 
00183 // Convert new Gazebo message to ROS message and publish it
00184 void GazeboRosLaser::OnScan(ConstLaserScanStampedPtr &_msg)
00185 {
00186   // We got a new message from the Gazebo sensor.  Stuff a
00187   // corresponding ROS message and publish it.
00188   sensor_msgs::LaserScan laser_msg;
00189   laser_msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
00190   laser_msg.header.frame_id = this->frame_name_;
00191   laser_msg.angle_min = _msg->scan().angle_min();
00192   laser_msg.angle_max = _msg->scan().angle_max();
00193   laser_msg.angle_increment = _msg->scan().angle_step();
00194   laser_msg.time_increment = 0;  // instantaneous simulator scan
00195   laser_msg.scan_time = 0;  // not sure whether this is correct
00196   laser_msg.range_min = _msg->scan().range_min();
00197   laser_msg.range_max = _msg->scan().range_max();
00198   laser_msg.ranges.resize(_msg->scan().ranges_size());
00199   std::copy(_msg->scan().ranges().begin(),
00200             _msg->scan().ranges().end(),
00201             laser_msg.ranges.begin());
00202   laser_msg.intensities.resize(_msg->scan().intensities_size());
00203   std::copy(_msg->scan().intensities().begin(),
00204             _msg->scan().intensities().end(),
00205             laser_msg.intensities.begin());
00206   this->pub_queue_->push(laser_msg, this->pub_);
00207 }
00208 }


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25