SelfLocalizer.cpp
Go to the documentation of this file.
00001 #include "SelfLocalizer.h"
00002 
00003 #include <tf/transform_listener.h>
00004 #include <math.h>
00005 
00006 bool isNaN(double a)
00007 {
00008         //return (a != a);
00009         return boost::math::isnan(a);
00010 }
00011 
00012 double angle_diff(double a, double b)
00013 {
00014         a = atan2(sin(a),cos(a));
00015         b = atan2(sin(b),cos(b));
00016         double d1 = a - b;
00017         double d2 = 2 * M_PI - fabs(d1);
00018         if(d1 > 0)
00019         d2 *= -1.0;
00020         if(fabs(d1) < fabs(d2))
00021                 return(d1);
00022         else
00023                 return(d2);
00024 }
00025 
00026 OdometryData::OdometryData(const tf::StampedTransform& pNewPose, const tf::StampedTransform& pLastPose)
00027 {
00028         mDeltaX = pNewPose.getOrigin().x() - pLastPose.getOrigin().x();
00029         mDeltaY = pNewPose.getOrigin().y() - pLastPose.getOrigin().y();
00030         mDeltaTheta = tf::getYaw(pNewPose.getRotation()) -  tf::getYaw(pLastPose.getRotation());
00031 }
00032 
00033 LaserData::LaserData(const sensor_msgs::LaserScan::ConstPtr& scan)
00034 {
00035         mRangeCount = scan->ranges.size();
00036         mRanges = new double[mRangeCount][2];
00037         mRangeMax = scan->range_max;
00038         
00039         double angle_min = scan->angle_min;
00040         double angle_inc = scan->angle_increment; 
00041         
00042         angle_inc = fmod(angle_inc + 5*M_PI, 2*M_PI) - M_PI;
00043         
00044         for(int i = 0; i < mRangeCount; i++)
00045         {
00046                 if(scan->ranges[i] <= scan->range_min)
00047                         mRanges[i][0] = scan->range_max;
00048                 else
00049                         mRanges[i][0] = scan->ranges[i];
00050 
00051                 // Compute bearing
00052                 mRanges[i][1] = angle_min + (i * angle_inc);
00053         }
00054 }
00055 
00056 LaserData::~LaserData()
00057 {
00058         delete[] mRanges;
00059 }
00060 
00061 map_t* SelfLocalizer::sMap = NULL;
00062 double SelfLocalizer::sSigmaHit;
00063 double SelfLocalizer::sLamdaShort;
00064 double SelfLocalizer::sZHit;
00065 double SelfLocalizer::sZMax;
00066 double SelfLocalizer::sZRand;
00067 double SelfLocalizer::sZShort;
00068 int SelfLocalizer::sMaxBeams;
00069 double SelfLocalizer::sLikelihoodMaxDist;
00070 
00071 double SelfLocalizer::sAlpha1;
00072 double SelfLocalizer::sAlpha2;
00073 double SelfLocalizer::sAlpha3;
00074 double SelfLocalizer::sAlpha4;
00075 
00076 pf_vector_t SelfLocalizer::sLaserPose;
00077 
00078 tf::StampedTransform SelfLocalizer::mLastPose;
00079 
00080 SelfLocalizer::SelfLocalizer(bool publish)
00081  : mPublishParticles(publish)
00082 {
00083         mActionModelFunction = (pf_action_model_fn_t)SelfLocalizer::calculateMoveModel;
00084         
00085         ros::NodeHandle globalNode;
00086         globalNode.param("laser_frame", mLaserFrame, std::string("laser"));
00087         globalNode.param("robot_frame", mRobotFrame, std::string("robot"));
00088         globalNode.param("odometry_frame", mOdometryFrame, std::string("odometry_base"));
00089         globalNode.param("map_frame", mMapFrame, std::string("map"));
00090         
00091         ros::NodeHandle localNode("~/");
00092         localNode.param("min_particles", mMinParticles, 500);
00093         localNode.param("max_particles", mMaxParticles, 2500);
00094         localNode.param("alpha_slow", mAlphaSlow, 0.001);
00095         localNode.param("alpha_fast", mAlphaFast, 0.1);
00096         localNode.param("min_translation", mMinTranslation, 0.2);
00097         localNode.param("min_rotation", mMinRotation, 0.5);
00098         localNode.param("pop_err", mPopulationErr, 0.01);
00099         localNode.param("pop_z", mPopulationZ, 0.99);
00100         
00101         localNode.param("laser_sigma_hit", sSigmaHit, 0.2);
00102         localNode.param("laser_lambda_short", sLamdaShort, 0.1);
00103         localNode.param("laser_z_hit", sZHit, 0.95);
00104         localNode.param("laser_z_max", sZMax, 0.05);
00105         localNode.param("laser_z_rand", sZRand, 0.05);
00106         localNode.param("laser_z_short", sZShort, 0.1);
00107         localNode.param("laser_max_beams", sMaxBeams, 30);
00108         localNode.param("laser_likelihood_max_dist", sLikelihoodMaxDist, 2.0);
00109         
00110         localNode.param("odom_alpha_1", sAlpha1, 0.25);
00111         localNode.param("odom_alpha_2", sAlpha2, 0.25);
00112         localNode.param("odom_alpha_3", sAlpha3, 0.25);
00113         localNode.param("odom_alpha_4", sAlpha4, 0.25);
00114         
00115         localNode.param("laser_model_type", mLaserModelType, 2);
00116         switch(mLaserModelType)
00117         {
00118         case 2:
00119                 mSensorModelFunction = (pf_sensor_model_fn_t)SelfLocalizer::calculateLikelihoodFieldModel;
00120                 break;
00121         case 1:
00122         default:
00123                 mLaserModelType = 1;
00124                 mSensorModelFunction = (pf_sensor_model_fn_t)SelfLocalizer::calculateBeamModel;
00125         }
00126         
00127         if(mPublishParticles)
00128         {
00129                 mParticlePublisher = localNode.advertise<geometry_msgs::PoseArray>("particles", 1, true);
00130         }
00131 
00132         mFirstScanReceived = false;
00133         mParticleFilter = NULL;
00134         
00135         // Apply tf_prefix to all used frame-id's
00136         std::string tfPrefix = mTransformListener.getTFPrefix();
00137         mMapFrame = tf::resolve(tfPrefix, mMapFrame);
00138         mOdometryFrame = tf::resolve(tfPrefix, mOdometryFrame);
00139         mRobotFrame = tf::resolve(tfPrefix, mRobotFrame);
00140         mLaserFrame = tf::resolve(tfPrefix, mLaserFrame);
00141         
00142         // Use squared distance so we don't need sqrt() later
00143         mMinTranslation *= mMinTranslation;
00144         mMapToOdometry.setIdentity();
00145 }
00146 
00147 SelfLocalizer::~SelfLocalizer()
00148 {
00149         if(mParticleFilter)
00150                 pf_free(mParticleFilter);
00151         if(sMap)        
00152                 map_free(sMap);
00153 }
00154 
00155 pf_vector_t SelfLocalizer::distributeParticles(void* data)
00156 {
00157         map_t* map = (map_t*)data;
00158 
00159         double min_x, max_x, min_y, max_y;
00160         
00161         min_x = map->origin_x - (map->size_x * map->scale / 2.0);
00162         max_x = map->origin_x + (map->size_x * map->scale / 2.0);
00163         min_y = map->origin_y - (map->size_y * map->scale / 2.0);
00164         max_y = map->origin_y + (map->size_y * map->scale / 2.0);
00165 
00166         pf_vector_t p;
00167 
00168         while(true)
00169         {
00170                 p.v[0] = min_x + drand48() * (max_x - min_x);
00171                 p.v[1] = min_y + drand48() * (max_y - min_y);
00172                 p.v[2] = drand48() * 2 * M_PI - M_PI;
00173 
00174                 // Check that it's a free cell
00175                 int i,j;
00176                 i = MAP_GXWX(map, p.v[0]);
00177                 j = MAP_GYWY(map, p.v[1]);
00178                 if(MAP_VALID(map,i,j) && (map->cells[MAP_INDEX(map,i,j)].occ_state == -1))
00179                         break;
00180         }
00181         return p;
00182 }
00183 
00184 double SelfLocalizer::calculateMoveModel(OdometryData* data, pf_sample_set_t* set)
00185 {
00186         // Implement sample_motion_odometry (Prob Rob p 136)
00187         double delta_rot1, delta_trans, delta_rot2;
00188         double delta_rot1_hat, delta_trans_hat, delta_rot2_hat;
00189         double delta_rot1_noise, delta_rot2_noise;
00190 
00191         // Avoid computing a bearing from two poses that are extremely near each
00192         // other (happens on in-place rotation).
00193         delta_trans = sqrt(data->mDeltaX * data->mDeltaX + data->mDeltaY * data->mDeltaY);
00194         if(delta_trans < 0.01)
00195                 delta_rot1 = 0.0;
00196         else
00197                 delta_rot1 = angle_diff(atan2(data->mDeltaY, data->mDeltaX), tf::getYaw(mLastPose.getRotation()));
00198 
00199         delta_rot2 = angle_diff(data->mDeltaTheta, delta_rot1);
00200 
00201         // We want to treat backward and forward motion symmetrically for the
00202         // noise model to be applied below.  The standard model seems to assume
00203         // forward motion.
00204         delta_rot1_noise = std::min(fabs(angle_diff(delta_rot1,0.0)), fabs(angle_diff(delta_rot1,M_PI)));
00205         delta_rot2_noise = std::min(fabs(angle_diff(delta_rot2,0.0)), fabs(angle_diff(delta_rot2,M_PI)));
00206 
00207         for (int i = 0; i < set->sample_count; i++)
00208         {
00209                 pf_sample_t* sample = set->samples + i;
00210 
00211                 // Sample pose differences
00212                 delta_rot1_hat = angle_diff(delta_rot1, pf_ran_gaussian(sAlpha1*delta_rot1_noise*delta_rot1_noise + sAlpha2*delta_trans*delta_trans));
00213                 delta_trans_hat = delta_trans - pf_ran_gaussian(sAlpha3*delta_trans*delta_trans + sAlpha4*delta_rot1_noise*delta_rot1_noise + sAlpha4*delta_rot2_noise*delta_rot2_noise);
00214                 delta_rot2_hat = angle_diff(delta_rot2, pf_ran_gaussian(sAlpha1*delta_rot2_noise*delta_rot2_noise + sAlpha2*delta_trans*delta_trans));
00215 
00216                 // Apply sampled update to particle pose
00217                 sample->pose.v[0] += delta_trans_hat * cos(sample->pose.v[2] + delta_rot1_hat);
00218                 sample->pose.v[1] += delta_trans_hat * sin(sample->pose.v[2] + delta_rot1_hat);
00219                 sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat;
00220                 sample->weight = 1.0 / set->sample_count;
00221         }
00222         
00223         return 0.0;
00224 }
00225 
00226 double SelfLocalizer::calculateBeamModel(LaserData *data, pf_sample_set_t* set)
00227 {
00228         pf_sample_t *sample;
00229         pf_vector_t pose;
00230         
00231         double mapRange;
00232         double obsRange, obsBearing;
00233         double z, pz; // What is z/pz ?
00234         
00235         double totalWeight = 0.0;
00236         
00237         for (int j = 0; j < set->sample_count; j++)
00238         {
00239                 sample = set->samples + j;
00240                 pose = sample->pose;
00241 
00242                 pose = pf_vector_coord_add(pose, sLaserPose);
00243 //              pose = pf_vector_coord_sub(pose, sLaserPose);
00244 
00245                 double p = 1.0;
00246                 int step = (data->mRangeCount - 1) / (sMaxBeams - 1);
00247                 for (int i = 0; i < data->mRangeCount; i+=step)
00248                 {
00249                         obsRange = data->mRanges[i][0];
00250                         obsBearing = data->mRanges[i][1];
00251                         mapRange = map_calc_range(sMap, pose.v[0], pose.v[1], pose.v[2]+obsBearing, data->mRangeMax);
00252                         pz = 0.0;
00253 
00254                         // Part 1: good, but noisy, hit
00255                         z = obsRange - mapRange;
00256                         pz += sZHit * exp(-(z * z) / (2 * sSigmaHit * sSigmaHit));
00257 
00258                         // Part 2: short reading from unexpected obstacle (e.g., a person)
00259                         if(z < 0)
00260                         pz += sZShort * sLamdaShort * exp(- sLamdaShort * obsRange);
00261 
00262                         // Part 3: Failure to detect obstacle, reported as max-range
00263                         if(obsRange == data->mRangeMax)
00264                         pz += sZMax * 1.0;
00265 
00266                         // Part 4: Random measurements
00267                         if(obsRange < data->mRangeMax)
00268                         pz += sZRand * 1.0/data->mRangeMax;
00269 
00270                         // TODO: outlier rejection for short readings
00271 
00272                         assert(pz <= 1.0);
00273                         assert(pz >= 0.0);
00274 
00275                         p += pz*pz*pz;
00276                 }
00277                 sample->weight *= p;
00278                 totalWeight += sample->weight;
00279         }
00280         return totalWeight;
00281 }
00282 
00283 double SelfLocalizer::calculateLikelihoodFieldModel(LaserData *data, pf_sample_set_t* set)
00284 {
00285         int i, step;
00286         double obsRange, obsBearing;
00287         double totalWeight = 0.0;
00288         pf_sample_t* sample;
00289         pf_vector_t pose;
00290         pf_vector_t hit;
00291 
00292         // Compute the sample weights
00293         for (int j = 0; j < set->sample_count; j++)
00294         {
00295                 sample = set->samples + j;
00296                 pose = sample->pose;
00297 
00298                 // Take into account the laser pose relative to the robot
00299                 pose = pf_vector_coord_add(sLaserPose, pose);
00300 
00301                 // Pre-compute a couple of things
00302                 double zHitDenom = 2.0 * sSigmaHit * sSigmaHit;
00303                 double zRandMult = 1.0 / data->mRangeMax;
00304                 double p = 1.0;
00305 
00306                 step = (data->mRangeCount - 1) / (sMaxBeams - 1);
00307                 for (i = 0; i < data->mRangeCount; i += step)
00308                 {
00309                         obsRange = data->mRanges[i][0];
00310                         obsBearing = data->mRanges[i][1];
00311 
00312                         // This model ignores max range readings
00313                         if(obsRange >= data->mRangeMax)
00314                                 continue;
00315 
00316                         double z = 0.0;
00317                         double pz = 0.0;
00318 
00319                         // Compute the endpoint of the beam
00320                         hit.v[0] = pose.v[0] + obsRange * cos(pose.v[2] + obsBearing);
00321                         hit.v[1] = pose.v[1] + obsRange * sin(pose.v[2] + obsBearing);
00322 
00323                         // Convert to map grid coords.
00324                         int mi = MAP_GXWX(sMap, hit.v[0]);
00325                         int mj = MAP_GYWY(sMap, hit.v[1]);
00326 
00327                         // Part 1: Get distance from the hit to closest obstacle.
00328                         // Off-map penalized as max distance
00329                         if(!MAP_VALID(sMap, mi, mj))
00330                                 z = sMap->max_occ_dist;
00331                         else
00332                                 z = sMap->cells[MAP_INDEX(sMap,mi,mj)].occ_dist;
00333 
00334                         // Gaussian model
00335                         // NOTE: this should have a normalization of 1/(sqrt(2pi)*sigma)
00336                         pz += sZHit * exp(-(z * z) / zHitDenom);
00337 
00338                         // Part 2: random measurements
00339                         pz += sZRand * zRandMult;
00340 
00341                         // TODO: outlier rejection for short readings
00342 
00343                         if(pz < 0.0 || pz > 1.0)
00344                                 ROS_WARN("Value pz = %.2f, but it should be in range 0..1", pz);
00345 
00346                         // here we have an ad-hoc weighting scheme for combining beam probs
00347                         // works well, though...
00348                         p += (pz*pz*pz);
00349                 }
00350 
00351                 sample->weight *= p;
00352                 totalWeight += sample->weight;
00353         }
00354 
00355         return(totalWeight);
00356 }
00357 
00358 bool SelfLocalizer::initialize()
00359 {
00360         // Create the particle filter
00361         mParticleFilter = pf_alloc(     mMinParticles, mMaxParticles, 
00362                                                                 mAlphaSlow, mAlphaFast,
00363                                                                 SelfLocalizer::distributeParticles,
00364                                                                 (void*) sMap);
00365                 
00366         pf_sample_set_t* set = mParticleFilter->sets + mParticleFilter->current_set;
00367         ROS_INFO("Initialized PF with %d samples.", set->sample_count); 
00368         mParticleFilter->pop_err = mPopulationErr;
00369         mParticleFilter->pop_z = mPopulationZ;
00370         
00371         // Distribute particles uniformly in the free space of the map
00372         pf_init_model(mParticleFilter, SelfLocalizer::distributeParticles, sMap);
00373         
00374         // Get the laser pose on the robot
00375         tf::StampedTransform laserPose;
00376         mTransformListener.waitForTransform(mRobotFrame, mLaserFrame, ros::Time(0), ros::Duration(5.0));
00377         
00378         try
00379         {
00380                 mTransformListener.lookupTransform(mRobotFrame, mLaserFrame, ros::Time(0), laserPose);
00381         }
00382         catch(tf::TransformException e)
00383         {
00384                 return false;
00385         }
00386         
00387         sLaserPose.v[0] = laserPose.getOrigin().getX();
00388         sLaserPose.v[1] = laserPose.getOrigin().getY();
00389         sLaserPose.v[2] = tf::getYaw(laserPose.getRotation());
00390         
00391         return true;
00392 }
00393 
00394 void SelfLocalizer::process(const sensor_msgs::LaserScan::ConstPtr& scan)
00395 {
00396         // Ignore all scans unless we got a map
00397         if(sMap == NULL) return;
00398         
00399         // Get the odometry pose from TF. (We use RobotFrame here instead of LaserFrame, 
00400         // so the motion model of the particle filter can work correctly.)
00401         tf::StampedTransform tfPose;
00402         try
00403         {
00404                 mTransformListener.lookupTransform(mOdometryFrame, mRobotFrame, scan->header.stamp, tfPose);
00405         }
00406         catch(tf::TransformException e)
00407         {
00408                 try
00409                 {
00410                         mTransformListener.lookupTransform(mOdometryFrame, mRobotFrame, ros::Time(0), tfPose);
00411                 }
00412                 catch(tf::TransformException e)
00413                 {
00414                         ROS_WARN("Failed to compute odometry pose, skipping scan (%s)", e.what());
00415                         return;
00416                 }
00417         }
00418         
00419         if(!mFirstScanReceived)
00420         {
00421                 // Process the first laser scan after initialization
00422                 mLastPose = tfPose;
00423                 mFirstScanReceived = true;
00424                 mProcessedScans = 0;
00425         }
00426         
00427         // Update motion model with odometry data
00428         OdometryData odom(tfPose, mLastPose);
00429 
00430         double dist = odom.mDeltaX * odom.mDeltaX + odom.mDeltaY * odom.mDeltaY;
00431         if(dist < mMinTranslation && fabs(odom.mDeltaTheta) < mMinRotation)
00432                 return;
00433 
00434         mProcessedScans++;
00435         pf_update_action(mParticleFilter, mActionModelFunction, (void*) &odom);
00436         mLastPose = tfPose;
00437 
00438         // Update sensor model with laser data
00439         LaserData laser(scan);
00440         pf_update_sensor(mParticleFilter, mSensorModelFunction, (void*) &laser);
00441 
00442         // Do the resampling step
00443         pf_update_resample(mParticleFilter);
00444         
00445         // Create the map-to-odometry transform
00446         tf::Transform map2robot = getBestPose();
00447         tf::Stamped<tf::Pose> odom2map;
00448         try
00449         {
00450                 tf::Stamped<tf::Pose> robot2map;
00451                 robot2map.setData(map2robot.inverse());
00452                 robot2map.stamp_ = scan->header.stamp;
00453                 robot2map.frame_id_ = mRobotFrame;
00454 
00455                 mTransformListener.transformPose(mOdometryFrame, robot2map, odom2map);
00456                 mMapToOdometry = odom2map.inverse();
00457         }
00458         catch(tf::TransformException)
00459         {
00460                 ROS_WARN("Failed to subtract base to odom transform");
00461         }
00462 
00463         // Publish the particles for visualization
00464         publishParticleCloud();
00465 }
00466 
00467 void SelfLocalizer::convertMap( const nav_msgs::OccupancyGrid& map_msg )
00468 {
00469         map_t* map = map_alloc();
00470         ROS_ASSERT(map);
00471 
00472         map->size_x = map_msg.info.width;
00473         map->size_y = map_msg.info.height;
00474         map->scale = map_msg.info.resolution;
00475         map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
00476         map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
00477 
00478         // Convert to pf-internal format
00479         map->cells = (map_cell_t*)malloc(sizeof(map_cell_t)*map->size_x*map->size_y);
00480         ROS_ASSERT(map->cells);
00481         for(int i = 0; i < map->size_x * map->size_y; i++)
00482         {
00483                 if(map_msg.data[i] == 0)
00484                         map->cells[i].occ_state = -1;
00485                 else if(map_msg.data[i] == 100)
00486                         map->cells[i].occ_state = +1;
00487                 else
00488                         map->cells[i].occ_state = 0;
00489         }
00490 
00491         if(sMap)        
00492                 map_free(sMap);
00493                 
00494         sMap = map;
00495         if(mLaserModelType == 2)
00496         {
00497                 ROS_INFO("Initializing likelihood field model. This can take some time on large maps...");
00498                 map_update_cspace(sMap, sLikelihoodMaxDist);
00499         }
00500 }
00501 
00502 double SelfLocalizer::getCovariance()
00503 {
00504         pf_sample_set_t* set = mParticleFilter->sets + mParticleFilter->current_set;
00505         double max = set->cov.m[0][0];
00506         if(set->cov.m[1][1] > max) max = set->cov.m[1][1];
00507         if(set->cov.m[2][2] > max) max = set->cov.m[2][2];
00508         return max;
00509 }
00510 
00511 tf::Transform SelfLocalizer::getBestPose()
00512 {
00513         pf_vector_t pose;
00514         pose.v[0] = 0;
00515         pose.v[1] = 0;
00516         pose.v[2] = 0;
00517         pf_sample_set_t* set = mParticleFilter->sets + mParticleFilter->current_set;
00518         
00519         // Wow, is this really the only way to do this !?!
00520         double max_weight = 0.0;
00521         
00522         for(int i = 0; i < set->cluster_count; i++)
00523         {
00524                 double weight;
00525                 pf_vector_t pose_mean;
00526                 pf_matrix_t pose_cov;
00527                 if (!pf_get_cluster_stats(mParticleFilter, i, &weight, &pose_mean, &pose_cov))
00528                 {
00529                         ROS_ERROR("Couldn't get stats on cluster %d", i);
00530                         break;
00531                 }
00532 
00533                 if(weight > max_weight)
00534                 {
00535                         max_weight = weight;
00536                         pose = pose_mean;
00537                 }
00538         }
00539 
00540         if(max_weight > 0.0)
00541         {
00542                 ROS_INFO("Determined pose at: %.3f %.3f %.3f", pose.v[0], pose.v[1], pose.v[2]);
00543         }else
00544         {
00545                 ROS_ERROR("Could not get pose from particle filter!");
00546         }
00547 //      pose = pf_vector_coord_sub(pose, sLaserPose);
00548 //      return pose;
00549         
00550         tf::Transform map2robot;
00551         map2robot.setOrigin(tf::Vector3(pose.v[0], pose.v[1], 0));
00552         map2robot.setRotation(tf::createQuaternionFromYaw(pose.v[2]));
00553 
00554         return map2robot;
00555 }
00556 
00557 void SelfLocalizer::publishParticleCloud()
00558 {
00559         if(!mPublishParticles) return;
00560         
00561         pf_sample_set_t* set = mParticleFilter->sets + mParticleFilter->current_set;
00562         
00563         geometry_msgs::PoseArray cloud_msg;
00564         cloud_msg.header.stamp = ros::Time::now();
00565         cloud_msg.header.frame_id = mMapFrame.c_str();
00566         cloud_msg.poses.resize(set->sample_count);
00567         for(int i = 0; i < set->sample_count; i++)
00568         {
00569                 double x = set->samples[i].pose.v[0];
00570                 double y = set->samples[i].pose.v[1];
00571                 double yaw = set->samples[i].pose.v[2];
00572                 tf::Pose pose(tf::createQuaternionFromYaw(yaw), tf::Vector3(x, y, 0));
00573                 tf::poseTFToMsg(pose, cloud_msg.poses[i]);
00574 
00575                 // Check content of the message because sometimes NaN values occur and therefore visualization in rviz breaks
00576                 geometry_msgs::Pose pose_check = cloud_msg.poses.at(i);
00577                 geometry_msgs::Point pt = pose_check.position;
00578                 if(isNaN(pt.x))
00579                         ROS_WARN("NaN occured at pt.x before publishing particle cloud...");
00580                 if(isNaN(pt.y))
00581                         ROS_WARN("NaN occured at pt.y before publishing particle cloud...");
00582                 if(isNaN(pt.z))
00583                         ROS_WARN("NaN occured at pt.z before publishing particle cloud...");
00584                 geometry_msgs::Quaternion ori = pose_check.orientation;
00585                 if(isNaN(ori.x)){
00586                         ROS_WARN("NaN occured at ori.x before publishing particle cloud, setting it to zero (original x:%f y:%f yaw:%f) ...", set->samples[i].pose.v[0], set->samples[i].pose.v[1], set->samples[i].pose.v[2]);
00587                         cloud_msg.poses.at(i).orientation.x = 0;
00588                 }
00589                 if(isNaN(ori.y)){
00590                         ROS_WARN("NaN occured at ori.y before publishing particle cloud, setting it to zero (original x:%f y:%f yaw:%f) ...", set->samples[i].pose.v[0], set->samples[i].pose.v[1], set->samples[i].pose.v[2]);
00591                         cloud_msg.poses.at(i).orientation.y = 0;
00592                 }
00593                 if(isNaN(ori.z))
00594                         ROS_WARN("NaN occured at ori.z before publishing particle cloud ...");
00595                 if(isNaN(ori.w))
00596                         ROS_WARN("NaN occured at ori.w before publishing particle cloud ...");
00597 
00598         }
00599         mParticlePublisher.publish(cloud_msg);
00600 }


self_localizer
Author(s): Sebastian Kasperski
autogenerated on Fri Feb 21 2014 12:26:53