gazebo_ros_block_laser.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2012-2014 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  * Desc: ros laser controller.
00019  * Author: Nathan Koenig
00020  * Date: 01 Feb 2007
00021  */
00022 
00023 #ifndef GAZEBO_ROS_BLOCK_LASER_HH
00024 #define GAZEBO_ROS_BLOCK_LASER_HH
00025 
00026 // Custom Callback Queue
00027 #include <ros/ros.h>
00028 #include <ros/callback_queue.h>
00029 #include <ros/advertise_options.h>
00030 
00031 #include <sdf/Param.hh>
00032 #include <gazebo/physics/physics.hh>
00033 #include <gazebo/transport/TransportTypes.hh>
00034 #include <gazebo/msgs/MessageTypes.hh>
00035 #include <gazebo/common/Time.hh>
00036 #include <gazebo/common/Plugin.hh>
00037 #include <gazebo/sensors/SensorTypes.hh>
00038 #include <gazebo/plugins/RayPlugin.hh>
00039 
00040 #include <boost/bind.hpp>
00041 #include <boost/thread.hpp>
00042 #include <boost/thread/mutex.hpp>
00043 
00044 #include <sensor_msgs/PointCloud.h>
00045 
00046 namespace gazebo
00047 {
00048 
00049   class GazeboRosBlockLaser : public RayPlugin
00050   {
00053     public: GazeboRosBlockLaser();
00054 
00056     public: ~GazeboRosBlockLaser();
00057 
00060     public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00061 
00063     protected: virtual void OnNewLaserScans();
00064 
00066     private: void PutLaserData(common::Time &_updateTime);
00067 
00068     private: common::Time last_update_time_;
00069 
00071     private: int laser_connect_count_;
00072     private: void LaserConnect();
00073     private: void LaserDisconnect();
00074 
00075     // Pointer to the model
00076     private: physics::WorldPtr world_;
00078     private: sensors::SensorPtr parent_sensor_;
00079     private: sensors::RaySensorPtr parent_ray_sensor_;
00080 
00082     private: ros::NodeHandle* rosnode_;
00083     private: ros::Publisher pub_;
00084 
00086     private: sensor_msgs::PointCloud cloud_msg_;
00087    
00089     private: std::string topic_name_;
00090 
00092     private: std::string frame_name_;
00093 
00095     private: double gaussian_noise_;
00096 
00098     private: double GaussianKernel(double mu,double sigma);
00099 
00101     private: boost::mutex lock;
00102 
00104     //private: ParamT<double> *hokuyoMinIntensityP;
00105     private: double hokuyo_min_intensity_;
00106 
00108     private: double update_rate_;
00109 
00111     private: std::string robot_namespace_;
00112 
00113     // Custom Callback Queue
00114     private: ros::CallbackQueue laser_queue_;
00115     private: void LaserQueueThread();
00116     private: boost::thread callback_laser_queue_thread_;
00117 
00118     // subscribe to world stats
00119     private: transport::NodePtr node_;
00120     private: common::Time sim_time_;
00121     public: void OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg);
00122 
00123   };
00124 
00125 }
00126 
00127 #endif
00128 


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:09