GAMS  1.2.2
Sensor.h
Go to the documentation of this file.
1 
54 #ifndef _GAMS_VARIABLES_SENSOR_H_
55 #define _GAMS_VARIABLES_SENSOR_H_
56 
57 #include <vector>
58 #include <map>
59 #include <string>
60 
61 #include "gams/GamsExport.h"
62 #include "madara/knowledge/containers/Double.h"
63 #include "madara/knowledge/containers/Map.h"
64 #include "madara/knowledge/KnowledgeBase.h"
65 
66 #include "gams/pose/SearchArea.h"
67 #include "gams/pose/GPSFrame.h"
69 
70 #include <set>
71 using std::set;
72 
73 namespace gams
74 {
75  namespace variables
76  {
81  {
82  public:
86  Sensor ();
87 
91  Sensor (const std::string & name,
92  madara::knowledge::KnowledgeBase * knowledge,
93  const double & range = 0.0,
94  const pose::Position & origin = pose::Position (pose::gps_frame(), DBL_MAX, DBL_MAX));
95 
99  ~Sensor ();
100 
105  void operator= (const Sensor & rhs);
106 
112  set<pose::Position> discretize (
113  const pose::Region & region);
114 
120  set<pose::Position> discretize (
121  const pose::SearchArea & area);
122 
127  double get_discretization () const;
128 
134  pose::Position get_gps_from_index (
135  const pose::Position & index);
136 
142  pose::Position get_index_from_gps (
143  const pose::Position & pos);
144 
149  std::string get_name () const;
150 
155  pose::Position get_origin();
156 
161  double get_range () const;
162 
168  double get_value (const pose::Position& pos);
169 
174  void set_origin (const pose::Position& origin);
175 
180  void set_range (const double& range);
181 
188  void set_value (const pose::Position& pos, const double& val,
189  const madara::knowledge::KnowledgeUpdateSettings& settings =
190  madara::knowledge::KnowledgeUpdateSettings());
198  void init_vars (const std::string & name,
199  madara::knowledge::KnowledgeBase* knowledge,
200  const double & range = 0.0,
201  const pose::Position & origin = pose::Position (pose::gps_frame(), DBL_MAX, DBL_MAX));
202 
203  protected:
209  std::string index_pos_to_index (const pose::Position& pos) const;
210 
211  void regenerate_local_frame (void);
212 
216  void init_vars ();
217 
219  madara::knowledge::containers::Map value_;
220 
222  madara::knowledge::KnowledgeBase* knowledge_;
223 
225  madara::knowledge::containers::Double range_;
226 
228  std::string name_;
229 
231  madara::knowledge::containers::NativeDoubleArray origin_;
232 
235  };
236 
238  typedef std::map <std::string, Sensor*> Sensors;
239 
241  typedef std::vector <std::string> SensorNames;
242  }
243 }
244 
245 #endif // _GAMS_VARIABLES_SENSOR_H_
madara::knowledge::containers::NativeDoubleArray origin_
origin for index calculations
Definition: Sensor.h:231
madara::knowledge::containers::Map value_
the map of locations to sensor value
Definition: Sensor.h:219
A container for sensor information.
Definition: Sensor.h:80
std::map< std::string, Sensor * > Sensors
a map of sensor names to the sensor information
Definition: Sensor.h:238
A utility class for search areas.
Definition: SearchArea.h:71
std::string name_
name of the sensor
Definition: Sensor.h:228
madara::knowledge::containers::Double range_
the range of the sensor, determines discretization
Definition: Sensor.h:225
GAMS_EXPORT void init_vars(AccentStatuses &variables, madara::knowledge::KnowledgeBase &knowledge, const std::string &prefix)
Initializes accent status containers.
Contains all GAMS-related tools, classes and code.
madara::knowledge::KnowledgeBase * knowledge_
knowledge base
Definition: Sensor.h:222
#define GAMS_EXPORT
Definition: GamsExport.h:20
pose::ReferenceFrame local_frame_
local cartesian frame
Definition: Sensor.h:234
std::vector< std::string > SensorNames
a list of sensor names
Definition: Sensor.h:241
Provides Reference Frame (i.e., coordinate systemm) transforms.
A helper class for region information.
Definition: Region.h:78
GAMS_EXPORT const ReferenceFrame & gps_frame(void)
Returns the canonical GPS frame representing Earth.