00001
00018
00019 #include <unistd.h>
00020 #include <stdio.h>
00021 #include <sys/time.h>
00022 #include <sstream>
00023 #include <vector>
00024 #include <algorithm>
00025
00026 #include "bird_track_impl.h"
00027 #include "tracker_impl.h"
00028 #include "transform_coords.h"
00029
00030 #define DOUBLE_VECTOR_LENGTH 6
00031
00032 #define NOTE_KEY_1 "X"
00033 #define NOTE_KEY_2 "Y"
00034 #define NOTE_KEY_3 "Z"
00035 #define NOTE_KEY_4 "RX"
00036 #define NOTE_KEY_5 "RY"
00037 #define NOTE_KEY_6 "RZ"
00038
00039 extern unsigned int debugLevel;
00040 typedef boost::array< ::geometry_msgs::Point_<std::allocator<void> > , 8> BoundingBox;
00041 tracker_impl::tracker_impl(trackerID t, BirdTrack_impl* b, std::string trackerName) : myID(t), myBird(b), seqId(0)
00042 {
00044 threadRunning = false;
00045 myTransformer = new transformCoords();
00046 generalPublisher = node.advertise<asr_msgs::AsrObject>("fob_objects", 1000);
00047 }
00048
00049 tracker_impl::~tracker_impl(){
00050 threadRunning = false;
00051
00052
00053 }
00054
00055
00056 void
00057 *tracker_impl::s_workerThread(void* arg)
00058 {
00059 tracker_impl* myobj = (tracker_impl*)arg;
00060 printf("static WorkerThread method called!\n");
00061
00062 myobj->workerThread();
00063 printf( "Worker thread exit.\n");
00064 return NULL;
00065 }
00066
00067
00068
00069 #define MAX_SETS 1
00070 #define PAUSE_SET 30000
00071 #define PAUSE_WRITE 30000
00072
00073 double getMedian(double (&vAcc)[MAX_SETS][6], unsigned int index){
00074 if (MAX_SETS == 1)
00075 return vAcc[0][index];
00076
00077 std::vector<double> data;
00078 for (unsigned int i=0; i<MAX_SETS; i++)
00079 data.push_back(vAcc[i][index]);
00080 std::sort(data.begin(), data.end());
00081
00082 if (MAX_SETS % 2 == 0)
00083 return ((data[MAX_SETS / 2 - 1] + data[MAX_SETS / 2]) / 2);
00084 else
00085 return data[(MAX_SETS - 1) / 2];
00086 }
00087
00088
00089 void
00090 tracker_impl::workerThread(){
00091
00092 double v[6];
00093 double vAcc[MAX_SETS][6];
00094
00095 while(threadRunning)
00096 {
00098 for (unsigned int i=0; i<MAX_SETS; i++)
00099 {
00101 myBird->get_posangles(myID, vAcc[i]);
00102
00103 if (i+1 < MAX_SETS)
00104 usleep(PAUSE_SET);
00105 }
00106
00107 for (unsigned int i=0; i<6; i++)
00108 {
00109 v[i] = getMedian(vAcc, i);
00110 }
00111
00112
00113 myTransformer->transform(v);
00114
00115
00116 if (!this->writeNotification(myID, vAcc[0], v)){
00117 printf( "Couldn't write Notification to NotificationManager. Error!\n");
00118 exit(-1);
00119 }
00120
00121 if (debugLevel > 0 )
00122 {
00123 if (myID == rightTracker)
00124 printf("\n");
00125 }
00126
00127 usleep(PAUSE_WRITE);
00128 }
00129 threadRunning = false;
00130 }
00131
00132 void
00133 tracker_impl::start(){
00134 printf( "Starting myBird\n");
00135 myBird->start();
00136
00138 if(!threadRunning){
00139 threadRunning = true;
00140 pthread_create(&workerThreadHandle,NULL, &s_workerThread, (void*)this);
00141 }
00142 else
00143 printf( "Thread started, but was already running.\n");
00144 printf( "Thread running.\n");
00145 }
00146
00147 void
00148 tracker_impl::stop(){
00149 printf( "Stopping myBird\n");
00150 myBird->stop();
00151
00153 threadRunning = false;
00154 }
00155
00156
00157 bool
00158 tracker_impl::loadCalibFile(const char *srcFileName)
00159 {
00160
00161
00162
00163 bool res;
00164 std::string filename;
00165 std::stringstream s;
00166
00167 int fcountLeft, fcountRight;
00168 fulcrum fulcrumarrayLeft[255], fulcrumarrayRight[255];
00169 FILE *f;
00170 res = ((f=fopen(srcFileName, "r"))!=NULL);
00171 std::size_t readSize = 0;
00172 if (res)
00173 {
00174 readSize = fread(&fcountLeft, sizeof(fcountLeft),1,f);
00175 readSize = fread(&fcountRight, sizeof(fcountRight),1,f);
00176
00177 if (debugLevel > 0) {
00178 printf("loadCalibFile %s\n",srcFileName);
00179 printf("fcountLeft:%i, fcountRight:%i\n",fcountLeft,fcountRight);
00180 }
00181 readSize = fread(&fulcrumarrayLeft,sizeof(fulcrumarrayLeft[0]),fcountLeft,f);
00182 readSize = fread(&fulcrumarrayRight,sizeof(fulcrumarrayRight[0]),fcountRight,f);
00183
00184 if (debugLevel > 1) {
00185 printf("fulcrumyArrayLeft(%i):\n",fcountLeft);
00186 for(int i=0;i < fcountLeft;i++) {
00187 printf("\nentry %i:\n",i);
00188 printFulcrum(fulcrumarrayLeft[i]);
00189 }
00190 printf("fulcrumyArrayRight(%i):\n",fcountRight);
00191 for(int i=0;i < fcountRight;i++) {
00192 printf("\nentry %i:\n",i);
00193 printFulcrum(fulcrumarrayRight[i]);
00194 }
00195 }
00196
00197 s << "Loaded " << (fcountLeft+fcountRight) << " fulcrums\n";
00198 fclose(f);
00199 }
00200 else {
00201 printf("error loading calibration data: 2%s:%u\n",__FILE__,__LINE__);
00202 return false;
00203 }
00204
00205 if (myID == rightTracker) {
00206 if (debugLevel > 0)
00207 printf("loading Calibration into rightTracker\n");
00208 res = loadCalibration(fulcrumarrayRight, fcountRight);
00209 } else {
00210 if (debugLevel > 0)
00211 printf("loading Calibration into leftTracker\n");
00212 res = loadCalibration(fulcrumarrayLeft, fcountLeft);
00213 }
00214 if(res)
00215 printf("Success! Calibration data loaded\n");
00216 else
00217 printf("error loading calibration data: %s:%u\n",__FILE__,__LINE__);
00218
00219 return res;
00220 }
00221
00222
00223 void tracker_impl::printFulcrum(fulcrum fulc) {
00224 printf("sensorVal: %3.3f, %3.3f, %3.3f\n",fulc.sensorVal[0] ,fulc.sensorVal[1], fulc.sensorVal[2]);
00225 printf("sensorAngle: %3.3f, %3.3f, %3.3f\n",fulc.sensorAngle[0] ,fulc.sensorAngle[1], fulc.sensorAngle[2]);
00226 printf("worldVal: %3.3f, %3.3f, %3.3f\n",fulc.worldVal[0] ,fulc.worldVal[1], fulc.worldVal[2]);
00227 printf("worldAngle: %3.3f, %3.3f, %3.3f\n",fulc.worldAngle[0] ,fulc.worldAngle[1], fulc.worldAngle[2]);
00228 }
00229
00230 bool
00231 tracker_impl::loadCalibration(const fulcrum cal[255], unsigned int length)
00232 {
00233 double world[6],sensor[6];
00234 myTransformer->resetCalibration();
00235 for (unsigned int i=0; i < length; i++)
00236 {
00237 for (int j=0;j<3;j++)
00238 {
00239 sensor[j]=cal[i].sensorVal[j];
00240 sensor[j+3]=cal[i].sensorAngle[j];
00241 world[j]=cal[i].worldVal[j];
00242 world[j+3]=cal[i].worldAngle[j];
00243 }
00244 myTransformer->addCalibrationData(sensor,world);
00245 }
00246 return myTransformer->isCalibrated();
00247 }
00248
00249 void tracker_impl::getPbdObject(std::string name, double *data, asr_msgs::AsrObject &object)
00250 {
00251
00252
00253 object.header.frame_id = "";
00254 object.header.seq = seqId;
00255 object.header.stamp = ros::Time::now();
00256
00257
00258 object.providedBy = "asr_flock_of_birds";
00259
00260
00261
00262 geometry_msgs::Pose help_pose;
00263 help_pose.position.x = data[0] / 1000.0;
00264 help_pose.position.y = data[1] / 1000.0;
00265 help_pose.position.z = data[2] / 1000.0;
00266
00267 tf::Quaternion orientation = tf::createQuaternionFromRPY(data[5] * M_PI/180.0, data[4] * M_PI/180.0, data[3] * M_PI/180.0);
00268 help_pose.orientation.x = orientation.x();
00269 help_pose.orientation.y = orientation.y();
00270 help_pose.orientation.z = orientation.z();
00271 help_pose.orientation.w = orientation.w();
00272
00273 geometry_msgs::PoseWithCovariance help_pose_with_c;
00274 help_pose_with_c.pose = help_pose;
00275 if (object.sampledPoses.size() > 0)
00276 {
00277 object.sampledPoses.pop_back();
00278 }
00279 object.sampledPoses.push_back(help_pose_with_c);
00280
00281
00282 for (unsigned int i=0; i<8; i++)
00283 object.boundingBox[i] = help_pose.position;
00284 object.sizeConfidence = 1.0;
00285
00286
00287 object.type = "tracker";
00288 object.typeConfidence = 1.0;
00289
00290 object.identifier = name;
00291
00292 object.meshResourcePath = "";
00293
00294 }
00295
00296 void tracker_impl::getTransform(double *data, tf::Transform &transform)
00297 {
00298 transform.setOrigin( tf::Vector3(data[0] / 1000.0, data[1] / 1000.0, data[2] / 1000.0) );
00299 transform.setRotation( tf::createQuaternionFromRPY(data[5] * M_PI/180.0, data[4] * M_PI/180.0, data[3] * M_PI/180.0));
00300 }
00301
00302 bool
00303 tracker_impl::writeNotification(trackerID id, double *raw, double *calibrated)
00304 {
00305
00306
00307
00308
00309 std::string name = id == leftTracker ? "tracker_left" : "tracker_right";
00310
00311 if (debugLevel > 2 )
00312 printf( "%s_raw %3.3f %3.3f %3.3f %3.3f° %3.3f° %3.3f° ", name.c_str(),
00313 raw[0], raw[1], raw[2], raw[3], raw[4], raw[5]);
00314 if (debugLevel > 0 )
00315 printf( "%s %3.3f %3.3f %3.3f %3.3f° %3.3f° %3.3f° ", name.c_str(),
00316 calibrated[0], calibrated[1], calibrated[2], calibrated[3], calibrated[4], calibrated[5]);
00317
00318
00319
00320 tf::Transform transform;
00321 asr_msgs::AsrObject object;
00322
00323
00324 getPbdObject(name, calibrated, object);
00325 generalPublisher.publish(object);
00326
00327
00328 getTransform(calibrated, transform);
00329 transformPublisher.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "tracker_base", name));
00330
00331
00332 name += "_raw";
00333 getPbdObject(name, raw, object);
00334 generalPublisher.publish(object);
00335
00336 getTransform(raw, transform);
00337 transformPublisher.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "Root", name));
00338
00339 this->seqId++;
00340 return true;
00341 }
00342
00343
00344
00345
00346
00347 #if tracker_impl_test
00348 int main(int argc, char **argv)
00349 {
00350 bgcorba::init(argc, argv);
00351
00352
00353 tracker_impl *impl = new tracker_impl;
00354
00355 int retval = bgcorba::main(impl);
00356
00357 delete impl;
00358
00359 return retval;
00360 }
00361 #endif
00362