1 #ifndef GAZEBO_ROS_IR_SENSOR_HH 2 #define GAZEBO_ROS_IR_SENSOR_HH 6 #include <boost/bind.hpp> 7 #include <boost/thread.hpp> 11 #include "std_msgs/Float32.h" 13 #include <sdf/Param.hh> 14 #include <gazebo/physics/physics.hh> 15 #include <gazebo/transport/TransportTypes.hh> 16 #include <gazebo/msgs/MessageTypes.hh> 17 #include <gazebo/common/Time.hh> 18 #include <gazebo/common/Plugin.hh> 19 #include <gazebo/common/Events.hh> 20 #include <gazebo/sensors/SensorTypes.hh> 21 #include <gazebo/plugins/RayPlugin.hh> 36 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
69 private: sdf::ElementPtr
sdf_;
76 private:
void OnScan(ConstLaserScanStampedPtr &_msg);
gazebo::transport::SubscriberPtr ir_sensor_scan_sub_
ros::NodeHandle * rosnode_
PubQueue< std_msgs::Float32 >::Ptr pub_queue_
void IrSensorDisconnect()
std::string robot_namespace_
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
gazebo::transport::NodePtr gazebo_node_
int ir_sensor_connect_count_
boost::thread deferred_load_thread_
sensors::RaySensorPtr parent_ray_sensor_
void OnScan(ConstLaserScanStampedPtr &_msg)