#include <thermal.h>
Definition at line 42 of file thermal.h.
stdr_robot::ThermalSensor::ThermalSensor |
( |
const nav_msgs::OccupancyGrid & |
map, |
|
|
const stdr_msgs::ThermalSensorMsg & |
msg, |
|
|
const std::string & |
name, |
|
|
ros::NodeHandle & |
n |
|
) |
| |
Default constructor.
- Parameters
-
map | [const nav_msgs::OccupancyGrid&] An occupancy grid map |
msg | [const stdr_msgs::ThermalSensorMsg&] The thermal 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 29 of file thermal.cpp.
stdr_robot::ThermalSensor::~ThermalSensor |
( |
void |
| ) |
|
Default destructor.
- Returns
- void
Definition at line 52 of file thermal.cpp.
void stdr_robot::ThermalSensor::receiveThermalSources |
( |
const stdr_msgs::ThermalSourceVector & |
msg | ) |
|
Receives the existent sound sources.
Receives the existent sources.
- Parameters
-
msg | [const stdr_msgs::ThermalSourceVector&] The thermal sources message |
- Returns
- void
Definition at line 118 of file thermal.cpp.
void stdr_robot::ThermalSensor::updateSensorCallback |
( |
void |
| ) |
|
|
virtual |
Updates the sensor measurements.
- Returns
- void
< Must implement the functionality
< Check for max distance
Implements stdr_robot::Sensor.
Definition at line 61 of file thermal.cpp.
stdr_msgs::ThermalSensorMsg stdr_robot::ThermalSensor::_description |
|
private |
< thermal sensor description
ROS subscriber for sound sources
Definition at line 82 of file thermal.h.
stdr_msgs::ThermalSourceVector stdr_robot::ThermalSensor::thermal_sources_ |
|
private |
The currently existent sources.
Definition at line 85 of file thermal.h.
The documentation for this class was generated from the following files: