kogmo_fob/trackerServer/tracker_impl.h
Go to the documentation of this file.
1 
18 #ifndef TRACKER_H
19 #define TRACKER_H
20 
21 //MACROS
22 #define DIEonERR(value) if (value<0) { \
23  fprintf(stderr,"%i DIED in %s line %i with error %i\n",getpid(),__FILE__,__LINE__,-value);exit(1); }
24 
25 /* system includes */
26 #include <string>
27 
28 /* my includes */
29 #include "transformCoords.h"
30 //KOGMO_RTDB standard includes
31 #define KOGMO_RTDB_DONT_INCLUDE_ALL_OBJECTS
32 #include "kogmo_rtdb.h"
33 #include "kogmo_rtdb_obj_typeids.h"
34 //KOGMO_RTDB special includes for our project with the id E1
35 #include "itec/kogmo_rtdb_obj_e1_itec.h"
36 using namespace KogniMobil;
37 
38 
40 
41 //for reference purposes: the old data structure
42 /*
43  // Definition of a calibration data set
44  struct fulcrum{
45  double sensorVal[3];
46  double sensorAngle[3];
47  double worldVal[3];
48  double worldAngle[3];
49  };
50  //typedef sequence<fulcrum> oneSensorCal;
51  typedef sequence<fulcrum> allSensorCal;
52 */
53 
54 class tracker_impl{
55  public:
56  tracker_impl(trackerID t, BirdTrack_impl* b, std::string trackerName);
57  ~tracker_impl();
58 
59  void start();
60  void stop();
61 
62  bool loadCalibFile(const char *srcFileName);
63 
64 
65 private:
66  trackerID myID;
67  BirdTrack_impl* myBird;
68  transformCoords* myTransformer;
69  struct fulcrum{
70  double sensorVal[3];
71  double sensorAngle[3];
72  double worldVal[3];
73  double worldAngle[3];
74  };
75  /* variables that handle the database connection */
76  kogmo_rtdb_handle_t *dbc; /*< the database connection handle */
77  kogmo_rtdb_connect_info_t dbinfo; /*< information about the database connection */
78 
79  kogmo_rtdb_obj_info_t dataobj_info_data; /*< information about the type of the dataobject, for calibrated data */
80  kogmo_rtdb_obj_info_t dataobj_info_raw; /*< information about the type of the dataobject, for raw data */
81 
82  kogmo_rtdb_obj_e1_fobtracker_t *dataobj_data; /*< the dataobject specific to the sensor */
83  kogmo_rtdb_obj_e1_fobtracker_t *dataobj_raw; /*< the dataobject specific to the sensor */
84 
85  kogmo_rtdb_objid_t oid; /*< some id */
86  kogmo_rtdb_objid_t pid; /*< another id */
87 
89  void workerThread();
91  bool threadRunning;
92  bool writeNotification(kogmo_rtdb_obj_info_t &dataobj_info, double*);
93 
95  pthread_t workerThreadHandle;
97  static void *s_workerThread(void* arg);
98 
99  void printFulcrum(fulcrum fulc);
100 
101  bool loadCalibration(const fulcrum cal[255], unsigned int length);
102 
103 };
104 
105 #endif /* TRACKER_H */
kogmo_rtdb_obj_info_t dataobj_info_data
kogmo_rtdb_obj_info_t dataobj_info_raw
kogmo_rtdb_obj_e1_fobtracker_t * dataobj_data
kogmo_rtdb_connect_info_t dbinfo
kogmo_rtdb_obj_e1_fobtracker_t * dataobj_raw


asr_flock_of_birds
Author(s): Bernhardt Andre, Engelmann Stephan, Giesler Björn, Heller Florian, Jäkel Rainer, Nguyen Trung, Pardowitz Michael, Weckesser Peter, Yi Xie, Zöllner Raoul
autogenerated on Mon Jun 10 2019 12:44:40