EstimationNode.cpp
Go to the documentation of this file.
00001 
00022 #include "EstimationNode.h"
00023 #include "ros/ros.h"
00024 #include "ros/package.h"
00025 #include "geometry_msgs/Twist.h"
00026 #include "sensor_msgs/Image.h"
00027 #include "tf/tfMessage.h"
00028 #include "tf/transform_listener.h"
00029 #include "tf/transform_broadcaster.h"
00030 #include "std_msgs/Empty.h"
00031 #include "std_srvs/Empty.h"
00032 #include "../HelperFunctions.h"
00033 #include "DroneKalmanFilter.h"
00034 #include <ardrone_autonomy/Navdata.h>
00035 #include "deque"
00036 #include "tum_ardrone/filter_state.h"
00037 #include "PTAMWrapper.h"
00038 #include "std_msgs/String.h"
00039 #include "std_msgs/Empty.h"
00040 #include "std_srvs/Empty.h"
00041 #include "MapView.h"
00042 #include <sys/stat.h>
00043 #include <string>
00044 
00045 using namespace std;
00046 
00047 pthread_mutex_t EstimationNode::logIMU_CS = PTHREAD_MUTEX_INITIALIZER;
00048 pthread_mutex_t EstimationNode::logPTAM_CS = PTHREAD_MUTEX_INITIALIZER;
00049 pthread_mutex_t EstimationNode::logFilter_CS = PTHREAD_MUTEX_INITIALIZER;
00050 pthread_mutex_t EstimationNode::logPTAMRaw_CS = PTHREAD_MUTEX_INITIALIZER;
00051 
00052 EstimationNode::EstimationNode()
00053 {
00054     navdata_channel = nh_.resolveName("ardrone/navdata");
00055     control_channel = nh_.resolveName("cmd_vel");
00056     output_channel = nh_.resolveName("ardrone/predictedPose");
00057     video_channel = nh_.resolveName("ardrone/image_raw");
00058     command_channel = nh_.resolveName("tum_ardrone/com");
00059         packagePath = ros::package::getPath("tum_ardrone");
00060 
00061         std::string val;
00062         float valFloat = 0;
00063 
00064         predTime = ros::Duration(25*0.001);
00065 
00066         ros::param::get("~publishFreq", val);
00067         if(val.size()>0)
00068                 sscanf(val.c_str(), "%f", &valFloat);
00069         else
00070                 valFloat = 30;
00071         publishFreq = valFloat;
00072         cout << "set publishFreq to " << valFloat << "Hz"<< endl;
00073 
00074 
00075 
00076         ros::param::get("~calibFile", calibFile);
00077         if(calibFile.size()>0)
00078                 cout << "set calibFile to " << calibFile << endl;
00079         else
00080                 cout << "set calibFile to DEFAULT" << endl;
00081 
00082 
00083         navdata_sub       = nh_.subscribe(navdata_channel, 10, &EstimationNode::navdataCb, this);
00084         vel_sub          = nh_.subscribe(control_channel,10, &EstimationNode::velCb, this);
00085         vid_sub          = nh_.subscribe(video_channel,10, &EstimationNode::vidCb, this);
00086 
00087         dronepose_pub      = nh_.advertise<tum_ardrone::filter_state>(output_channel,1);
00088 
00089         tum_ardrone_pub    = nh_.advertise<std_msgs::String>(command_channel,50);
00090         tum_ardrone_sub    = nh_.subscribe(command_channel,50, &EstimationNode::comCb, this);
00091 
00092         //tf_broadcaster();
00093 
00094         // other internal vars
00095         logfileIMU = logfilePTAM = logfileFilter = logfilePTAMRaw = 0;
00096         currentLogID = 0;
00097         lastDroneTS = 0;
00098         lastRosTS = 0;
00099         droneRosTSOffset = 0;
00100         lastNavStamp = ros::Time(0);
00101         filter = new DroneKalmanFilter(this);
00102         ptamWrapper = new PTAMWrapper(filter, this);
00103         mapView = new MapView(filter, ptamWrapper, this);
00104         arDroneVersion = 0;
00105         //memset(&lastNavdataReceived,0,sizeof(ardrone_autonomy::Navdata));
00106 
00107 
00108 }
00109 
00110 EstimationNode::~EstimationNode()
00111 {
00112         filter->release();
00113         delete mapView;
00114         delete ptamWrapper;
00115         delete filter;
00116 
00117 
00118         //delete infoQueue;
00119 }
00120 void EstimationNode::navdataCb(const ardrone_autonomy::NavdataConstPtr navdataPtr)
00121 {
00122         lastNavdataReceived = *navdataPtr;
00123         if(ros::Time::now() - lastNavdataReceived.header.stamp > ros::Duration(30.0))
00124                 lastNavdataReceived.header.stamp = ros::Time::now();
00125 
00126         if(arDroneVersion == 0)
00127         {
00128                 arDroneVersion = (navdataPtr->pressure == 0) ? 1 : 2;
00129                 std::cout <<"Found ARDrone Version " << arDroneVersion << std::endl;
00130         }
00131 
00132 
00133         // darn ROS really messes up timestamps.
00134         // they should arrive every 5ms, with occasionally dropped packages.
00135         // instead, they arrive with gaps of up to 30ms, and then 6 packages with the same timestamp.
00136         // so: this procedure "smoothes out" received package timestamps, shifting their timestamp by max. 20ms to better fit the order.
00137         long rosTS = getMS(lastNavdataReceived.header.stamp);
00138         long droneTS = navdataPtr->tm / 1000;
00139 
00140         if(lastDroneTS == 0) lastDroneTS = droneTS;
00141 
00142         if((droneTS+1000000) < lastDroneTS)
00143         {
00144                 droneRosTSOffset = rosTS - droneTS;     // timestamp-overflow, reset running average.
00145                 ROS_WARN("Drone Navdata timestamp overflow! (should happen epprox every 30min, while drone switched on)");
00146         }
00147         else
00148                 droneRosTSOffset = 0.9 * droneRosTSOffset + 0.1*(rosTS - droneTS);
00149 
00150         long rosTSNew =droneTS + droneRosTSOffset;      // this should be the correct timestamp.
00151         long TSDiff = std::min(100l,std::max(-100l,rosTSNew-rosTS));    // never change by more than 100ms.
00152         lastNavdataReceived.header.stamp += ros::Duration(TSDiff/1000.0);       // change!
00153         lastRosTS = rosTS;
00154         lastDroneTS = droneTS;
00155 
00156 
00157         // convert to originally sent drone values (undo ardrone_autonomy changes)
00158         lastNavdataReceived.rotZ *= -1; // yaw inverted
00159         lastNavdataReceived.rotY *= -1; // pitch inverted
00160         lastNavdataReceived.vy *= -1;   // yaw inverted
00161         lastNavdataReceived.vz *= -1;   // pitch inverted
00162         lastNavdataReceived.ay *= -1;   // yaw inverted
00163         lastNavdataReceived.az *= -1;   // pitch inverted
00164 
00165 
00166 
00167         // push back in filter queue.
00168         pthread_mutex_lock( &filter->filter_CS );
00169         filter->navdataQueue->push_back(lastNavdataReceived);
00170         pthread_mutex_unlock( &filter->filter_CS );
00171 
00172 
00173         // give to PTAM (for scale estimation)
00174         ptamWrapper->newNavdata(&lastNavdataReceived);
00175 
00176 
00177         // save last timestamp
00178         if(lastNavStamp != ros::Time(0) && (lastNavdataReceived.header.stamp - lastNavStamp > ros::Duration(0.1)))
00179                 std::cout << (lastNavdataReceived.header.stamp - lastNavStamp).toSec() << "s between two consecutive navinfos. This system requires Navinfo at 200Hz. If this error persists, set drone to debug mode and change publish freq in ardrone_autonomy" << std::endl;
00180         lastNavStamp = lastNavdataReceived.header.stamp;
00181 
00182 
00183         if(logfileIMU != NULL)
00184         {
00185                 int pingNav = 0, pingVid = 0;
00186                 pthread_mutex_lock(&logIMU_CS);
00187                 if(logfileIMU != NULL)
00188                         (*logfileIMU) << getMS(lastNavdataReceived.header.stamp) << " " << lastNavdataReceived.tm << " " <<
00189                         lastNavdataReceived.vx << " " << lastNavdataReceived.vy << " " << lastNavdataReceived.altd << " " << lastNavdataReceived.rotX/1000.0 << " " << lastNavdataReceived.rotY/1000.0 << " " << lastNavdataReceived.rotZ/1000.0 << " " <<
00190                         lastNavdataReceived.pressure << " " <<  0 << " " <<  0 << " " << 0 << " " <<    // control: roll pitch gaz yaw.
00191                         pingNav << " " << pingVid << "\n";
00192                 pthread_mutex_unlock(&logIMU_CS);
00193         }
00194 
00195 }
00196 
00197 void EstimationNode::velCb(const geometry_msgs::TwistConstPtr velPtr)
00198 {
00199         geometry_msgs::TwistStamped ts;
00200         ts.header.stamp = ros::Time::now();
00201         ts.twist = *velPtr;
00202 
00203         // for some reason this needs to be inverted.
00204         // linear.y corresponds to ROLL
00205         ts.twist.linear.y *= -1;
00206         ts.twist.linear.x *= -1;
00207         ts.twist.angular.z *= -1;
00208 
00209         pthread_mutex_lock( &filter->filter_CS );
00210         filter->velQueue->push_back(ts);
00211         pthread_mutex_unlock( &filter->filter_CS );
00212 }
00213 
00214 void EstimationNode::vidCb(const sensor_msgs::ImageConstPtr img)
00215 {
00216         // give to PTAM
00217         ptamWrapper->newImage(img);
00218 }
00219 
00220 void EstimationNode::comCb(const std_msgs::StringConstPtr str)
00221 {
00222         if(str->data.length() > 2 && str->data.substr(0,2) == "p ")
00223         {
00224                 ptamWrapper->handleCommand(str->data.substr(2,str->data.length()-2));
00225         }
00226 
00227         if(str->data.length() > 2 && str->data.substr(0,2) == "f ")
00228         {
00229                 mapView->handleCommand(str->data.substr(2,str->data.length()-2));
00230         }
00231 
00232         if(str->data.length() > 2 && str->data.substr(0,2) == "m ")
00233         {
00234                 mapView->handleCommand(str->data.substr(2,str->data.length()-2));
00235         }
00236 
00237         if(str->data.length() == 9 && str->data.substr(0,9) == "toggleLog")
00238         {
00239                 this->toogleLogging();
00240         }
00241 
00242 
00243 
00244 
00245 
00246         int a, b;
00247         if(sscanf(str->data.c_str(),"pings %d %d",&a, &b) == 2)
00248         {
00249                 filter->setPing((unsigned int)a, (unsigned int)b);
00250                 predTime = ros::Duration((0.001*filter->delayControl)); // set predTime to new delayControl
00251         }
00252 }
00253 
00254 
00255 void EstimationNode::Loop()
00256 {
00257           ros::Rate pub_rate(publishFreq);
00258 
00259           ros::Time lastInfoSent = ros::Time::now();
00260 
00261           while (nh_.ok())
00262           {
00263                   // -------------- 1. put nav & control in internal queues. ---------------
00264                   ros::spinOnce();
00265 
00266 
00267                   // -------------- 3. get predicted pose and publish! ---------------
00268                   // get filter state msg
00269                   pthread_mutex_lock( &filter->filter_CS );
00270                   tum_ardrone::filter_state s = filter->getPoseAt(ros::Time().now() + predTime);
00271                   pthread_mutex_unlock( &filter->filter_CS );
00272 
00273                   // fill metadata
00274                   s.header.stamp = ros::Time().now();
00275                   s.scale = filter->getCurrentScales()[0];
00276                   s.scaleAccuracy = filter->getScaleAccuracy();
00277                   s.ptamState = ptamWrapper->PTAMStatus;
00278                   s.droneState = lastNavdataReceived.state;
00279                   s.batteryPercent = lastNavdataReceived.batteryPercent;
00280 
00281                   // publish!
00282                   dronepose_pub.publish(s);
00283 
00284 
00285                   // --------- if need be: add fake PTAM obs --------
00286                   // if PTAM updates hang (no video or e.g. init), filter is never permanently rolled forward -> queues get too big.
00287                   // dont allow this to happen by faking a ptam observation if queue gets too big (500ms = 100 observations)
00288                   if((getMS(ros::Time().now()) - filter->predictdUpToTimestamp) > 500)
00289                           filter->addFakePTAMObservation(getMS(ros::Time().now()) - 300);
00290 
00291 
00292                   // ---------- maybe send new info --------------------------
00293                   if((ros::Time::now() - lastInfoSent) > ros::Duration(0.4))
00294                   {
00295                           reSendInfo();
00296                           lastInfoSent = ros::Time::now();
00297                   }
00298 
00299                   // -------------- 4. sleep until rate is hit. ---------------
00300                   pub_rate.sleep();
00301           }
00302 }
00303 void EstimationNode::dynConfCb(tum_ardrone::StateestimationParamsConfig &config, uint32_t level)
00304 {
00305         if(!filter->allSyncLocked && config.PTAMSyncLock)
00306                 ROS_WARN("Ptam Sync has been disabled. This fixes scale etc.");
00307 
00308         if(!ptamWrapper->mapLocked && config.PTAMMapLock)
00309                 ROS_WARN("Ptam Map has been locked.");
00310 
00311 
00312         filter->useControl =config.UseControlGains;
00313         filter->usePTAM =config.UsePTAM;
00314         filter->useNavdata =config.UseNavdata;
00315 
00316         filter->useScalingFixpoint = config.RescaleFixOrigin;
00317 
00318         ptamWrapper->maxKF = config.PTAMMaxKF;
00319         ptamWrapper->mapLocked = config.PTAMMapLock;
00320         filter->allSyncLocked = config.PTAMSyncLock;
00321 
00322 
00323         ptamWrapper->setPTAMPars(config.PTAMMinKFTimeDiff, config.PTAMMinKFWiggleDist, config.PTAMMinKFDist);
00324 
00325 
00326         filter->c1 = config.c1;
00327         filter->c2 = config.c2;
00328         filter->c3 = config.c3;
00329         filter->c4 = config.c4;
00330         filter->c5 = config.c5;
00331         filter->c6 = config.c6;
00332         filter->c7 = config.c7;
00333         filter->c8 = config.c8;
00334 
00335 }
00336 
00337 pthread_mutex_t EstimationNode::tum_ardrone_CS = PTHREAD_MUTEX_INITIALIZER; //pthread_mutex_lock( &cs_mutex );
00338 void EstimationNode::publishCommand(std::string c)
00339 {
00340         std_msgs::String s;
00341         s.data = c.c_str();
00342         pthread_mutex_lock(&tum_ardrone_CS);
00343         tum_ardrone_pub.publish(s);
00344         pthread_mutex_unlock(&tum_ardrone_CS);
00345 }
00346 
00347 void EstimationNode::publishTf(TooN::SE3<> trans, ros::Time stamp, int seq, std::string system)
00348 {
00349         trans = trans.inverse();
00350 
00351         tf::Matrix3x3 m;
00352         m[0][0] = trans.get_rotation().get_matrix()(0,0);
00353         m[0][1] = trans.get_rotation().get_matrix()(0,1);
00354         m[0][2] = trans.get_rotation().get_matrix()(0,2);
00355         m[1][0] = trans.get_rotation().get_matrix()(1,0);
00356         m[1][1] = trans.get_rotation().get_matrix()(1,1);
00357         m[1][2] = trans.get_rotation().get_matrix()(1,2);
00358         m[2][0] = trans.get_rotation().get_matrix()(2,0);
00359         m[2][1] = trans.get_rotation().get_matrix()(2,1);
00360         m[2][2] = trans.get_rotation().get_matrix()(2,2);
00361 
00362         tf::Vector3 v;
00363         v[0] = trans.get_translation()[0];
00364         v[1] = trans.get_translation()[1];
00365         v[2] = trans.get_translation()[2];
00366 
00367 
00368         tf::Transform tr = tf::Transform(m,v);
00369         tf::StampedTransform t = tf::StampedTransform(tr,stamp,"map",system);
00370         tf_broadcaster.sendTransform(t);
00371 
00372 
00373 
00374         if(logfilePTAMRaw != NULL)
00375         {
00376                 pthread_mutex_lock(&(logPTAMRaw_CS));
00377                 // log:
00378                 // - filterPosePrePTAM estimated for videoFrameTimestamp-delayVideo.
00379                 // - PTAMResulttransformed estimated for videoFrameTimestamp-delayVideo. (using imu only for last step)
00380                 // - predictedPoseSpeed estimated for lastNfoTimestamp+filter->delayControl     (actually predicting)
00381                 // - predictedPoseSpeedATLASTNFO estimated for lastNfoTimestamp (using imu only)
00382                 if(logfilePTAMRaw != NULL)
00383                         (*(logfilePTAMRaw)) << seq << " " << stamp << " " << tr.getOrigin().x() << " " << tr.getOrigin().y() << " " << tr.getOrigin().z() << " " <<
00384                         tr.getRotation().x() << " " << tr.getRotation().y() << " " << tr.getRotation().z() << " " << tr.getRotation().w() << std::endl;
00385 
00386                 pthread_mutex_unlock(&(logPTAMRaw_CS));
00387         }
00388 
00389 }
00390 
00391 void EstimationNode::toogleLogging()
00392 {
00393         // first: always check for /log dir
00394         struct stat st;
00395         if(stat((packagePath+std::string("/logs")).c_str(),&st) != 0)
00396                 mkdir((packagePath+std::string("/logs")).c_str(),S_IXGRP | S_IXOTH | S_IXUSR | S_IRWXU | S_IRWXG | S_IROTH);
00397 
00398         char buf[200];
00399         bool quitLogging = false;
00400         if(logfileIMU == 0)
00401         {
00402                 currentLogID = ((long)time(0))*100+(getMS()%100);               // time(0) + ms
00403                 startedLogClock = getMS();
00404                 ROS_INFO("\n\nENABLED LOGGING to %s/logs/%ld\n\n\n",packagePath.c_str(),currentLogID);
00405                 sprintf(buf,"%s/logs/%ld",packagePath.c_str(),currentLogID);
00406                 mkdir(buf, S_IXGRP | S_IXOTH | S_IXUSR | S_IRWXU | S_IRWXG | S_IROTH);
00407 
00408 
00409                 sprintf(buf,"u l ENABLED LOGGING to %s/logs/%ld",packagePath.c_str(),currentLogID);
00410                 publishCommand(buf);
00411         }
00412         else
00413                 quitLogging = true;
00414 
00415 
00416 
00417         // IMU
00418         pthread_mutex_lock(&logIMU_CS);
00419         if(logfileIMU == 0)
00420         {
00421                 logfileIMU = new std::ofstream();
00422                 sprintf(buf,"%s/logs/%ld/logIMU.txt",packagePath.c_str(),currentLogID);
00423                 logfileIMU->open (buf);
00424         }
00425         else
00426         {
00427                 logfileIMU->flush();
00428                 logfileIMU->close();
00429                 delete logfileIMU;
00430                 logfileIMU = NULL;
00431         }
00432         pthread_mutex_unlock(&logIMU_CS);
00433 
00434 
00435         // IMU
00436         pthread_mutex_lock(&logPTAM_CS);
00437         if(logfilePTAM == 0)
00438         {
00439                 logfilePTAM = new std::ofstream();
00440                 sprintf(buf,"%s/logs/%ld/logPTAM.txt",packagePath.c_str(),currentLogID);
00441                 logfilePTAM->open (buf);
00442         }
00443         else
00444         {
00445                 logfilePTAM->flush();
00446                 logfilePTAM->close();
00447                 delete logfilePTAM;
00448                 logfilePTAM = NULL;
00449         }
00450         pthread_mutex_unlock(&logPTAM_CS);
00451 
00452 
00453 
00454         // IMU
00455         pthread_mutex_lock(&logFilter_CS);
00456         if(logfileFilter == 0)
00457         {
00458                 logfileFilter = new std::ofstream();
00459                 sprintf(buf,"%s/logs/%ld/logFilter.txt",packagePath.c_str(),currentLogID);
00460                 logfileFilter->open (buf);
00461         }
00462         else
00463         {
00464                 logfileFilter->flush();
00465                 logfileFilter->close();
00466                 delete logfileFilter;
00467                 logfileFilter = NULL;
00468         }
00469         pthread_mutex_unlock(&logFilter_CS);
00470 
00471 
00472         // IMU
00473         pthread_mutex_lock(&logPTAMRaw_CS);
00474         if(logfilePTAMRaw == 0)
00475         {
00476                 logfilePTAMRaw = new std::ofstream();
00477                 sprintf(buf,"%s/logs/%ld/logPTAMRaw.txt",packagePath.c_str(),currentLogID);
00478                 logfilePTAMRaw->open (buf);
00479         }
00480         else
00481         {
00482                 logfilePTAMRaw->flush();
00483                 logfilePTAMRaw->close();
00484                 delete logfilePTAMRaw;
00485                 logfilePTAMRaw = NULL;
00486         }
00487         pthread_mutex_unlock(&logPTAMRaw_CS);
00488 
00489 
00490         if(quitLogging)
00491         {
00492                 printf("\n\nDISABLED LOGGING (logged %ld sec)\n\n\n",(getMS()-startedLogClock+500)/1000);
00493                 char buf2[200];
00494                 sprintf(buf,"%s/logs/%ld",packagePath.c_str(),currentLogID);
00495                 sprintf(buf2,"%s/logs/%ld-%lds",packagePath.c_str(),currentLogID,(getMS()-startedLogClock+500)/1000);
00496                 rename(buf,buf2);
00497         }
00498 
00499 }
00500 
00501 void EstimationNode::reSendInfo()
00502 {
00503 
00504         // get ptam status string
00505         std::string ptamStatus;
00506         switch(ptamWrapper->PTAMStatus)
00507         {
00508         case PTAMWrapper::PTAM_IDLE:
00509                 ptamStatus = "Idle";
00510                 break;
00511         case PTAMWrapper::PTAM_INITIALIZING:
00512                 ptamStatus = "Initializing";
00513                 break;
00514         case PTAMWrapper::PTAM_LOST:
00515                 ptamStatus = "Lost";
00516                 break;
00517         case PTAMWrapper::PTAM_FALSEPOSITIVE:
00518                 ptamStatus = "FalsePositive";
00519                 break;
00520         case PTAMWrapper::PTAM_GOOD:
00521                 ptamStatus = "Good";
00522                 break;
00523         case PTAMWrapper::PTAM_TOOKKF:
00524         case PTAMWrapper::PTAM_BEST:
00525                 ptamStatus = "Best";
00526                 break;
00527         }
00528 
00529 
00530 
00531         // parse PTAM message
00532         std::string ptamMsg = ptamWrapper->lastPTAMMessage;
00533         int kf, kp, kps[4], kpf[4];
00534         int pos = ptamMsg.find("Found: ");
00535         int found = 0;
00536         if(pos != std::string::npos)
00537                 found = sscanf(ptamMsg.substr(pos).c_str(),"Found: %d/%d %d/%d %d/%d %d/%d Map: %dP, %dKF",
00538                                                 &kpf[0],&kps[0],&kpf[1],&kps[1],&kpf[2],&kps[2],&kpf[3],&kps[3],&kp,&kf);
00539         char bufp[200];
00540         if(found == 10)
00541                 snprintf(bufp,200,"Map: KF: %d, KP: %d (%d of %d found)",
00542                                 kf, kp,kpf[0]+kpf[1]+kpf[2]+kpf[3], kps[0]+kps[1]+kps[2]+kps[3]);
00543         else
00544                 snprintf(bufp,200,"Map: -");
00545 
00546         lastNavdataReceived.batteryPercent;
00547 
00548         std::string status = "";
00549         switch( lastNavdataReceived.state)
00550         {
00551                 case 0: status = "Unknown";break;
00552                 case 1: status = "Init"; break;
00553                 case 2: status = "Landed";break;
00554                 case 3: status = "Flying"; break;
00555                 case 4: status = "Hovering";break;
00556                 case 5: status = "Test"; break;
00557                 case 6: status = "Taking off";break;
00558                 case 7: status = "Goto Fix Point"; break;
00559                 case 8: status = "Landing";break;
00560                 case 9: status = "Looping"; break;
00561         }
00562         /*
00563         PTAM: Idle | Good | Dodgy | Lost
00564         Map: KF: X, KP: X (X searched, X found)
00565         Scale: X (in: X, out: x), acc: X
00566         Scale Fixpoint: NONE | DRONE
00567         Status: X (Battery: X)
00568         */
00569         char buf[1000];
00570         snprintf(buf,1000,"u s PTAM: %s\n%s\nScale: %.3f (%d in, %d out), acc: %.2f\nScaleFixpoint: %s\nDrone Status: %s (%d Battery)",
00571                         ptamStatus.c_str(),
00572                         bufp,
00573                         filter->getCurrentScales()[0],filter->scalePairsIn,filter->scalePairsOut,filter->getScaleAccuracy(),
00574                         filter->useScalingFixpoint ? "FIX" : "DRONE",
00575                         status.c_str(), (int)lastNavdataReceived.batteryPercent);
00576 
00577         publishCommand(buf);
00578 }


tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:27:22