MRXT: The Multi-Robot eXploration Tool
Multi-Robot autonomous exploration and mapping simulator.
include/architecture/slam/slamInterface.h
00001 /*
00002 *
00003 * Author: Miguel Julia <mjulia@umh.es> 
00004 * 
00005 * Date:   2008
00006 * 
00007 * Class slam
00008 *
00009 
00010 *
00011 */
00012 
00013 #pragma once
00014 #ifndef __SLAM__INTERFACE__
00015 #define __SLAM__INTERFACE__
00016 
00017 #include "gridMapInterface.h"
00018 #include "visualMap.h"
00019 #include "stepEvent.h"
00020 #include "ConfigFile.h"
00021 #include <iostream>
00022 #include <stdlib.h>
00023 #include <loki/Factory.h>
00024 #include <loki/Typelist.h>
00025 #include <loki/Functor.h>
00026 #include "ClThread.h"
00027 #include "robotBase.h"
00028 #include "worldModelInterface.h"
00029 #include <QObject>
00030 #include <QPixmap>
00031 
00032 /**
00033 * @brief Interface for landmark-based visual SLAM algorithms
00034 *
00035 */
00036 class slamInterface: public QObject, public ClThread, public stepEventManager{
00037 
00038 ///////////////////////////////////////////////////////////////////////
00039 //-------------------------  Methods  --------------------------------
00040 ///////////////////////////////////////////////////////////////////////
00041 
00042 public:
00043         
00044         virtual ~slamInterface(){};
00045         
00046         ///initializer  
00047         virtual void initialize(int nrobots, ConfigFile& configfile)=0;
00048         
00049         /// sets the pointer to a robot base object
00050         virtual void setRobotBase(int robot, robotBase& rbase)=0;
00051         /// sets the world model
00052         virtual void setWorldModel(worldModelInterface& scene)=0;
00053 
00054         /// return the number of robots
00055         virtual int getNumRobots() const=0;
00056         /// returns the width of the map
00057         virtual float getWidth() const=0;
00058         /// return the height of the map
00059         virtual float getHeight() const=0;
00060         /// return the x position of the origin of grid map in real coordinates
00061         virtual float getXOrigin() const=0;
00062         /// return the y position of the origin of grid map in real coordinates
00063         virtual float getYOrigin() const=0;
00064         /// returns the resolution of the gridmap
00065         virtual float getResolution() const=0;
00066         /// returns the width in cells of the grid map
00067         virtual int getGMWidth() const=0;
00068         /// returns the height in cells of the grid map
00069         virtual int getGMHeight() const=0;
00070 
00071         /// sets the high uncertainty threshold for the localization state 
00072         virtual void setHighThreshold(float thb)=0;
00073         /// sets the low uncertainty threshold for the localization state 
00074         virtual void setLowThreshold(float tha)=0;
00075         
00076         /// returns a copy of the current occupancy map
00077         virtual gridMapInterface* getOMap()=0;
00078         /// returns a copy of the current visual map
00079         virtual visualMap* getVMap()=0;
00080         /// return a copy of the current precise pose map
00081         virtual binMap* getPreMap()=0;
00082         /// returns a copy of the current imprecise pose map
00083         virtual binMap* getImpMap()=0;
00084 
00085         /// returns the current pose of the robot
00086         virtual pose getPos(int robot)=0;
00087         /// returns the current cell of the robot
00088         virtual point getCell(int robot)=0;
00089         /// returns the matrix that represents the covariance of the position of the robot
00090         virtual matrix getCovariance(int robot) const=0;
00091         /// returns the matrix that represents the covariance of robots and marks
00092         virtual Ematrix getGlobalCovariance() const = 0 ;
00093         /// returns a measure of the dispersion of the robot
00094         virtual float getDisp(int robot) const=0;
00095         /// return the current state of localization of the robot
00096         virtual bool getLoc(int robot) const=0;
00097 
00098         /// returns the current simulation time
00099         virtual float getTime() const =0;
00100         /// returns the period of the simulation time step
00101         virtual float getSampleTime() const =0;
00102 
00103         /// sets the name of the log file
00104         virtual void setLogName(const char*)=0;
00105         /// sets the name of the gridmap file   
00106         virtual void setGridMapName(const char*)=0;
00107 
00108         virtual void setWindowName(const char*)=0;
00109 
00110         virtual void disableRobotBase(int r)=0;
00111 
00112         virtual QPixmap* getPixmap()=0;
00113         virtual QImage* getQImage()=0;
00114 
00115 
00116 //--------------------------------------------------------------------- 
00117 ///////////////////////////////////////////////////////////////////////
00118 };
00119 
00120 /// create object function format
00121 typedef Loki::Functor<slamInterface*, LOKI_TYPELIST_2(int,ConfigFile&)> slamCreator;
00122 /// Factory
00123 typedef Loki::SingletonHolder< Loki::Factory< slamInterface, int, LOKI_TYPELIST_2(int,ConfigFile&)> > slamFactory;
00124 
00125 #endif
 All Classes Functions Variables Typedefs