ROS laser block simulation. More...
#include <gazebo_ros_block_laser.h>
Public Member Functions | |
| GazeboRosBlockLaser (Entity *parent) | |
| Constructor. | |
| virtual | ~GazeboRosBlockLaser () |
| Destructor. | |
Protected Member Functions | |
| virtual void | FiniChild () |
| Finalize the controller. | |
| virtual void | InitChild () |
| Init the controller. | |
| virtual void | LoadChild (XMLConfigNode *node) |
| Load the controller. | |
| virtual void | UpdateChild () |
| Update the controller. | |
Private Member Functions | |
| double | GaussianKernel (double mu, double sigma) |
| Gaussian noise generator. | |
| void | LaserConnect () |
| void | LaserDisconnect () |
| void | PutLaserData () |
| Put laser data to the ROS topic. | |
| void | QueueThread () |
Private Attributes | |
| boost::thread | callback_queue_thread_ |
| sensor_msgs::PointCloud | cloudMsg |
| ros message | |
| std::string | frameName |
| ParamT< std::string > * | frameNameP |
| frame transform name, should match link name | |
| double | gaussianNoise |
| ParamT< double > * | gaussianNoiseP |
| Gaussian noise. | |
| int | laserConnectCount |
| Keep track of number of connctions. | |
| boost::mutex | lock |
| A mutex to lock access to fields that are used in message callbacks. | |
| RaySensor * | myParent |
| The parent sensor. | |
| ros::Publisher | pub_ |
| ros::CallbackQueue | queue_ |
| std::string | robotNamespace |
| ParamT< std::string > * | robotNamespaceP |
| for setting ROS name space | |
| ros::NodeHandle * | rosnode_ |
| pointer to ros node | |
| std::string | topicName |
| ParamT< std::string > * | topicNameP |
| topic name | |
ROS laser block simulation.
<model:physical name="ray_model">
<body:empty name="ray_body_name">
<sensor:ray name="ray_sensor">
<rayCount>30</rayCount>
<rangeCount>30</rangeCount>
<laserCount>1</laserCount>
<origin>0.0 0.0 0.05</origin>
<displayRays>false</displayRays>
<minAngle>-15</minAngle>
<maxAngle> 15</maxAngle>
<minRange>0.05</minRange>
<maxRange>100.0</maxRange>
<updateRate>10.0</updateRate>
<verticalRayCount>30</verticalRayCount>
<verticalRangeCount>30</verticalRangeCount>
<verticalMinAngle>-20</verticalMinAngle>
<verticalMaxAngle> 0</verticalMaxAngle>
<controller:gazebo_ros_block_laser name="ray_block_controller" plugin="libgazebo_ros_block_laser.so">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>10.0</updateRate>
<topicName>full_cloud</topicName>
<frameName>ray_model</frameName>
<interface:laser name="ray_block_iface" />
</controller:gazebo_ros_block_laser>
</sensor:ray>
</body:empty>
</model:phyiscal>
Definition at line 136 of file gazebo_ros_block_laser.h.
| GazeboRosBlockLaser::GazeboRosBlockLaser | ( | Entity * | parent | ) |
Constructor.
| parent | The parent entity, must be a Model or a Sensor |
Definition at line 53 of file gazebo_ros_block_laser.cpp.
| GazeboRosBlockLaser::~GazeboRosBlockLaser | ( | ) | [virtual] |
Destructor.
Definition at line 71 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::FiniChild | ( | ) | [protected, virtual] |
Finalize the controller.
Definition at line 162 of file gazebo_ros_block_laser.cpp.
| double GazeboRosBlockLaser::GaussianKernel | ( | double | mu, | |
| double | sigma | |||
| ) | [private] |
Gaussian noise generator.
Definition at line 305 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::InitChild | ( | ) | [protected, virtual] |
Init the controller.
Definition at line 134 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::LaserConnect | ( | ) | [private] |
Definition at line 119 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::LaserDisconnect | ( | ) | [private] |
Definition at line 125 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Load the controller.
| node | XML config node |
Definition at line 82 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::PutLaserData | ( | ) | [private] |
Put laser data to the ROS topic.
Definition at line 173 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::QueueThread | ( | ) | [private] |
Definition at line 322 of file gazebo_ros_block_laser.cpp.
| void GazeboRosBlockLaser::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 144 of file gazebo_ros_block_laser.cpp.
boost::thread gazebo::GazeboRosBlockLaser::callback_queue_thread_ [private] |
Definition at line 203 of file gazebo_ros_block_laser.h.
sensor_msgs::PointCloud gazebo::GazeboRosBlockLaser::cloudMsg [private] |
ros message
Definition at line 174 of file gazebo_ros_block_laser.h.
std::string gazebo::GazeboRosBlockLaser::frameName [private] |
Definition at line 183 of file gazebo_ros_block_laser.h.
ParamT<std::string>* gazebo::GazeboRosBlockLaser::frameNameP [private] |
frame transform name, should match link name
FIXME: extract link name directly?
Definition at line 182 of file gazebo_ros_block_laser.h.
double gazebo::GazeboRosBlockLaser::gaussianNoise [private] |
Definition at line 187 of file gazebo_ros_block_laser.h.
ParamT<double>* gazebo::GazeboRosBlockLaser::gaussianNoiseP [private] |
Gaussian noise.
Definition at line 186 of file gazebo_ros_block_laser.h.
int gazebo::GazeboRosBlockLaser::laserConnectCount [private] |
Keep track of number of connctions.
Definition at line 162 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 193 of file gazebo_ros_block_laser.h.
RaySensor* gazebo::GazeboRosBlockLaser::myParent [private] |
The parent sensor.
Definition at line 167 of file gazebo_ros_block_laser.h.
ros::Publisher gazebo::GazeboRosBlockLaser::pub_ [private] |
Definition at line 171 of file gazebo_ros_block_laser.h.
ros::CallbackQueue gazebo::GazeboRosBlockLaser::queue_ [private] |
Definition at line 201 of file gazebo_ros_block_laser.h.
std::string gazebo::GazeboRosBlockLaser::robotNamespace [private] |
Definition at line 198 of file gazebo_ros_block_laser.h.
ParamT<std::string>* gazebo::GazeboRosBlockLaser::robotNamespaceP [private] |
for setting ROS name space
Definition at line 197 of file gazebo_ros_block_laser.h.
ros::NodeHandle* gazebo::GazeboRosBlockLaser::rosnode_ [private] |
pointer to ros node
Definition at line 170 of file gazebo_ros_block_laser.h.
std::string gazebo::GazeboRosBlockLaser::topicName [private] |
Definition at line 178 of file gazebo_ros_block_laser.h.
ParamT<std::string>* gazebo::GazeboRosBlockLaser::topicNameP [private] |
topic name
Definition at line 177 of file gazebo_ros_block_laser.h.