Public Member Functions | Private Attributes | List of all members
stdr_robot::CO2Sensor Class Reference

#include <co2.h>

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

Public Member Functions

 CO2Sensor (const nav_msgs::OccupancyGrid &map, const stdr_msgs::CO2SensorMsg &msg, const std::string &name, ros::NodeHandle &n)
 Default constructor. More...
 
void receiveCO2Sources (const stdr_msgs::CO2SourceVector &msg)
 Receives the existent co2 sources. More...
 
virtual void updateSensorCallback ()
 Updates the sensor measurements. More...
 
 ~CO2Sensor (void)
 Default destructor. More...
 
- Public Member Functions inherited from stdr_robot::Sensor
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 ~Sensor (void)
 Default destructor. More...
 

Private Attributes

stdr_msgs::CO2SensorMsg _description
 < CO2 sensor description More...
 
stdr_msgs::CO2SourceVector co2_sources_
 
ros::Subscriber co2_sources_subscriber_
 The currently existent sources. More...
 

Additional Inherited Members

- Protected Member Functions inherited from stdr_robot::Sensor
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 inherited from stdr_robot::Sensor
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

Definition at line 42 of file co2.h.

Constructor & Destructor Documentation

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

Default constructor.

Parameters
map[const nav_msgs::OccupancyGrid&] An occupancy grid map
msg[const stdr_msgs::CO2SensorMsg&] The CO2 sensor \ description message
name[const std::string&] The sensor frame id without the base
n[ros::NodeHandle&] The ROS node handle
Returns
void
Parameters
map[const nav_msgs::OccupancyGrid&] An occupancy grid map
msg[const stdr_msgs::CO2SensorMsg&] The sensor 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 co2.cpp.

stdr_robot::CO2Sensor::~CO2Sensor ( void  )

Default destructor.

Returns
void

Definition at line 57 of file co2.cpp.

Member Function Documentation

void stdr_robot::CO2Sensor::receiveCO2Sources ( const stdr_msgs::CO2SourceVector &  msg)

Receives the existent co2 sources.

Receives the existent sources.

Parameters
msg[const stdr_msgs::CO2SourceVector&] The CO2 sources message
Returns
void

Definition at line 108 of file co2.cpp.

void stdr_robot::CO2Sensor::updateSensorCallback ( void  )
virtual

Updates the sensor measurements.

Returns
void

!< Must implement the functionality

< Calculate distance

Implements stdr_robot::Sensor.

Definition at line 66 of file co2.cpp.

Member Data Documentation

stdr_msgs::CO2SensorMsg stdr_robot::CO2Sensor::_description
private

< CO2 sensor description

ROS subscriber for CO2 sources

Definition at line 82 of file co2.h.

stdr_msgs::CO2SourceVector stdr_robot::CO2Sensor::co2_sources_
private

Definition at line 88 of file co2.h.

ros::Subscriber stdr_robot::CO2Sensor::co2_sources_subscriber_
private

The currently existent sources.

Definition at line 85 of file co2.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