A class that provides sensor abstraction. More...
#include <sensor_base.h>
Public Member Functions | |
std::string | getFrameId (void) const |
Getter function for returning the sensor frame id. | |
geometry_msgs::Pose2D | getSensorPose (void) const |
Getter function for returning the sensor pose relatively to robot. | |
virtual void | updateSensorCallback (void)=0 |
Virtual function for sensor value callback. Implement this function on derived class to publish sensor measurements. | |
virtual | ~Sensor (void) |
Default destructor. | |
Protected Member Functions | |
void | checkAndUpdateSensor (const ros::TimerEvent &ev) |
Checks if transform is available and calls updateSensorCallback() | |
Sensor (const nav_msgs::OccupancyGrid &map, const std::string &name, ros::NodeHandle &n, const geometry_msgs::Pose2D &sensorPose, const std::string &sensorFrameId, float updateFrequency) | |
Default constructor. | |
void | updateTransform (const ros::TimerEvent &ev) |
Function for updating the sensor tf transform. | |
Protected Attributes | |
bool | _gotTransform |
const nav_msgs::OccupancyGrid & | _map |
Sensor pose relative to robot. | |
const std::string & | _namespace |
< The base for the sensor frame_id | |
ros::Publisher | _publisher |
ROS tf listener. | |
const std::string | _sensorFrameId |
A ROS timer for updating the sensor values. | |
const geometry_msgs::Pose2D | _sensorPose |
Update frequency of _timer. | |
tf::StampedTransform | _sensorTransform |
True if sensor got the _sensorTransform. | |
tf::TransformListener | _tfListener |
ROS transform from sensor to map. | |
ros::Timer | _tfTimer |
ROS publisher for posting the sensor measurements. | |
ros::Timer | _timer |
A ROS timer for updating the sensor tf. | |
const float | _updateFrequency |
Sensor frame id. |
A class that provides sensor abstraction.
Definition at line 40 of file sensor_base.h.
virtual stdr_robot::Sensor::~Sensor | ( | void | ) | [inline, virtual] |
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.
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 |
Definition at line 36 of file sensor_base.cpp.
void stdr_robot::Sensor::checkAndUpdateSensor | ( | const ros::TimerEvent & | ev | ) | [protected] |
Checks if transform is available and calls updateSensorCallback()
ev | [const ros::TimerEvent&] A ROS timer event |
< wait for transform
Definition at line 63 of file sensor_base.cpp.
std::string stdr_robot::Sensor::getFrameId | ( | void | ) | const [inline] |
Getter function for returning the sensor frame id.
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.
Definition at line 55 of file sensor_base.h.
virtual void stdr_robot::Sensor::updateSensorCallback | ( | void | ) | [pure virtual] |
Virtual function for sensor value callback. Implement this function on derived class to publish sensor measurements.
Implemented in stdr_robot::CO2Sensor, stdr_robot::SoundSensor, stdr_robot::ThermalSensor, stdr_robot::RfidReader, stdr_robot::Laser, and stdr_robot::Sonar.
void stdr_robot::Sensor::updateTransform | ( | const ros::TimerEvent & | ev | ) | [protected] |
Function for updating the sensor tf transform.
Updates the sensor tf transform.
ev | [const ros::TimerEvent&] A ROS timer event |
Definition at line 76 of file sensor_base.cpp.
bool stdr_robot::Sensor::_gotTransform [protected] |
Definition at line 138 of file sensor_base.h.
const nav_msgs::OccupancyGrid& stdr_robot::Sensor::_map [protected] |
Sensor pose relative to robot.
Definition at line 118 of file sensor_base.h.
const std::string& stdr_robot::Sensor::_namespace [protected] |
< The base for the sensor frame_id
The environment occupancy grid map
Definition at line 115 of file sensor_base.h.
ros::Publisher stdr_robot::Sensor::_publisher [protected] |
ROS tf listener.
Definition at line 132 of file sensor_base.h.
const std::string stdr_robot::Sensor::_sensorFrameId [protected] |
A ROS timer for updating the sensor values.
Definition at line 125 of file sensor_base.h.
const geometry_msgs::Pose2D stdr_robot::Sensor::_sensorPose [protected] |
Update frequency of _timer.
Definition at line 120 of file sensor_base.h.
True if sensor got the _sensorTransform.
Definition at line 137 of file sensor_base.h.
tf::TransformListener stdr_robot::Sensor::_tfListener [protected] |
ROS transform from sensor to map.
Definition at line 134 of file sensor_base.h.
ros::Timer stdr_robot::Sensor::_tfTimer [protected] |
ROS publisher for posting the sensor measurements.
Definition at line 130 of file sensor_base.h.
ros::Timer stdr_robot::Sensor::_timer [protected] |
A ROS timer for updating the sensor tf.
Definition at line 127 of file sensor_base.h.
const float stdr_robot::Sensor::_updateFrequency [protected] |
Sensor frame id.
Definition at line 122 of file sensor_base.h.