#include <microphone.h>

Public Member Functions | |
| void | receiveSoundSources (const stdr_msgs::SoundSourceVector &msg) |
| Receives the existent sound sources. | |
| SoundSensor (const nav_msgs::OccupancyGrid &map, const stdr_msgs::SoundSensorMsg &msg, const std::string &name, ros::NodeHandle &n) | |
| Default constructor. | |
| virtual void | updateSensorCallback () |
| Updates the sensor measurements. | |
| ~SoundSensor (void) | |
| Default destructor. | |
Private Attributes | |
| stdr_msgs::SoundSensorMsg | _description |
| < sound sensor description | |
| stdr_msgs::SoundSourceVector | sound_sources_ |
| ros::Subscriber | sound_sources_subscriber_ |
| The currently existent sources. | |
Definition at line 42 of file microphone.h.
| stdr_robot::SoundSensor::SoundSensor | ( | const nav_msgs::OccupancyGrid & | map, |
| const stdr_msgs::SoundSensorMsg & | msg, | ||
| const std::string & | name, | ||
| ros::NodeHandle & | n | ||
| ) |
Default constructor.
| map | [const nav_msgs::OccupancyGrid&] An occupancy grid map |
| msg | [const stdr_msgs::SoundSensorMsg&] The sound sensor \ description message |
| name | [const std::string&] The sensor frame id without the base |
| n | [ros::NodeHandle&] The ROS node handle |
| map | [const nav_msgs::OccupancyGrid&] An occupancy grid map |
| msg | [const stdr_msgs::SoundSensorMsg&] The sensor description message |
| name | [const std::string&] The sensor frame id without the base |
| n | [ros::NodeHandle&] The ROS node handle |
Definition at line 34 of file microphone.cpp.
| void stdr_robot::SoundSensor::receiveSoundSources | ( | const stdr_msgs::SoundSourceVector & | msg | ) |
Receives the existent sound sources.
Receives the existent sources.
| msg | [const stdr_msgs::SoundSourceVector&] The sound sources message |
Definition at line 125 of file microphone.cpp.
| void stdr_robot::SoundSensor::updateSensorCallback | ( | void | ) | [virtual] |
Updates the sensor measurements.
< 0 db for silence
< Must implement the functionality
< Check for max distance
Implements stdr_robot::Sensor.
Definition at line 66 of file microphone.cpp.
stdr_msgs::SoundSensorMsg stdr_robot::SoundSensor::_description [private] |
< sound sensor description
ROS subscriber for sound sources
Definition at line 84 of file microphone.h.
stdr_msgs::SoundSourceVector stdr_robot::SoundSensor::sound_sources_ [private] |
Definition at line 88 of file microphone.h.
The currently existent sources.
Definition at line 87 of file microphone.h.