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 <gazebo/physics/World.hh>
00029 #include <gazebo/physics/HingeJoint.hh>
00030 #include <gazebo/sensors/Sensor.hh>
00031 #include <sdf/sdf.hh>
00032 #include <sdf/Param.hh>
00033 #include <gazebo/common/Exception.hh>
00034 #include <gazebo/sensors/RaySensor.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_laser.h>
00042
00043 namespace gazebo
00044 {
00045
00046 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosLaser)
00047
00048
00049
00050 GazeboRosLaser::GazeboRosLaser()
00051 {
00052 this->seed = 0;
00053 }
00054
00056
00057 GazeboRosLaser::~GazeboRosLaser()
00058 {
00059 this->rosnode_->shutdown();
00060 delete this->rosnode_;
00061 }
00062
00064
00065 void GazeboRosLaser::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00066 {
00067
00068 RayPlugin::Load(_parent, this->sdf);
00069
00070 std::string worldName = _parent->GetWorldName();
00071 this->world_ = physics::get_world(worldName);
00072
00073 this->sdf = _sdf;
00074
00075 this->parent_ray_sensor_ =
00076 boost::dynamic_pointer_cast<sensors::RaySensor>(_parent);
00077
00078 if (!this->parent_ray_sensor_)
00079 gzthrow("GazeboRosLaser controller requires a Ray Sensor as its parent");
00080
00081 this->robot_namespace_ = GetRobotNamespace(_parent, _sdf, "Laser");
00082
00083 if (!this->sdf->HasElement("frameName"))
00084 {
00085 ROS_INFO("Laser plugin missing <frameName>, defaults to /world");
00086 this->frame_name_ = "/world";
00087 }
00088 else
00089 this->frame_name_ = this->sdf->Get<std::string>("frameName");
00090
00091
00092 if (!this->sdf->HasElement("topicName"))
00093 {
00094 ROS_INFO("Laser plugin missing <topicName>, defaults to /world");
00095 this->topic_name_ = "/world";
00096 }
00097 else
00098 this->topic_name_ = this->sdf->Get<std::string>("topicName");
00099
00100 this->laser_connect_count_ = 0;
00101
00102
00103 if (!ros::isInitialized())
00104 {
00105 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00106 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00107 return;
00108 }
00109
00110 ROS_INFO ( "Starting Laser Plugin (ns = %s)!", this->robot_namespace_.c_str() );
00111
00112 this->deferred_load_thread_ = boost::thread(
00113 boost::bind(&GazeboRosLaser::LoadThread, this));
00114
00115 }
00116
00118
00119 void GazeboRosLaser::LoadThread()
00120 {
00121 this->gazebo_node_ = gazebo::transport::NodePtr(new gazebo::transport::Node());
00122 this->gazebo_node_->Init(this->world_name_);
00123
00124 this->pmq.startServiceThread();
00125
00126 this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00127
00128 this->tf_prefix_ = tf::getPrefixParam(*this->rosnode_);
00129 if(this->tf_prefix_.empty()) {
00130 this->tf_prefix_ = this->robot_namespace_;
00131 boost::trim_right_if(this->tf_prefix_,boost::is_any_of("/"));
00132 }
00133 ROS_INFO("Laser Plugin (ns = %s) <tf_prefix_>, set to \"%s\"",
00134 this->robot_namespace_.c_str(), this->tf_prefix_.c_str());
00135
00136
00137 this->frame_name_ = tf::resolve(this->tf_prefix_, this->frame_name_);
00138
00139 if (this->topic_name_ != "")
00140 {
00141 ros::AdvertiseOptions ao =
00142 ros::AdvertiseOptions::create<sensor_msgs::LaserScan>(
00143 this->topic_name_, 1,
00144 boost::bind(&GazeboRosLaser::LaserConnect, this),
00145 boost::bind(&GazeboRosLaser::LaserDisconnect, this),
00146 ros::VoidPtr(), NULL);
00147 this->pub_ = this->rosnode_->advertise(ao);
00148 this->pub_queue_ = this->pmq.addPub<sensor_msgs::LaserScan>();
00149 }
00150
00151
00152
00153
00154 this->parent_ray_sensor_->SetActive(false);
00155 }
00156
00158
00159 void GazeboRosLaser::LaserConnect()
00160 {
00161 this->laser_connect_count_++;
00162 if (this->laser_connect_count_ == 1)
00163 this->laser_scan_sub_ =
00164 this->gazebo_node_->Subscribe(this->parent_ray_sensor_->GetTopic(),
00165 &GazeboRosLaser::OnScan, this);
00166 }
00167
00169
00170 void GazeboRosLaser::LaserDisconnect()
00171 {
00172 this->laser_connect_count_--;
00173 if (this->laser_connect_count_ == 0)
00174 this->laser_scan_sub_.reset();
00175 }
00176
00178
00179 void GazeboRosLaser::OnScan(ConstLaserScanStampedPtr &_msg)
00180 {
00181
00182
00183 sensor_msgs::LaserScan laser_msg;
00184 laser_msg.header.stamp = ros::Time(_msg->time().sec(), _msg->time().nsec());
00185 laser_msg.header.frame_id = this->frame_name_;
00186 laser_msg.angle_min = _msg->scan().angle_min();
00187 laser_msg.angle_max = _msg->scan().angle_max();
00188 laser_msg.angle_increment = _msg->scan().angle_step();
00189 laser_msg.time_increment = 0;
00190 laser_msg.scan_time = 0;
00191 laser_msg.range_min = _msg->scan().range_min();
00192 laser_msg.range_max = _msg->scan().range_max();
00193 laser_msg.ranges.resize(_msg->scan().ranges_size());
00194 std::copy(_msg->scan().ranges().begin(),
00195 _msg->scan().ranges().end(),
00196 laser_msg.ranges.begin());
00197 laser_msg.intensities.resize(_msg->scan().intensities_size());
00198 std::copy(_msg->scan().intensities().begin(),
00199 _msg->scan().intensities().end(),
00200 laser_msg.intensities.begin());
00201 this->pub_queue_->push(laser_msg, this->pub_);
00202 }
00203 }