#include <co2.h>
List of all members.
Detailed Description
Definition at line 42 of file co2.h.
Constructor & Destructor Documentation
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.
Default destructor.
- Returns:
- void
Definition at line 57 of file co2.cpp.
Member Function Documentation
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.
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
< CO2 sensor description
ROS subscriber for CO2 sources
Definition at line 84 of file co2.h.
Definition at line 88 of file co2.h.
The currently existent sources.
Definition at line 87 of file co2.h.
The documentation for this class was generated from the following files: