$search
ROS laser scan controller. More...
#include <gazebo_ros_laser.h>
Public Member Functions | |
GazeboRosLaser (Entity *parent) | |
Constructor. | |
virtual | ~GazeboRosLaser () |
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 | |
void | DeprecatedLaserConnect () |
void | DeprecatedLaserDisconnect () |
double | GaussianKernel (double mu, double sigma) |
Gaussian noise generator. | |
void | LaserConnect () |
void | LaserDisconnect () |
void | PutLaserData () |
Put laser data to the ROS topic. | |
Private Attributes | |
ros::Publisher | deprecated_pub_ |
int | deprecatedLaserConnectCount |
std::string | deprecatedTopicName |
ParamT< std::string > * | deprecatedTopicNameP |
std::string | frameName |
ParamT< std::string > * | frameNameP |
frame transform name, should match link name | |
double | gaussianNoise |
ParamT< double > * | gaussianNoiseP |
Gaussian noise. | |
double | hokuyoMinIntensity |
ParamT< double > * | hokuyoMinIntensityP |
hack to mimic hokuyo intensity cutoff of 100 | |
int | laserConnectCount |
Keep track of number of connctions. | |
sensor_msgs::LaserScan | laserMsg |
ros message | |
boost::mutex | lock |
A mutex to lock access to fields that are used in message callbacks. | |
RaySensor * | myParent |
The parent sensor. | |
ros::Publisher | pub_ |
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 scan controller.
<model:physical name="ray_model"> <body:empty name="ray_body_name"> <sensor:ray name="ray_sensor"> <origin>0.0 0.0 0.0</origin> <rayCount>683</rayCount> <rangeCount>683</rangeCount> <laserCount>1</laserCount> <displayRays>false</displayRays> <minAngle>-45</minAngle> <maxAngle> 45</maxAngle> <minRange>0.05</minRange> <maxRange>10.0</maxRange> <updateRate>10.0</updateRate> <controller:gazebo_ros_laser name="ros_ray_sensor_controller" plugin="libgazebo_ros_laser.so"> <gaussianNoise>0.005</gaussianNoise> <alwaysOn>true</alwaysOn> <updateRate>15.0</updateRate> <topicName>ray_scan</topicName> <frameName>ray_model</frameName> <interface:laser name="ros_ray_sensor_iface" /> </controller:gazebo_ros_laser> </sensor:ray> </body:empty> </model:phyiscal>
Definition at line 122 of file gazebo_ros_laser.h.
gazebo::GazeboRosLaser::GazeboRosLaser | ( | Entity * | parent | ) |
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 51 of file gazebo_ros_laser.cpp.
gazebo::GazeboRosLaser::~GazeboRosLaser | ( | ) | [virtual] |
Destructor.
Definition at line 74 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::DeprecatedLaserConnect | ( | ) | [private] |
Definition at line 175 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::DeprecatedLaserDisconnect | ( | ) | [private] |
Definition at line 183 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::FiniChild | ( | ) | [protected, virtual] |
Finalize the controller.
Definition at line 212 of file gazebo_ros_laser.cpp.
double gazebo::GazeboRosLaser::GaussianKernel | ( | double | mu, | |
double | sigma | |||
) | [private] |
Gaussian noise generator.
Definition at line 307 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::InitChild | ( | ) | [protected, virtual] |
Init the controller.
Definition at line 147 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::LaserConnect | ( | ) | [private] |
Definition at line 159 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::LaserDisconnect | ( | ) | [private] |
Definition at line 165 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Load the controller.
node | XML config node |
Definition at line 87 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::PutLaserData | ( | ) | [private] |
Put laser data to the ROS topic.
Definition at line 225 of file gazebo_ros_laser.cpp.
void gazebo::GazeboRosLaser::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 193 of file gazebo_ros_laser.cpp.
Definition at line 161 of file gazebo_ros_laser.h.
int gazebo::GazeboRosLaser::deprecatedLaserConnectCount [private] |
Definition at line 151 of file gazebo_ros_laser.h.
std::string gazebo::GazeboRosLaser::deprecatedTopicName [private] |
Definition at line 170 of file gazebo_ros_laser.h.
ParamT<std::string>* gazebo::GazeboRosLaser::deprecatedTopicNameP [private] |
Definition at line 169 of file gazebo_ros_laser.h.
std::string gazebo::GazeboRosLaser::frameName [private] |
Definition at line 174 of file gazebo_ros_laser.h.
ParamT<std::string>* gazebo::GazeboRosLaser::frameNameP [private] |
frame transform name, should match link name
Definition at line 173 of file gazebo_ros_laser.h.
double gazebo::GazeboRosLaser::gaussianNoise [private] |
Definition at line 178 of file gazebo_ros_laser.h.
ParamT<double>* gazebo::GazeboRosLaser::gaussianNoiseP [private] |
Gaussian noise.
Definition at line 177 of file gazebo_ros_laser.h.
double gazebo::GazeboRosLaser::hokuyoMinIntensity [private] |
Definition at line 188 of file gazebo_ros_laser.h.
ParamT<double>* gazebo::GazeboRosLaser::hokuyoMinIntensityP [private] |
hack to mimic hokuyo intensity cutoff of 100
Definition at line 187 of file gazebo_ros_laser.h.
int gazebo::GazeboRosLaser::laserConnectCount [private] |
Keep track of number of connctions.
Definition at line 148 of file gazebo_ros_laser.h.
ros message
Definition at line 164 of file gazebo_ros_laser.h.
boost::mutex gazebo::GazeboRosLaser::lock [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 184 of file gazebo_ros_laser.h.
RaySensor* gazebo::GazeboRosLaser::myParent [private] |
The parent sensor.
Definition at line 156 of file gazebo_ros_laser.h.
ros::Publisher gazebo::GazeboRosLaser::pub_ [private] |
Definition at line 160 of file gazebo_ros_laser.h.
std::string gazebo::GazeboRosLaser::robotNamespace [private] |
Definition at line 192 of file gazebo_ros_laser.h.
ParamT<std::string>* gazebo::GazeboRosLaser::robotNamespaceP [private] |
for setting ROS name space
Definition at line 191 of file gazebo_ros_laser.h.
ros::NodeHandle* gazebo::GazeboRosLaser::rosnode_ [private] |
pointer to ros node
Definition at line 159 of file gazebo_ros_laser.h.
std::string gazebo::GazeboRosLaser::topicName [private] |
Definition at line 168 of file gazebo_ros_laser.h.
ParamT<std::string>* gazebo::GazeboRosLaser::topicNameP [private] |
topic name
Definition at line 167 of file gazebo_ros_laser.h.