Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
stdr_robot::Sensor Class Referenceabstract

A class that provides sensor abstraction. More...

#include <sensor_base.h>

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

Public Member Functions

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...
 

Protected Member Functions

void checkAndUpdateSensor (const ros::TimerEvent &ev)
 Checks if transform is available and calls updateSensorCallback() More...
 
 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. More...
 
void updateTransform (const ros::TimerEvent &ev)
 Function for updating the sensor tf transform. More...
 

Protected Attributes

bool _gotTransform
 
const nav_msgs::OccupancyGrid & _map
 Sensor pose relative to robot. More...
 
const std::string & _namespace
 < The base for the sensor frame_id More...
 
ros::Publisher _publisher
 ROS tf listener. More...
 
const std::string _sensorFrameId
 A ROS timer for updating the sensor values. More...
 
const geometry_msgs::Pose2D _sensorPose
 Update frequency of _timer. More...
 
tf::StampedTransform _sensorTransform
 True if sensor got the _sensorTransform. More...
 
tf::TransformListener _tfListener
 ROS transform from sensor to map. More...
 
ros::Timer _tfTimer
 ROS publisher for posting the sensor measurements. More...
 
ros::Timer _timer
 A ROS timer for updating the sensor tf. More...
 
const float _updateFrequency
 Sensor frame id. More...
 

Detailed Description

A class that provides sensor abstraction.

Definition at line 40 of file sensor_base.h.

Constructor & Destructor Documentation

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.

Member Function Documentation

void stdr_robot::Sensor::checkAndUpdateSensor ( const ros::TimerEvent ev)
protected

Checks if transform is available and calls updateSensorCallback()

Parameters
ev[const ros::TimerEvent&] A ROS timer event
Returns
void

< 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.

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

Virtual function for sensor value callback. Implement this function on derived class to publish sensor measurements.

Returns
void

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.

Parameters
ev[const ros::TimerEvent&] A ROS timer event
Returns
void
void

Definition at line 76 of file sensor_base.cpp.

Member Data Documentation

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 116 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 114 of file sensor_base.h.

ros::Publisher stdr_robot::Sensor::_publisher
protected

ROS tf listener.

Definition at line 131 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

Update frequency of _timer.

Definition at line 119 of file sensor_base.h.

tf::StampedTransform stdr_robot::Sensor::_sensorTransform
protected

True if sensor got the _sensorTransform.

Definition at line 135 of file sensor_base.h.

tf::TransformListener stdr_robot::Sensor::_tfListener
protected

ROS transform from sensor to map.

Definition at line 133 of file sensor_base.h.

ros::Timer stdr_robot::Sensor::_tfTimer
protected

ROS publisher for posting the sensor measurements.

Definition at line 128 of file sensor_base.h.

ros::Timer stdr_robot::Sensor::_timer
protected

A ROS timer for updating the sensor tf.

Definition at line 126 of file sensor_base.h.

const float stdr_robot::Sensor::_updateFrequency
protected

Sensor frame id.

Definition at line 121 of file sensor_base.h.


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


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Mon Jun 10 2019 15:15:10