Particle plume C++ class. More...
#include <ParticlePlume.h>
Classes | |
struct | BubbleData |
Data coming from the nose topic is stored in this form on a buffer. More... | |
struct | CellCandidate |
Auxiliary data structure. More... | |
Public Member Functions | |
ParticlePlume () | |
Constructor. | |
void | publishPlume () |
Publish plume. | |
~ParticlePlume () | |
Destructor. | |
Private Member Functions | |
float | drand () |
Uniform distribution. | |
void | noseCallback (const boost::shared_ptr< const lse_sensor_msgs::Nostril > &msg) |
Nose topic callback. | |
double | randomNormal () |
Normal distribution. | |
Private Attributes | |
double | bubble_radius_ |
Bubble radius. | |
double | cell_size_ |
Cell size. | |
nav_msgs::GridCells | cells_ |
Data structure that holds the visited cells. | |
std::vector< ros::Time > | cells_birth_ |
Data structure to hold the birth time of the visited cells. | |
bool | cells_changed_ |
Flag for wether the cells_ data structure was changed or not. | |
ros::Publisher | cells_pub_ |
Visited cells topic publisher. | |
std::string | global_frame_id_ |
Global frame_id. | |
int | max_particles_per_bubble_ |
Maximum number of points per bubble. | |
ros::NodeHandle | n_ |
Node handler. | |
message_filters::Subscriber < lse_sensor_msgs::Nostril > | nose_sub_ |
Nose topic subscriber. | |
std::vector< BubbleData > | odor_readings_ |
Buffer for holding pre-processed incoming chemical readings. | |
int | particle_life_time_ |
Particle life time. | |
pcl::PointCloud< Particle > | plume_ |
Particle plume data structure. | |
pcl_ros::Publisher< Particle > | plume_pub_ |
Particle plume topic publisher. | |
ros::NodeHandle | pn_ |
Private node handler. | |
double | publish_frequency_ |
Publish frequency. | |
std::string | sensor_model_ |
Sensor Model. | |
tf::TransformListener | tf_ |
Transform listener. | |
tf::MessageFilter < lse_sensor_msgs::Nostril > * | tf_filter_ |
Particle plume C++ class.
This class receives data from electronic noses converting the chemical concentration data into a virtual plume. This virtual plume is represented by a 3D cloud of particles where a higher concentration of particles indicates a higher chemical concentration. Each chemical reading is converted into a small cloud of particles centered around the reading point over a normal distribution with a standard deviation of 1. Chemical data can be gathered from multiple sources, various sensors on a robot, various robots, stationary sensor network nodes, etc.
Definition at line 58 of file ParticlePlume.h.
Constructor.
Definition at line 42 of file ParticlePlume.cpp.
Destructor.
Definition at line 71 of file ParticlePlume.cpp.
float particle_plume::ParticlePlume::drand | ( | ) | [private] |
Uniform distribution.
Uniform distribution, [0 ... 1]
Definition at line 321 of file ParticlePlume.cpp.
void particle_plume::ParticlePlume::noseCallback | ( | const boost::shared_ptr< const lse_sensor_msgs::Nostril > & | msg | ) | [private] |
Nose topic callback.
This function receives messages from the nose topic.
msg | Incoming lse_sensor_msgs::Nostri msg. |
Definition at line 76 of file ParticlePlume.cpp.
Publish plume.
This function publishes the particle plume.
Definition at line 162 of file ParticlePlume.cpp.
double particle_plume::ParticlePlume::randomNormal | ( | ) | [private] |
Normal distribution.
Normal distribution, centered on 0, std dev 1.
Definition at line 326 of file ParticlePlume.cpp.
double particle_plume::ParticlePlume::bubble_radius_ [private] |
Bubble radius.
The bubble radius determines the sphere inside which points will be generated for each chemical reading.
Definition at line 128 of file ParticlePlume.h.
double particle_plume::ParticlePlume::cell_size_ [private] |
Cell size.
The height and width for each visited cell.
Definition at line 148 of file ParticlePlume.h.
nav_msgs::GridCells particle_plume::ParticlePlume::cells_ [private] |
Data structure that holds the visited cells.
Definition at line 110 of file ParticlePlume.h.
std::vector<ros::Time> particle_plume::ParticlePlume::cells_birth_ [private] |
Data structure to hold the birth time of the visited cells.
Definition at line 113 of file ParticlePlume.h.
bool particle_plume::ParticlePlume::cells_changed_ [private] |
Flag for wether the cells_ data structure was changed or not.
Definition at line 116 of file ParticlePlume.h.
Visited cells topic publisher.
Definition at line 98 of file ParticlePlume.h.
std::string particle_plume::ParticlePlume::global_frame_id_ [private] |
Global frame_id.
Definition at line 122 of file ParticlePlume.h.
int particle_plume::ParticlePlume::max_particles_per_bubble_ [private] |
Maximum number of points per bubble.
This value determines the number of points generated inside a sphere for a maximum chemical reading.
Definition at line 133 of file ParticlePlume.h.
Node handler.
Definition at line 91 of file ParticlePlume.h.
message_filters::Subscriber<lse_sensor_msgs::Nostril> particle_plume::ParticlePlume::nose_sub_ [private] |
Nose topic subscriber.
Definition at line 101 of file ParticlePlume.h.
std::vector<BubbleData> particle_plume::ParticlePlume::odor_readings_ [private] |
Buffer for holding pre-processed incoming chemical readings.
Definition at line 119 of file ParticlePlume.h.
int particle_plume::ParticlePlume::particle_life_time_ [private] |
Particle life time.
Each particle can have a life time in minutes. Once this time is up the particle is removed from the plume. A value of 0 indicates that the particles are never removed.
Definition at line 138 of file ParticlePlume.h.
pcl::PointCloud<Particle> particle_plume::ParticlePlume::plume_ [private] |
Particle plume data structure.
Definition at line 107 of file ParticlePlume.h.
pcl_ros::Publisher<Particle> particle_plume::ParticlePlume::plume_pub_ [private] |
Particle plume topic publisher.
Definition at line 96 of file ParticlePlume.h.
Private node handler.
Definition at line 93 of file ParticlePlume.h.
double particle_plume::ParticlePlume::publish_frequency_ [private] |
Publish frequency.
The rate at which the particle plume is published in Hz. Plume update occurs every time a chemical reading arrives.
Definition at line 143 of file ParticlePlume.h.
std::string particle_plume::ParticlePlume::sensor_model_ [private] |
Sensor Model.
The sensor model accepted for this plume.
Definition at line 153 of file ParticlePlume.h.
Transform listener.
Definition at line 103 of file ParticlePlume.h.
Definition at line 104 of file ParticlePlume.h.