#include <thermal.h>
Public Member Functions | |
void | receiveThermalSources (const stdr_msgs::ThermalSourceVector &msg) |
Receives the existent sound sources. | |
ThermalSensor (const nav_msgs::OccupancyGrid &map, const stdr_msgs::ThermalSensorMsg &msg, const std::string &name, ros::NodeHandle &n) | |
Default constructor. | |
virtual void | updateSensorCallback () |
Updates the sensor measurements. | |
~ThermalSensor (void) | |
Default destructor. | |
Private Attributes | |
stdr_msgs::ThermalSensorMsg | _description |
< thermal sensor description | |
stdr_msgs::ThermalSourceVector | thermal_sources_ |
ros::Subscriber | thermal_sources_subscriber_ |
The currently existent sources. |
stdr_robot::ThermalSensor::ThermalSensor | ( | const nav_msgs::OccupancyGrid & | map, |
const stdr_msgs::ThermalSensorMsg & | msg, | ||
const std::string & | name, | ||
ros::NodeHandle & | n | ||
) |
Default constructor.
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 |
Definition at line 29 of file thermal.cpp.
void stdr_robot::ThermalSensor::receiveThermalSources | ( | const stdr_msgs::ThermalSourceVector & | msg | ) |
Receives the existent sound sources.
Receives the existent sources.
msg | [const stdr_msgs::ThermalSourceVector&] The thermal sources message |
Definition at line 118 of file thermal.cpp.
void stdr_robot::ThermalSensor::updateSensorCallback | ( | void | ) | [virtual] |
Updates the sensor measurements.
< 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] |
stdr_msgs::ThermalSourceVector stdr_robot::ThermalSensor::thermal_sources_ [private] |