00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef GAZEBO_ROS_BLOCK_LASER_HH
00029 #define GAZEBO_ROS_BLOCK_LASER_HH
00030
00031
00032 #include <ros/callback_queue.h>
00033 #include <ros/advertise_options.h>
00034
00035 #include <gazebo/Controller.hh>
00036
00037 #include <ros/ros.h>
00038 #include "boost/thread/mutex.hpp"
00039 #include <sensor_msgs/PointCloud.h>
00040 #include <gazebo/Param.hh>
00041
00042 namespace gazebo
00043 {
00044 class RaySensor;
00045
00048
00138 class GazeboRosBlockLaser : public Controller
00139 {
00142 public: GazeboRosBlockLaser(Entity *parent);
00143
00145 public: virtual ~GazeboRosBlockLaser();
00146
00149 protected: virtual void LoadChild(XMLConfigNode *node);
00150
00152 protected: virtual void InitChild();
00153
00155 protected: virtual void UpdateChild();
00156
00158 protected: virtual void FiniChild();
00159
00161 private: void PutLaserData();
00162
00164 private: int laserConnectCount;
00165 private: void LaserConnect();
00166 private: void LaserDisconnect();
00167
00169 private: RaySensor *myParent;
00170
00172 private: ros::NodeHandle* rosnode_;
00173 private: ros::Publisher pub_;
00174
00176 private: sensor_msgs::PointCloud cloudMsg;
00177
00179 private: ParamT<std::string> *topicNameP;
00180 private: std::string topicName;
00181
00184 private: ParamT<std::string> *frameNameP;
00185 private: std::string frameName;
00186
00188 private: ParamT<double> *gaussianNoiseP;
00189 private: double gaussianNoise;
00190
00192 private: double GaussianKernel(double mu,double sigma);
00193
00195 private: boost::mutex lock;
00196
00197
00199 private: ParamT<std::string> *robotNamespaceP;
00200 private: std::string robotNamespace;
00201
00202
00203 private: ros::CallbackQueue queue_;
00204 private: void QueueThread();
00205 private: boost::thread callback_queue_thread_;
00206
00207 };
00208
00210
00211
00212 }
00213
00214 #endif
00215