#include <gazebo_ros_block_laser.h>
Public Member Functions | |
GazeboRosBlockLaser () | |
Constructor. | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. | |
void | OnStats (const boost::shared_ptr< msgs::WorldStatistics const > &_msg) |
~GazeboRosBlockLaser () | |
Destructor. | |
Protected Member Functions | |
virtual void | OnNewLaserScans () |
Update the controller. | |
Private Member Functions | |
double | GaussianKernel (double mu, double sigma) |
Gaussian noise generator. | |
void | LaserConnect () |
void | LaserDisconnect () |
void | LaserQueueThread () |
void | PutLaserData (common::Time &_updateTime) |
Put laser data to the ROS topic. | |
Private Attributes | |
boost::thread | callback_laser_queue_thread_ |
sensor_msgs::PointCloud | cloud_msg_ |
ros message | |
std::string | frame_name_ |
frame transform name, should match link name | |
double | gaussian_noise_ |
Gaussian noise. | |
double | hokuyo_min_intensity_ |
hack to mimic hokuyo intensity cutoff of 100 | |
int | laser_connect_count_ |
Keep track of number of connctions. | |
ros::CallbackQueue | laser_queue_ |
common::Time | last_update_time_ |
boost::mutex | lock |
A mutex to lock access to fields that are used in message callbacks. | |
transport::NodePtr | node_ |
sensors::RaySensorPtr | parent_ray_sensor_ |
sensors::SensorPtr | parent_sensor_ |
The parent sensor. | |
ros::Publisher | pub_ |
std::string | robot_namespace_ |
for setting ROS name space | |
ros::NodeHandle * | rosnode_ |
pointer to ros node | |
common::Time | sim_time_ |
std::string | topic_name_ |
topic name | |
double | update_rate_ |
update rate of this sensor | |
physics::WorldPtr | world_ |
Definition at line 54 of file gazebo_ros_block_laser.h.
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 53 of file gazebo_ros_block_laser.cpp.
Destructor.
Definition at line 59 of file gazebo_ros_block_laser.cpp.
double gazebo::GazeboRosBlockLaser::GaussianKernel | ( | double | mu, |
double | sigma | ||
) | [private] |
Gaussian noise generator.
Definition at line 359 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::LaserConnect | ( | ) | [private] |
Definition at line 186 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::LaserDisconnect | ( | ) | [private] |
Definition at line 193 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::LaserQueueThread | ( | ) | [private] |
Definition at line 376 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::Load | ( | sensors::SensorPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the plugin.
take | in SDF root element |
Definition at line 73 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::OnNewLaserScans | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 203 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::OnStats | ( | const boost::shared_ptr< msgs::WorldStatistics const > & | _msg | ) |
Definition at line 386 of file gazebo_ros_block_laser.cpp.
void gazebo::GazeboRosBlockLaser::PutLaserData | ( | common::Time & | _updateTime | ) | [private] |
Put laser data to the ROS topic.
Definition at line 222 of file gazebo_ros_block_laser.cpp.
boost::thread gazebo::GazeboRosBlockLaser::callback_laser_queue_thread_ [private] |
Definition at line 121 of file gazebo_ros_block_laser.h.
ros message
Definition at line 91 of file gazebo_ros_block_laser.h.
std::string gazebo::GazeboRosBlockLaser::frame_name_ [private] |
frame transform name, should match link name
Definition at line 97 of file gazebo_ros_block_laser.h.
double gazebo::GazeboRosBlockLaser::gaussian_noise_ [private] |
Gaussian noise.
Definition at line 100 of file gazebo_ros_block_laser.h.
double gazebo::GazeboRosBlockLaser::hokuyo_min_intensity_ [private] |
hack to mimic hokuyo intensity cutoff of 100
Definition at line 110 of file gazebo_ros_block_laser.h.
int gazebo::GazeboRosBlockLaser::laser_connect_count_ [private] |
Keep track of number of connctions.
Definition at line 76 of file gazebo_ros_block_laser.h.
Definition at line 119 of file gazebo_ros_block_laser.h.
common::Time gazebo::GazeboRosBlockLaser::last_update_time_ [private] |
Definition at line 73 of file gazebo_ros_block_laser.h.
boost::mutex gazebo::GazeboRosBlockLaser::lock [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 106 of file gazebo_ros_block_laser.h.
transport::NodePtr gazebo::GazeboRosBlockLaser::node_ [private] |
Definition at line 124 of file gazebo_ros_block_laser.h.
sensors::RaySensorPtr gazebo::GazeboRosBlockLaser::parent_ray_sensor_ [private] |
Definition at line 84 of file gazebo_ros_block_laser.h.
sensors::SensorPtr gazebo::GazeboRosBlockLaser::parent_sensor_ [private] |
The parent sensor.
Definition at line 83 of file gazebo_ros_block_laser.h.
Definition at line 88 of file gazebo_ros_block_laser.h.
std::string gazebo::GazeboRosBlockLaser::robot_namespace_ [private] |
for setting ROS name space
Definition at line 116 of file gazebo_ros_block_laser.h.
pointer to ros node
Definition at line 87 of file gazebo_ros_block_laser.h.
common::Time gazebo::GazeboRosBlockLaser::sim_time_ [private] |
Definition at line 125 of file gazebo_ros_block_laser.h.
std::string gazebo::GazeboRosBlockLaser::topic_name_ [private] |
topic name
Definition at line 94 of file gazebo_ros_block_laser.h.
double gazebo::GazeboRosBlockLaser::update_rate_ [private] |
update rate of this sensor
Definition at line 113 of file gazebo_ros_block_laser.h.
physics::WorldPtr gazebo::GazeboRosBlockLaser::world_ [private] |
Definition at line 81 of file gazebo_ros_block_laser.h.