#include <microphone.h>
Public Member Functions | |
void | receiveSoundSources (const stdr_msgs::SoundSourceVector &msg) |
Receives the existent sound sources. More... | |
SoundSensor (const nav_msgs::OccupancyGrid &map, const stdr_msgs::SoundSensorMsg &msg, const std::string &name, ros::NodeHandle &n) | |
Default constructor. More... | |
virtual void | updateSensorCallback () |
Updates the sensor measurements. More... | |
~SoundSensor (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::SoundSensorMsg | _description |
< sound sensor description More... | |
stdr_msgs::SoundSourceVector | sound_sources_ |
ros::Subscriber | sound_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... | |
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.
stdr_robot::SoundSensor::~SoundSensor | ( | void | ) |
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.
|
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.
|
private |
< sound sensor description
ROS subscriber for sound sources
Definition at line 82 of file microphone.h.
|
private |
Definition at line 88 of file microphone.h.
|
private |
The currently existent sources.
Definition at line 85 of file microphone.h.