Go to the documentation of this file.00001
00018 #ifndef TRACKER_H
00019 #define TRACKER_H
00020
00021
00022 #define DIEonERR(value) if (value<0) { \
00023 fprintf(stderr,"%i DIED in %s line %i with error %i\n",getpid(),__FILE__,__LINE__,-value);exit(1); }
00024
00025
00026 #include <string>
00027
00028
00029 #include "ros/ros.h"
00030 #include <geometry_msgs/Pose.h>
00031 #include <tf/transform_broadcaster.h>
00032 #include <asr_msgs/AsrObject.h>
00033
00034 #include "transform_coords.h"
00035
00036 typedef enum{rightTracker=1, leftTracker}trackerID;
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051 class tracker_impl{
00052 public:
00053 tracker_impl(trackerID t, BirdTrack_impl* b, std::string trackerName);
00054 ~tracker_impl();
00055
00056 void start();
00057 void stop();
00058
00059 bool loadCalibFile(const char *srcFileName);
00060
00061
00062 private:
00063 trackerID myID;
00064 BirdTrack_impl* myBird;
00065 transformCoords* myTransformer;
00066 unsigned int seqId;
00067
00068 struct fulcrum{
00069 double sensorVal[3];
00070 double sensorAngle[3];
00071 double worldVal[3];
00072 double worldAngle[3];
00073 };
00074
00076 void workerThread();
00078 bool threadRunning;
00079 bool writeNotification(trackerID id, double* raw, double *calibrated);
00080
00082 pthread_t workerThreadHandle;
00084 static void *s_workerThread(void* arg);
00085
00086 void printFulcrum(fulcrum fulc);
00087
00088 bool loadCalibration(const fulcrum cal[255], unsigned int length);
00089
00090 void getPbdObject(std::string name, double *data, asr_msgs::AsrObject &object);
00091 void getTransform(double *data, tf::Transform &transform);
00092
00093 tf::TransformBroadcaster transformPublisher;
00094 ros::NodeHandle node;
00095 ros::Publisher generalPublisher;
00096 };
00097
00098 #endif
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 Sat Jun 8 2019 19:36:21