Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
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 #include <gazebo/gazebo_config.h>
00038
00039 #include <tf/tf.h>
00040 #include <tf/transform_listener.h>
00041
00042 #include "gazebo_plugins/gazebo_ros_gpu_laser.h"
00043 #include <gazebo_plugins/gazebo_ros_utils.h>
00044
00045 namespace gazebo
00046 {
00047
00048 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosLaser)
00049
00050
00051
00052 GazeboRosLaser::GazeboRosLaser()
00053 {
00054 this->seed = 0;
00055 }
00056
00058
00059 GazeboRosLaser::~GazeboRosLaser()
00060 {
00061 ROS_DEBUG_STREAM_NAMED("gpu_laser","Shutting down GPU Laser");
00062 this->rosnode_->shutdown();
00063 delete this->rosnode_;
00064 ROS_DEBUG_STREAM_NAMED("gpu_laser","Unloaded");
00065 }
00066
00068
00069 void GazeboRosLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00070 {
00071
00072 GpuRayPlugin::Load(_parent, this->sdf);
00073
00074
00075 # if GAZEBO_MAJOR_VERSION >= 7
00076 std::string worldName = _parent->WorldName();
00077 # else
00078 std::string worldName = _parent->GetWorldName();
00079 # endif
00080
00081 this->world_ = physics::get_world(worldName);
00082
00083 this->sdf = _sdf;
00084
00085 GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST;
00086 this->parent_ray_sensor_ =
00087 dynamic_pointer_cast<sensors::GpuRaySensor>(_parent);
00088
00089 if (!this->parent_ray_sensor_)
00090 gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent");
00091
00092 this->robot_namespace_ = GetRobotNamespace(_parent, _sdf, "Laser");
00093
00094 if (!this->sdf->HasElement("frameName"))
00095 {
00096 ROS_INFO("GazeboRosLaser plugin missing <frameName>, defaults to /world");
00097 this->frame_name_ = "/world";
00098 }
00099 else
00100 this->frame_name_ = this->sdf->Get<std::string>("frameName");
00101
00102 if (!this->sdf->HasElement("topicName"))
00103 {
00104 ROS_INFO("GazeboRosLaser plugin missing <topicName>, defaults to /world");
00105 this->topic_name_ = "/world";
00106 }
00107 else
00108 this->topic_name_ = this->sdf->Get<std::string>("topicName");
00109
00110 this->laser_connect_count_ = 0;
00111
00112
00113
00114 if (!ros::isInitialized())
00115 {
00116 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00117 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00118 return;
00119 }
00120
00121 ROS_INFO ( "Starting GazeboRosLaser Plugin (ns = %s)!", this->robot_namespace_.c_str() );
00122
00123 this->deferred_load_thread_ = boost::thread(
00124 boost::bind(&GazeboRosLaser::LoadThread, this));
00125
00126 }
00127
00129
00130 void GazeboRosLaser::LoadThread()
00131 {
00132 this->gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
00133 this->gazebo_node_->Init(this->world_name_);
00134
00135 this->pmq.startServiceThread();
00136
00137 this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00138
00139 this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
00140 if(this->tf_prefix_.empty()) {
00141 this->tf_prefix_ = this->robot_namespace_;
00142 boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
00143 }
00144 ROS_INFO("GPU Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
00145 this->robot_namespace_.c_str(), this->tf_prefix_.c_str());
00146
00147
00148 this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
00149
00150 if (this->topic_name_ != "")
00151 {
00152 ros::AdvertiseOptions ao =
00153 ros::AdvertiseOptions::create<sensor_msgs::LaserScan>(
00154 this->topic_name_, 1,
00155 boost::bind(&GazeboRosLaser::LaserConnect, this),
00156 boost::bind(&GazeboRosLaser::LaserDisconnect, this),
00157 ros::VoidPtr(), NULL);
00158 this->pub_ = this->rosnode_->advertise(ao);
00159 this->pub_queue_ = this->pmq.addPub<sensor_msgs::LaserScan>();
00160 }
00161
00162
00163
00164
00165 this->parent_ray_sensor_->SetActive(false);
00166
00167 ROS_INFO_STREAM_NAMED("gpu_laser","LoadThread function completed");
00168 }
00169
00171
00172 void GazeboRosLaser::LaserConnect()
00173 {
00174 this->laser_connect_count_++;
00175 if (this->laser_connect_count_ == 1)
00176 this->laser_scan_sub_ =
00177 # if GAZEBO_MAJOR_VERSION >= 7
00178 this->gazebo_node_->Subscribe(this->parent_ray_sensor_->Topic(),
00179 # else
00180 this->gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(),
00181 # endif
00182 &GazeboRosLaser::OnScan, this);
00183 }
00184
00186
00187 void GazeboRosLaser::LaserDisconnect()
00188 {
00189 this->laser_connect_count_--;
00190 if (this->laser_connect_count_ == 0)
00191 this->laser_scan_sub_.reset();
00192 }
00193
00195
00196 void GazeboRosLaser::OnScan(ConstLaserScanStampedPtr &_msg)
00197 {
00198
00199
00200 sensor_msgs::LaserScan laser_msg;
00201 laser_msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
00202 laser_msg.header.frame_id = this->frame_name_;
00203 laser_msg.angle_min = _msg->scan().angle_min();
00204 laser_msg.angle_max = _msg->scan().angle_max();
00205 laser_msg.angle_increment = _msg->scan().angle_step();
00206 laser_msg.time_increment = 0;
00207 laser_msg.scan_time = 0;
00208 laser_msg.range_min = _msg->scan().range_min();
00209 laser_msg.range_max = _msg->scan().range_max();
00210 laser_msg.ranges.resize(_msg->scan().ranges_size());
00211 std::copy(_msg->scan().ranges().begin(),
00212 _msg->scan().ranges().end(),
00213 laser_msg.ranges.begin());
00214 laser_msg.intensities.resize(_msg->scan().intensities_size());
00215 std::copy(_msg->scan().intensities().begin(),
00216 _msg->scan().intensities().end(),
00217 laser_msg.intensities.begin());
00218 this->pub_queue_->push(laser_msg, this->pub_);
00219 }
00220 }