Public Member Functions | Private Attributes
stdr_robot::Laser Class Reference

A class that provides laser implementation. Inherits publicly Sensor. More...

#include <laser.h>

Inheritance diagram for stdr_robot::Laser:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 Laser (const nav_msgs::OccupancyGrid &map, const stdr_msgs::LaserSensorMsg &msg, const std::string &name, ros::NodeHandle &n)
 Default constructor.
virtual void updateSensorCallback ()
 Updates the sensor measurements.
 ~Laser ()
 Default destructor.

Private Attributes

stdr_msgs::LaserSensorMsg _description
 < Laser sensor description

Detailed Description

A class that provides laser implementation. Inherits publicly Sensor.

Definition at line 39 of file laser.h.


Constructor & Destructor Documentation

stdr_robot::Laser::Laser ( const nav_msgs::OccupancyGrid &  map,
const stdr_msgs::LaserSensorMsg &  msg,
const std::string &  name,
ros::NodeHandle n 
)

Default constructor.

Parameters:
map[const nav_msgs::OccupancyGrid&] An occupancy grid map
msg[const stdr_msgs::LaserSensorMsg&] The laser description message
name[const std::string&] The sensor frame id without the base
n[ros::NodeHandle&] The ROS node handle
Returns:
void

Definition at line 34 of file laser.cpp.

Default destructor.

Returns:
void

Definition at line 66 of file laser.h.


Member Function Documentation

void stdr_robot::Laser::updateSensorCallback ( void  ) [virtual]

Updates the sensor measurements.

Returns:
void

Implements stdr_robot::Sensor.

Definition at line 51 of file laser.cpp.


Member Data Documentation

stdr_msgs::LaserSensorMsg stdr_robot::Laser::_description [private]

< Laser sensor description

Definition at line 71 of file laser.h.


The documentation for this class was generated from the following files:


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Wed Sep 2 2015 03:36:25