A class that provides sensor abstraction.
More...
#include <sensor_base.h>
|
| std::string | getFrameId (void) const |
| | Getter function for returning the sensor frame id. More...
|
| |
| geometry_msgs::Pose2D | getSensorPose (void) const |
| | Getter function for returning the sensor pose relatively to robot. More...
|
| |
| virtual void | updateSensorCallback (void)=0 |
| | Virtual function for sensor value callback. Implement this function on derived class to publish sensor measurements. More...
|
| |
| virtual | ~Sensor (void) |
| | Default destructor. More...
|
| |
A class that provides sensor abstraction.
Definition at line 40 of file sensor_base.h.
| virtual stdr_robot::Sensor::~Sensor |
( |
void |
| ) |
|
|
inlinevirtual |
Default destructor.
- Returns
- void
Definition at line 73 of file sensor_base.h.
| stdr_robot::Sensor::Sensor |
( |
const nav_msgs::OccupancyGrid & |
map, |
|
|
const std::string & |
name, |
|
|
ros::NodeHandle & |
n, |
|
|
const geometry_msgs::Pose2D & |
sensorPose, |
|
|
const std::string & |
sensorFrameId, |
|
|
float |
updateFrequency |
|
) |
| |
|
protected |
Default constructor.
- Parameters
-
| map | [const nav_msgs::OccupancyGrid&] An occupancy grid map |
| name | [const std::string&] The sensor frame id without the base |
| n | [ros::NodeHandle& n] A ROS NodeHandle to create timers |
| sensorPose | [const geometry_msgs::Pose2D&] The sensor's pose relative to robot |
| sensorFrameId | [const std::string&] The sensor's frame id |
| updateFrequency | [float] The sensor's update frequnecy |
- Returns
- void
Definition at line 36 of file sensor_base.cpp.
| void stdr_robot::Sensor::checkAndUpdateSensor |
( |
const ros::TimerEvent & |
ev | ) |
|
|
protected |
| std::string stdr_robot::Sensor::getFrameId |
( |
void |
| ) |
const |
|
inline |
Getter function for returning the sensor frame id.
- Returns
- std::string
Definition at line 64 of file sensor_base.h.
| geometry_msgs::Pose2D stdr_robot::Sensor::getSensorPose |
( |
void |
| ) |
const |
|
inline |
Getter function for returning the sensor pose relatively to robot.
- Returns
- geometry_msgs::Pose2D
Definition at line 55 of file sensor_base.h.
| virtual void stdr_robot::Sensor::updateSensorCallback |
( |
void |
| ) |
|
|
pure virtual |
Function for updating the sensor tf transform.
Updates the sensor tf transform.
- Parameters
-
- Returns
- void
-
void
Definition at line 76 of file sensor_base.cpp.
| bool stdr_robot::Sensor::_gotTransform |
|
protected |
| const nav_msgs::OccupancyGrid& stdr_robot::Sensor::_map |
|
protected |
| const std::string& stdr_robot::Sensor::_namespace |
|
protected |
< The base for the sensor frame_id
The environment occupancy grid map
Definition at line 114 of file sensor_base.h.
| const std::string stdr_robot::Sensor::_sensorFrameId |
|
protected |
A ROS timer for updating the sensor values.
Definition at line 123 of file sensor_base.h.
| const geometry_msgs::Pose2D stdr_robot::Sensor::_sensorPose |
|
protected |
True if sensor got the _sensorTransform.
Definition at line 135 of file sensor_base.h.
ROS publisher for posting the sensor measurements.
Definition at line 128 of file sensor_base.h.
A ROS timer for updating the sensor tf.
Definition at line 126 of file sensor_base.h.
| const float stdr_robot::Sensor::_updateFrequency |
|
protected |
The documentation for this class was generated from the following files: