| 
    MRXT: The Multi-Robot eXploration Tool
   
    
   Multi-Robot autonomous exploration and mapping simulator. 
   | 
  
  
  
 
Implements a particle in a rao-blackwellized particle filter for visual slam. More...
#include <particle.h>
Public Member Functions | |
| particle () | |
| Default Constructor.  | |
| particle (int nRobots, float w, float h, float res, float x, float y, int gmtype, int vmtype, int nmarks, const ConfigFile &conf) | |
| Constructor.  | |
| particle (const particle &) | |
| Copy Constructor.  | |
| virtual | ~particle () | 
| Default Destructor.  | |
| const point & | getCell (int robot) | 
| returns the cell where the robot is located  | |
| point * | getDataCell () | 
| returns a pointer to the data array of cells  | |
| pose * | getDataPos () | 
| returns a pointer to the data array of poses  | |
| binMap & | getImprecisePoseMap () | 
| returns a binary map of past poses with high dispersion  | |
| int | getNumRobots () | 
| returns the number of robots  | |
| gridMapInterface & | getOMap () | 
| returns the occupancy grid map  | |
| const pose & | getPos (int robot) | 
| returns the pose of the robot  | |
| binMap & | getPrecisePoseMap () | 
| returns a binary map of past poses with low dispersion  | |
| double | getSumLogWeight () | 
| returns the weight of the particle  | |
| visualMap & | getVMap () | 
| returns the visual map of landmarks  | |
| double | getWeight () | 
| returns the weight of the particle  | |
| void | initialize (int nRobots, float w, float h, float res, float x, float y, int gmtype, int vmtype, int nmarks, const ConfigFile &conf) | 
| initialization  | |
| particle & | operator= (const particle &) | 
| void | releaseVMap () | 
| void | setCell (const point &point, int robot) | 
| sets the cell where the robot is located  | |
| void | setPos (const pose &pos, int robot) | 
| sets the pose of a robot  | |
| void | setSumLogWeight (double w) | 
| sets the weight of the particle  | |
| void | setWeight (double w) | 
| sets the weight of the particle  | |
Private Attributes | |
| unsigned short | height | 
| binMap * | imprecisePoseMap | 
| int | nrobots | 
| gridMapInterface * | oMap | 
| binMap * | precisePoseMap | 
| point * | rcell | 
| float | realHeight | 
| float | realWidth | 
| float | resolution | 
| pose * | rpos | 
| double | sumLogWeight | 
| visualMap * | vMap | 
| double | weight | 
| unsigned short | width | 
| float | xorigin | 
| float | yorigin | 
Implements a particle in a rao-blackwellized particle filter for visual slam.
Definition at line 24 of file particle.h.
 1.7.6.1