gazebo_ros_block_laser.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 /*
18  * Desc: ros laser controller.
19  * Author: Nathan Koenig
20  * Date: 01 Feb 2007
21  */
22 
23 #ifndef GAZEBO_ROS_BLOCK_LASER_HH
24 #define GAZEBO_ROS_BLOCK_LASER_HH
25 
26 // Custom Callback Queue
27 #include <ros/ros.h>
28 #include <ros/callback_queue.h>
29 #include <ros/advertise_options.h>
30 
31 #include <sdf/Param.hh>
32 #include <gazebo/physics/physics.hh>
33 #include <gazebo/transport/TransportTypes.hh>
34 #include <gazebo/msgs/MessageTypes.hh>
35 #include <gazebo/common/Time.hh>
36 #include <gazebo/common/Plugin.hh>
37 #include <gazebo/sensors/SensorTypes.hh>
38 #include <gazebo/plugins/RayPlugin.hh>
39 
40 #include <boost/bind.hpp>
41 #include <boost/thread.hpp>
42 #include <boost/thread/mutex.hpp>
43 
44 #include <sensor_msgs/PointCloud.h>
45 
46 namespace gazebo
47 {
48 
49  class GazeboRosBlockLaser : public RayPlugin
50  {
53  public: GazeboRosBlockLaser();
54 
56  public: ~GazeboRosBlockLaser();
57 
60  public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
61 
63  protected: virtual void OnNewLaserScans();
64 
66  private: void PutLaserData(common::Time &_updateTime);
67 
68  private: common::Time last_update_time_;
69 
71  private: int laser_connect_count_;
72  private: void LaserConnect();
73  private: void LaserDisconnect();
74 
75  // Pointer to the model
76  private: physics::WorldPtr world_;
78  private: sensors::SensorPtr parent_sensor_;
79  private: sensors::RaySensorPtr parent_ray_sensor_;
80 
83  private: ros::Publisher pub_;
84 
86  private: sensor_msgs::PointCloud cloud_msg_;
87 
89  private: std::string topic_name_;
90 
92  private: std::string frame_name_;
93 
95  private: double gaussian_noise_;
96 
98  private: double GaussianKernel(double mu,double sigma);
99 
101  private: boost::mutex lock;
102 
104  //private: ParamT<double> *hokuyoMinIntensityP;
105  private: double hokuyo_min_intensity_;
106 
108  private: double update_rate_;
109 
111  private: std::string robot_namespace_;
112 
113  // Custom Callback Queue
115  private: void LaserQueueThread();
116  private: boost::thread callback_laser_queue_thread_;
117 
118  // subscribe to world stats
119  private: transport::NodePtr node_;
120  private: common::Time sim_time_;
121  public: void OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg);
122 
123  };
124 
125 }
126 
127 #endif
128 
ros::Publisher
gazebo::GazeboRosBlockLaser::laser_connect_count_
int laser_connect_count_
Keep track of number of connctions.
Definition: gazebo_ros_block_laser.h:71
boost::shared_ptr
gazebo
gazebo::GazeboRosBlockLaser::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_block_laser.h:82
ros.h
gazebo::GazeboRosBlockLaser::OnStats
void OnStats(const boost::shared_ptr< msgs::WorldStatistics const > &_msg)
Definition: gazebo_ros_block_laser.cpp:419
gazebo::GazeboRosBlockLaser::callback_laser_queue_thread_
boost::thread callback_laser_queue_thread_
Definition: gazebo_ros_block_laser.h:116
gazebo::GazeboRosBlockLaser
Definition: gazebo_ros_block_laser.h:49
gazebo::GazeboRosBlockLaser::laser_queue_
ros::CallbackQueue laser_queue_
Definition: gazebo_ros_block_laser.h:114
gazebo::GazeboRosBlockLaser::hokuyo_min_intensity_
double hokuyo_min_intensity_
hack to mimic hokuyo intensity cutoff of 100
Definition: gazebo_ros_block_laser.h:105
gazebo::GazeboRosBlockLaser::world_
physics::WorldPtr world_
Definition: gazebo_ros_block_laser.h:76
gazebo::GazeboRosBlockLaser::LaserConnect
void LaserConnect()
Definition: gazebo_ros_block_laser.cpp:197
gazebo::GazeboRosBlockLaser::lock
boost::mutex lock
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_block_laser.h:101
gazebo::GazeboRosBlockLaser::GazeboRosBlockLaser
GazeboRosBlockLaser()
Constructor.
Definition: gazebo_ros_block_laser.cpp:58
gazebo::GazeboRosBlockLaser::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_block_laser.h:111
ros::CallbackQueue
gazebo::GazeboRosBlockLaser::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_block_laser.h:89
gazebo::GazeboRosBlockLaser::frame_name_
std::string frame_name_
frame transform name, should match link name
Definition: gazebo_ros_block_laser.h:92
gazebo::GazeboRosBlockLaser::~GazeboRosBlockLaser
~GazeboRosBlockLaser()
Destructor.
Definition: gazebo_ros_block_laser.cpp:64
gazebo::GazeboRosBlockLaser::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_block_laser.cpp:392
callback_queue.h
gazebo::GazeboRosBlockLaser::LaserDisconnect
void LaserDisconnect()
Definition: gazebo_ros_block_laser.cpp:204
gazebo::GazeboRosBlockLaser::parent_ray_sensor_
sensors::RaySensorPtr parent_ray_sensor_
Definition: gazebo_ros_block_laser.h:79
gazebo::GazeboRosBlockLaser::parent_sensor_
sensors::SensorPtr parent_sensor_
The parent sensor.
Definition: gazebo_ros_block_laser.h:78
gazebo::GazeboRosBlockLaser::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_block_laser.h:68
advertise_options.h
gazebo::GazeboRosBlockLaser::pub_
ros::Publisher pub_
Definition: gazebo_ros_block_laser.h:83
gazebo::GazeboRosBlockLaser::LaserQueueThread
void LaserQueueThread()
Definition: gazebo_ros_block_laser.cpp:409
gazebo::GazeboRosBlockLaser::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_block_laser.h:95
gazebo::GazeboRosBlockLaser::OnNewLaserScans
virtual void OnNewLaserScans()
Update the controller.
Definition: gazebo_ros_block_laser.cpp:214
gazebo::GazeboRosBlockLaser::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_block_laser.cpp:78
gazebo::GazeboRosBlockLaser::node_
transport::NodePtr node_
Definition: gazebo_ros_block_laser.h:119
gazebo::GazeboRosBlockLaser::sim_time_
common::Time sim_time_
Definition: gazebo_ros_block_laser.h:120
gazebo::GazeboRosBlockLaser::update_rate_
double update_rate_
update rate of this sensor
Definition: gazebo_ros_block_laser.h:108
gazebo::GazeboRosBlockLaser::cloud_msg_
sensor_msgs::PointCloud cloud_msg_
ros message
Definition: gazebo_ros_block_laser.h:86
ros::NodeHandle
gazebo::GazeboRosBlockLaser::PutLaserData
void PutLaserData(common::Time &_updateTime)
Put laser data to the ROS topic.
Definition: gazebo_ros_block_laser.cpp:248


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28