$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/humanoid_localization/src/HumanoidLocalization.cpp $ 00002 // SVN $Id: HumanoidLocalization.cpp 3976 2013-02-26 10:40:04Z hornunga@informatik.uni-freiburg.de $ 00003 00004 /* 00005 * 6D localization for humanoid robots 00006 * 00007 * Copyright 2009-2012 Armin Hornung, University of Freiburg 00008 * http://www.ros.org/wiki/humanoid_localization 00009 * 00010 * 00011 * This program is free software: you can redistribute it and/or modify 00012 * it under the terms of the GNU General Public License as published by 00013 * the Free Software Foundation, version 3. 00014 * 00015 * This program is distributed in the hope that it will be useful, 00016 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00017 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00018 * GNU General Public License for more details. 00019 * 00020 * You should have received a copy of the GNU General Public License 00021 * along with this program. If not, see <http://www.gnu.org/licenses/>. 00022 */ 00023 00024 #include <humanoid_localization/HumanoidLocalization.h> 00025 #include <iostream> 00026 #include <pcl/keypoints/uniform_sampling.h> 00027 00028 // simple timing benchmark output 00029 #define _BENCH_TIME 0 00030 00031 namespace humanoid_localization{ 00032 HumanoidLocalization::HumanoidLocalization(unsigned randomSeed) 00033 : 00034 m_rngEngine(randomSeed), 00035 m_rngNormal(m_rngEngine, NormalDistributionT(0.0, 1.0)), 00036 m_rngUniform(m_rngEngine, UniformDistributionT(0.0, 1.0)), 00037 m_nh(),m_privateNh("~"), 00038 m_odomFrameId("odom"), m_baseFrameId("torso"), m_baseFootprintId("base_footprint"), m_globalFrameId("/map"), 00039 m_useRaycasting(true), m_initFromTruepose(false), m_numParticles(500), 00040 m_numSensorBeams(48), 00041 m_sensorSampleDist(0.2), 00042 m_nEffFactor(1.0), m_minParticleWeight(0.0), 00043 m_bestParticleIdx(-1), m_lastIMUMsgBuffer(5), 00044 m_bestParticleAsMean(true), 00045 m_receivedSensorData(false), m_initialized(false), m_initGlobal(false), m_paused(false), 00046 m_syncedTruepose(false), 00047 m_observationThresholdTrans(0.1), m_observationThresholdRot(M_PI/6), 00048 m_observationThresholdHeadYawRot(0.1), m_observationThresholdHeadPitchRot(0.1), 00049 m_temporalSamplingRange(0.1), m_transformTolerance(0.1), 00050 m_headYawRotationLastScan(0.0), m_headPitchRotationLastScan(0.0), 00051 m_useIMU(false), 00052 m_constrainMotionZ (false), m_constrainMotionRP(false) 00053 { 00054 00055 // raycasting or endpoint model? 00056 m_privateNh.param("use_raycasting", m_useRaycasting, m_useRaycasting); 00057 00058 m_privateNh.param("odom_frame_id", m_odomFrameId, m_odomFrameId); 00059 m_privateNh.param("base_frame_id", m_baseFrameId, m_baseFrameId); 00060 m_privateNh.param("base_footprint_id", m_baseFootprintId, m_baseFootprintId); 00061 m_privateNh.param("global_frame_id", m_globalFrameId, m_globalFrameId); 00062 m_privateNh.param("init_from_truepose", m_initFromTruepose, m_initFromTruepose); 00063 m_privateNh.param("init_global", m_initGlobal, m_initGlobal); 00064 m_privateNh.param("best_particle_as_mean", m_bestParticleAsMean, m_bestParticleAsMean); 00065 m_privateNh.param("num_particles", m_numParticles, m_numParticles); 00066 m_privateNh.param("neff_factor", m_nEffFactor, m_nEffFactor); 00067 m_privateNh.param("min_particle_weight", m_minParticleWeight, m_minParticleWeight); 00068 00069 m_privateNh.param("initial_pose/x", m_initPose(0), 0.0); 00070 m_privateNh.param("initial_pose/y", m_initPose(1), 0.0); 00071 m_privateNh.param("initial_pose/z", m_initPose(2), 0.32); // hip height when standing 00072 m_privateNh.param("initial_pose/roll", m_initPose(3), 0.0); 00073 m_privateNh.param("initial_pose/pitch", m_initPose(4), 0.0); 00074 m_privateNh.param("initial_pose/yaw", m_initPose(5), 0.0); 00075 m_privateNh.param("initial_pose_real_zrp", m_initPoseRealZRP, false); 00076 00077 m_privateNh.param("initial_std/x", m_initNoiseStd(0), 0.1); // 0.1 00078 m_privateNh.param("initial_std/y", m_initNoiseStd(1), 0.1); // 0.1 00079 m_privateNh.param("initial_std/z", m_initNoiseStd(2), 0.02); // 0.02 00080 m_privateNh.param("initial_std/roll", m_initNoiseStd(3), 0.04); // 0.04 00081 m_privateNh.param("initial_std/pitch", m_initNoiseStd(4), 0.04); // 0.04 00082 m_privateNh.param("initial_std_yaw", m_initNoiseStd(5), M_PI/12); // M_PI/12 00083 00084 // laser observation model parameters: 00085 m_privateNh.param("num_sensor_beams", m_numSensorBeams, m_numSensorBeams); 00086 m_privateNh.param("sensor_sampling_dist", m_sensorSampleDist, m_sensorSampleDist); 00087 m_privateNh.param("max_range", m_filterMaxRange, 30.0); 00088 m_privateNh.param("min_range", m_filterMinRange, 0.05); 00089 ROS_DEBUG("Using a range filter of %f to %f", m_filterMinRange, m_filterMaxRange); 00090 00091 m_privateNh.param("update_min_trans", m_observationThresholdTrans, m_observationThresholdTrans); 00092 m_privateNh.param("update_min_rot", m_observationThresholdRot, m_observationThresholdRot); 00093 m_privateNh.param("update_min_head_yaw", m_observationThresholdHeadYawRot, m_observationThresholdHeadYawRot); 00094 m_privateNh.param("update_min_head_pitch", m_observationThresholdHeadPitchRot, m_observationThresholdHeadPitchRot); 00095 m_privateNh.param("temporal_sampling_range", m_temporalSamplingRange, m_temporalSamplingRange); 00096 m_privateNh.param("transform_tolerance", m_transformTolerance, m_transformTolerance); 00097 00098 m_privateNh.param("use_imu", m_useIMU, m_useIMU); 00099 m_privateNh.param("constrain_motion_z", m_constrainMotionZ, m_constrainMotionZ); 00100 m_privateNh.param("constrain_motion_rp", m_constrainMotionRP, m_constrainMotionRP); 00101 00102 m_motionModel = boost::shared_ptr<MotionModel>(new MotionModel(&m_privateNh, &m_rngEngine, &m_tfListener, m_odomFrameId, m_baseFrameId)); 00103 00104 if (m_useRaycasting){ 00105 m_mapModel = boost::shared_ptr<MapModel>(new OccupancyMap(&m_privateNh)); 00106 m_observationModel = boost::shared_ptr<ObservationModel>(new RaycastingModel(&m_privateNh, m_mapModel, &m_rngEngine)); 00107 } else{ 00108 #ifndef SKIP_ENDPOINT_MODEL 00109 //m_mapModel = boost::shared_ptr<MapModel>(new DistanceMap(&m_privateNh)); 00110 m_mapModel = boost::shared_ptr<MapModel>(new OccupancyMap(&m_privateNh)); 00111 m_observationModel = boost::shared_ptr<ObservationModel>(new EndpointModel(&m_privateNh, m_mapModel, &m_rngEngine)); 00112 #else 00113 ROS_FATAL("EndpointModel not compiled due to missing dynamicEDT3D"); 00114 exit(-1); 00115 #endif 00116 } 00117 00118 00119 m_particles.resize(m_numParticles); 00120 m_poseArray.poses.resize(m_numParticles); 00121 m_poseArray.header.frame_id = m_globalFrameId; 00122 m_tfListener.clear(); 00123 00124 00125 // publishers can be advertised first, before needed: 00126 m_posePub = m_nh.advertise<geometry_msgs::PoseWithCovarianceStamped>("pose", 10); 00127 m_poseEvalPub = m_nh.advertise<geometry_msgs::PoseWithCovarianceStamped>("pose_eval", 10); 00128 m_poseOdomPub = m_privateNh.advertise<geometry_msgs::PoseStamped>("pose_odom_sync", 10); 00129 m_poseArrayPub = m_privateNh.advertise<geometry_msgs::PoseArray>("particlecloud", 10); 00130 m_bestPosePub = m_privateNh.advertise<geometry_msgs::PoseArray>("best_particle", 10); 00131 m_nEffPub = m_privateNh.advertise<std_msgs::Float32>("n_eff", 10); 00132 m_filteredPointCloudPub = m_privateNh.advertise<sensor_msgs::PointCloud2>("filtered_cloud", 1); 00133 00134 00135 reset(); 00136 00137 // ROS subscriptions last: 00138 m_globalLocSrv = m_nh.advertiseService("global_localization", &HumanoidLocalization::globalLocalizationCallback, this); 00139 00140 // subscription on laser, tf message filter 00141 m_laserSub = new message_filters::Subscriber<sensor_msgs::LaserScan>(m_nh, "scan", 100); 00142 m_laserFilter = new tf::MessageFilter<sensor_msgs::LaserScan>(*m_laserSub, m_tfListener, m_odomFrameId, 100); 00143 m_laserFilter->registerCallback(boost::bind(&HumanoidLocalization::laserCallback, this, _1)); 00144 00145 // subscription on point cloud, tf message filter 00146 m_pointCloudSub = new message_filters::Subscriber<PointCloud>(m_nh, "point_cloud", 100); 00147 m_pointCloudFilter = new tf::MessageFilter< PointCloud >(*m_pointCloudSub, m_tfListener, m_odomFrameId, 100); 00148 m_pointCloudFilter->registerCallback(boost::bind(&HumanoidLocalization::pointCloudCallback, this, _1)); 00149 00150 // subscription on init pose, tf message filter 00151 m_initPoseSub = new message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>(m_nh, "initialpose", 2); 00152 m_initPoseFilter = new tf::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>(*m_initPoseSub, m_tfListener, m_globalFrameId, 2); 00153 m_initPoseFilter->registerCallback(boost::bind(&HumanoidLocalization::initPoseCallback, this, _1)); 00154 00155 00156 m_pauseIntegrationSub = m_privateNh.subscribe("pause_localization", 1, &HumanoidLocalization::pauseLocalizationCallback, this); 00157 m_pauseLocSrv = m_privateNh.advertiseService("pause_localization_srv", &HumanoidLocalization::pauseLocalizationSrvCallback, this); 00158 m_resumeLocSrv = m_privateNh.advertiseService("resume_localization_srv", &HumanoidLocalization::resumeLocalizationSrvCallback, this); 00159 00160 if (m_useIMU) 00161 m_imuSub = m_nh.subscribe("imu", 5, &HumanoidLocalization::imuCallback, this); 00162 00163 ROS_INFO("NaoLocalization initialized with %d particles.", m_numParticles); 00164 } 00165 00166 HumanoidLocalization::~HumanoidLocalization() { 00167 00168 delete m_laserFilter; 00169 delete m_laserSub; 00170 00171 delete m_pointCloudFilter; 00172 delete m_pointCloudSub; 00173 00174 delete m_initPoseFilter; 00175 delete m_initPoseSub; 00176 00177 } 00178 00179 void HumanoidLocalization::reset(){ 00180 00181 #if defined(_BENCH_TIME) 00182 ros::WallTime startTime = ros::WallTime::now(); 00183 #endif 00184 00185 if (m_initGlobal){ 00186 this->initGlobal(); 00187 } else { 00188 geometry_msgs::PoseWithCovarianceStampedPtr posePtr(new geometry_msgs::PoseWithCovarianceStamped()); 00189 00190 if (m_initFromTruepose){ // useful for evaluation, when ground truth available: 00191 geometry_msgs::PoseStamped truePose; 00192 tf::Stamped<tf::Pose> truePoseTF; 00193 tf::Stamped<tf::Pose> ident (tf::Transform(tf::createIdentityQuaternion(), tf::Vector3(0,0,0)), ros::Time::now(), "/torso_real"); // TODO: param 00194 00195 ros::Time lookupTime = ros::Time::now(); 00196 while(m_nh.ok() && !m_tfListener.waitForTransform(m_globalFrameId, ident.frame_id_, lookupTime, ros::Duration(1.0))){ 00197 ROS_WARN("Waiting for transform %s --> %s for ground truth initialization failed, trying again...", m_globalFrameId.c_str(), ident.frame_id_.c_str()); 00198 lookupTime = ros::Time::now(); 00199 } 00200 ident.stamp_ = lookupTime; 00201 00202 m_tfListener.transformPose(m_globalFrameId, ident, truePoseTF); 00203 tf::poseStampedTFToMsg(truePoseTF, truePose); 00204 tf::poseTFToMsg(truePoseTF, posePtr->pose.pose); 00205 posePtr->header = truePose.header; 00206 00207 00208 // initial covariance acc. to params 00209 for(int j=0; j < 6; ++j){ 00210 for (int i = 0; i < 6; ++i){ 00211 if (i == j) 00212 posePtr->pose.covariance.at(i*6 +j) = m_initNoiseStd(i) * m_initNoiseStd(i); 00213 else 00214 posePtr->pose.covariance.at(i*6 +j) = 0.0; 00215 } 00216 } 00217 00218 } else{ 00219 posePtr.reset(new geometry_msgs::PoseWithCovarianceStamped()); 00220 for (int i = 0; i < 6; ++i){ 00221 posePtr->pose.covariance.at(i*6 +i) = m_initNoiseStd(i) * m_initNoiseStd(i); 00222 } 00223 00224 posePtr->pose.pose.position.x = m_initPose(0); 00225 posePtr->pose.pose.position.y = m_initPose(1); 00226 double roll, pitch; 00227 if(m_initPoseRealZRP) { 00228 // Get latest pose height 00229 tf::Stamped<tf::Pose> lastOdomPose; 00230 double poseHeight; 00231 if(m_motionModel->getLastOdomPose(lastOdomPose) && 00232 lookupPoseHeight(lastOdomPose.stamp_, poseHeight)) { 00233 posePtr->pose.pose.position.z = poseHeight; 00234 } else { 00235 ROS_WARN("Could not determine current pose height, falling back to init_pose_z"); 00236 posePtr->pose.pose.position.z = m_initPose(2); 00237 } 00238 00239 // Get latest roll and pitch 00240 if(!m_lastIMUMsgBuffer.empty()) { 00241 getRP(m_lastIMUMsgBuffer.back().orientation, roll, pitch); 00242 } else { 00243 ROS_WARN("Could not determine current roll and pitch, falling back to init_pose_{roll,pitch}"); 00244 roll = m_initPose(3); 00245 pitch = m_initPose(4); 00246 } 00247 } else { 00248 // Use pose height, roll and pitch from init_pose_{z,roll,pitch} parameters 00249 posePtr->pose.pose.position.z = m_initPose(2); 00250 roll = m_initPose(3); 00251 pitch = m_initPose(4); 00252 } 00253 00254 tf::Quaternion quat; 00255 quat.setRPY(roll, pitch, m_initPose(5)); 00256 tf::quaternionTFToMsg(quat, posePtr->pose.pose.orientation); 00257 00258 } 00259 00260 this->initPoseCallback(posePtr); 00261 00262 } 00263 00264 00265 00266 00267 00268 #if defined(_BENCH_TIME) 00269 double dt = (ros::WallTime::now() - startTime).toSec(); 00270 ROS_INFO_STREAM("Initialization of "<< m_numParticles << " particles took " 00271 << dt << "s (="<<dt/m_numParticles<<"s/particle)"); 00272 #endif 00273 00274 00275 } 00276 00277 00278 void HumanoidLocalization::laserCallback(const sensor_msgs::LaserScanConstPtr& msg){ 00279 ROS_DEBUG("Laser received (time: %f)", msg->header.stamp.toSec()); 00280 00281 if (!m_initialized){ 00282 ROS_WARN("Loclization not initialized yet, skipping laser callback."); 00283 return; 00284 } 00285 00286 double timediff = (msg->header.stamp - m_lastLaserTime).toSec(); 00287 if (m_receivedSensorData && timediff < 0){ 00288 ROS_WARN("Ignoring received laser data that is %f s older than previous data!", timediff); 00289 return; 00290 } 00291 00292 00294 tf::Stamped<tf::Pose> odomPose; 00295 // check if odometry available, skip scan if not. 00296 if (!m_motionModel->lookupOdomPose(msg->header.stamp, odomPose)) 00297 return; 00298 00299 00300 bool sensor_integrated = false; 00301 if (!m_paused && (!m_receivedSensorData || isAboveMotionThreshold(odomPose))) { 00302 00303 // convert laser to point cloud first: 00304 PointCloud pc_filtered; 00305 std::vector<float> laserRangesSparse; 00306 prepareLaserPointCloud(msg, pc_filtered, laserRangesSparse); 00307 00308 sensor_integrated = localizeWithMeasurement(pc_filtered, laserRangesSparse, msg->range_max); 00309 00310 } 00311 00312 if(!sensor_integrated){ // no laser integration: propagate particles forward by full interval 00313 00314 // relative odom transform to last odomPose 00315 tf::Transform odomTransform = m_motionModel->computeOdomTransform(odomPose); 00316 m_motionModel->applyOdomTransform(m_particles, odomTransform); 00317 constrainMotion(odomPose); 00318 } 00319 else 00320 { 00321 m_lastLocalizedPose = odomPose; 00322 } 00323 00324 m_motionModel->storeOdomPose(odomPose); 00325 publishPoseEstimate(msg->header.stamp, sensor_integrated); 00326 m_lastLaserTime = msg->header.stamp; 00327 } 00328 00329 void HumanoidLocalization::constrainMotion(const tf::Pose& odomPose){ 00330 // skip if nothing to do: 00331 if (!m_constrainMotionZ && !m_constrainMotionRP) 00332 return; 00333 00334 // reset z according to current odomPose: 00335 double z = odomPose.getOrigin().getZ(); 00336 double odomRoll, odomPitch, uselessYaw; 00337 odomPose.getBasis().getRPY(odomRoll, odomPitch, uselessYaw); 00338 00339 #pragma omp parallel for 00340 for (unsigned i=0; i < m_particles.size(); ++i){ 00341 if (m_constrainMotionZ){ 00342 tf::Vector3 pos = m_particles[i].pose.getOrigin(); 00343 double floor_z = m_mapModel->getFloorHeight(m_particles[i].pose); 00344 pos.setZ(z+floor_z); 00345 m_particles[i].pose.setOrigin(pos); 00346 } 00347 00348 if (m_constrainMotionRP){ 00349 double yaw = tf::getYaw(m_particles[i].pose.getRotation()); 00350 m_particles[i].pose.setRotation(tf::createQuaternionFromRPY(odomRoll, odomPitch, yaw)); 00351 00352 } 00353 } 00354 } 00355 00356 bool HumanoidLocalization::isAboveMotionThreshold(const tf::Pose& odomPose){ 00357 tf::Transform odomTransform = m_lastLocalizedPose.inverse() * odomPose; 00358 00359 double yaw, pitch, roll; 00360 odomTransform.getBasis().getRPY(roll, pitch, yaw); 00361 00362 return (odomTransform.getOrigin().length() >= m_observationThresholdTrans 00363 || std::abs(yaw) >= m_observationThresholdRot); 00364 } 00365 00366 bool HumanoidLocalization::localizeWithMeasurement(const PointCloud& pc_filtered, const std::vector<float>& ranges, double max_range){ 00367 ros::WallTime startTime = ros::WallTime::now(); 00368 ros::Time t = pc_filtered.header.stamp; 00369 // apply motion model with temporal sampling: 00370 m_motionModel->applyOdomTransformTemporal(m_particles, t, m_temporalSamplingRange); 00371 00372 // constrain to ground plane, if desired: 00373 tf::Stamped<tf::Transform> odomPose; 00374 assert(m_motionModel->lookupOdomPose(t, odomPose)); 00375 constrainMotion(odomPose); 00376 00377 // transformation from torso frame to sensor 00378 // this takes the latest tf, assumes that torso to sensor did not change over temp. sampling! 00379 tf::StampedTransform localSensorFrame; 00380 if (!m_motionModel->lookupLocalTransform(pc_filtered.header.frame_id, t, localSensorFrame)) 00381 return false; 00382 00383 tf::Transform torsoToSensor(localSensorFrame.inverse()); 00384 00385 //### Particles in log-form from here... 00386 toLogForm(); 00387 00388 // skip pose integration if z, roll and pitch constrained to floor by odometry 00389 if (!(m_constrainMotionRP && m_constrainMotionZ)){ 00390 bool imuMsgOk = false; 00391 double angleX, angleY; 00392 if(m_useIMU) { 00393 ros::Time imuStamp; 00394 imuMsgOk = getImuMsg(t, imuStamp, angleX, angleY); 00395 } else { 00396 tf::Stamped<tf::Pose> lastOdomPose; 00397 if(m_motionModel->lookupOdomPose(t, lastOdomPose)) { 00398 double dropyaw; 00399 lastOdomPose.getBasis().getRPY(angleX, angleY, dropyaw); 00400 imuMsgOk = true; 00401 } 00402 } 00403 00404 tf::StampedTransform footprintToTorso; 00405 // integrated pose (z, roll, pitch) meas. only if data OK: 00406 if(imuMsgOk) { 00407 if (!m_motionModel->lookupLocalTransform(m_baseFootprintId, t, footprintToTorso)) { 00408 ROS_WARN("Could not obtain pose height in localization, skipping Pose integration"); 00409 } else { 00410 m_observationModel->integratePoseMeasurement(m_particles, angleX, angleY, footprintToTorso); 00411 } 00412 } else { 00413 ROS_WARN("Could not obtain roll and pitch measurement, skipping Pose integration"); 00414 } 00415 } 00416 00417 m_filteredPointCloudPub.publish(pc_filtered); 00418 m_observationModel->integrateMeasurement(m_particles, pc_filtered, ranges, max_range, torsoToSensor); 00419 00420 // TODO: verify poses before measurements, ignore particles then 00421 m_mapModel->verifyPoses(m_particles); 00422 00423 // normalize weights and transform back from log: 00424 normalizeWeights(); 00425 //### Particles back in regular form now 00426 00427 double nEffParticles = nEff(); 00428 00429 std_msgs::Float32 nEffMsg; 00430 nEffMsg.data = nEffParticles; 00431 m_nEffPub.publish(nEffMsg); 00432 00433 if (nEffParticles <= m_nEffFactor*m_particles.size()){ // selective resampling 00434 ROS_INFO("Resampling, nEff=%f, numParticles=%zd", nEffParticles, m_particles.size()); 00435 resample(); 00436 } else { 00437 ROS_INFO("Skipped resampling, nEff=%f, numParticles=%zd", nEffParticles, m_particles.size()); 00438 } 00439 00440 m_receivedSensorData = true; 00441 00442 double dt = (ros::WallTime::now() - startTime).toSec(); 00443 ROS_INFO_STREAM("Observations for "<< m_numParticles << " particles took " 00444 << dt << "s (="<<dt/m_numParticles<<"s/particle)"); 00445 00446 return true; 00447 } 00448 00449 void HumanoidLocalization::prepareLaserPointCloud(const sensor_msgs::LaserScanConstPtr& laser, PointCloud& pc, std::vector<float>& ranges) const{ 00450 unsigned numBeams = laser->ranges.size(); 00451 // skip every n-th scan: 00452 //unsigned step = computeBeamStep(numBeams); 00453 // build complete pointcloud: 00454 unsigned step = 1; 00455 00456 00457 00458 // prepare laser message: 00459 unsigned int numBeamsSkipped = 0; 00460 00461 // range_min of laser is also used to filter out wrong messages: 00462 double laserMin = std::max(double(laser->range_min), m_filterMinRange); 00463 00464 // (range_max readings stay, will be used in the sensor model) 00465 00466 ranges.reserve(m_numSensorBeams+3); 00467 00468 // build a point cloud 00469 pc.header = laser->header; 00470 pc.points.reserve(m_numSensorBeams+3); 00471 for (unsigned beam_idx = 0; beam_idx < numBeams; beam_idx+= step){ 00472 float range = laser->ranges[beam_idx]; 00473 if (range >= laserMin && range <= m_filterMaxRange){ 00474 double laserAngle = laser->angle_min + beam_idx * laser->angle_increment; 00475 tf::Transform laserAngleRotation(tf::Quaternion(tf::Vector3(0.0, 0.0, 1.0), laserAngle)); 00476 tf::Vector3 laserEndpointTrans(range, 0.0, 0.0); 00477 tf::Vector3 pt(laserAngleRotation * laserEndpointTrans); 00478 00479 pc.points.push_back(pcl::PointXYZ(pt.x(), pt.y(), pt.z())); 00480 ranges.push_back(range); 00481 00482 } else{ 00483 numBeamsSkipped++; 00484 } 00485 00486 } 00487 pc.height = 1; 00488 pc.width = pc.points.size(); 00489 pc.is_dense = true; 00490 00491 // uniform sampling: 00492 pcl::UniformSampling<pcl::PointXYZ> uniformSampling; 00493 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudPtr; 00494 cloudPtr.reset(new pcl::PointCloud<pcl::PointXYZ> (pc)); 00495 uniformSampling.setInputCloud(cloudPtr); 00496 uniformSampling.setRadiusSearch(m_sensorSampleDist); 00497 pcl::PointCloud<int> sampledIndices; 00498 uniformSampling.compute(sampledIndices); 00499 pcl::copyPointCloud(*cloudPtr, sampledIndices.points, pc); 00500 // adjust "ranges" array to contain the same points: 00501 std::vector<float> rangesSparse; 00502 rangesSparse.resize(sampledIndices.size()); 00503 for (size_t i = 0; i < rangesSparse.size(); ++i){ 00504 rangesSparse[i] = ranges[sampledIndices.points[i]]; 00505 } 00506 ranges = rangesSparse; 00507 ROS_INFO("Laser PointCloud subsampled: %zu from %zu (%u out of valid range)", pc.size(), cloudPtr->size(), numBeamsSkipped); 00508 } 00509 00510 int HumanoidLocalization::filterUniform( const PointCloud & cloud_in, PointCloud & cloud_out, int numSamples) const{ 00511 int numPoints = static_cast<int>(cloud_in.size() ); 00512 numSamples = std::min( numSamples, numPoints); 00513 std::vector<unsigned int> indices; 00514 indices.reserve( numPoints ); 00515 for (int i=0; i<numPoints; ++i) 00516 indices.push_back(i); 00517 random_shuffle ( indices.begin(), indices.end()); 00518 00519 cloud_out.reserve( cloud_out.size() + numSamples ); 00520 for ( int i = 0; i < numSamples; ++i) 00521 { 00522 cloud_out.push_back( cloud_in.at(indices[i])); 00523 } 00524 return numSamples; 00525 } 00526 00527 00528 00529 void HumanoidLocalization::filterGroundPlane(const PointCloud& pc, PointCloud& ground, PointCloud& nonground, double groundFilterDistance, double groundFilterAngle, double groundFilterPlaneDistance){ 00530 ground.header = pc.header; 00531 nonground.header = pc.header; 00532 00533 if (pc.size() < 50){ 00534 ROS_WARN("Pointcloud in OctomapServer too small, skipping ground plane extraction"); 00535 nonground = pc; 00536 } else { 00537 // plane detection for ground plane removal: 00538 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); 00539 pcl::PointIndices::Ptr inliers (new pcl::PointIndices); 00540 00541 // Create the segmentation object and set up: 00542 pcl::SACSegmentation<pcl::PointXYZ> seg; 00543 seg.setOptimizeCoefficients (true); 00544 // TODO: maybe a filtering based on the surface normals might be more robust / accurate? 00545 seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE); 00546 seg.setMethodType(pcl::SAC_RANSAC); 00547 seg.setMaxIterations(200); 00548 seg.setDistanceThreshold (groundFilterDistance); 00549 seg.setAxis(Eigen::Vector3f(0,0,1)); 00550 seg.setEpsAngle(groundFilterAngle); 00551 00552 00553 PointCloud cloud_filtered(pc); 00554 // Create the filtering object 00555 pcl::ExtractIndices<pcl::PointXYZ> extract; 00556 bool groundPlaneFound = false; 00557 00558 while(cloud_filtered.size() > 10 && !groundPlaneFound){ 00559 seg.setInputCloud(cloud_filtered.makeShared()); 00560 seg.segment (*inliers, *coefficients); 00561 if (inliers->indices.size () == 0){ 00562 ROS_INFO("PCL segmentation did not find any plane."); 00563 00564 break; 00565 } 00566 00567 extract.setInputCloud(cloud_filtered.makeShared()); 00568 extract.setIndices(inliers); 00569 00570 if (std::abs(coefficients->values.at(3)) < groundFilterPlaneDistance){ 00571 ROS_DEBUG("Ground plane found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(), 00572 coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3)); 00573 extract.setNegative (false); 00574 extract.filter (ground); 00575 00576 // remove ground points from full pointcloud: 00577 // workaround for PCL bug: 00578 if(inliers->indices.size() != cloud_filtered.size()){ 00579 extract.setNegative(true); 00580 PointCloud cloud_out; 00581 extract.filter(cloud_out); 00582 nonground += cloud_out; 00583 cloud_filtered = cloud_out; 00584 } 00585 00586 groundPlaneFound = true; 00587 } else{ 00588 ROS_DEBUG("Horizontal plane (not ground) found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(), 00589 coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3)); 00590 pcl::PointCloud<pcl::PointXYZ> cloud_out; 00591 extract.setNegative (false); 00592 extract.filter(cloud_out); 00593 nonground +=cloud_out; 00594 // debug 00595 // pcl::PCDWriter writer; 00596 // writer.write<pcl::PointXYZ>("nonground_plane.pcd",cloud_out, false); 00597 00598 // remove current plane from scan for next iteration: 00599 // workaround for PCL bug: 00600 if(inliers->indices.size() != cloud_filtered.size()){ 00601 extract.setNegative(true); 00602 cloud_out.points.clear(); 00603 extract.filter(cloud_out); 00604 cloud_filtered = cloud_out; 00605 } else{ 00606 cloud_filtered.points.clear(); 00607 } 00608 } 00609 00610 } 00611 // TODO: also do this if overall starting pointcloud too small? 00612 if (!groundPlaneFound){ // no plane found or remaining points too small 00613 ROS_WARN("No ground plane found in scan"); 00614 00615 // do a rough fitlering on height to prevent spurious obstacles 00616 pcl::PassThrough<pcl::PointXYZ> second_pass; 00617 second_pass.setFilterFieldName("z"); 00618 second_pass.setFilterLimits(-groundFilterPlaneDistance, groundFilterPlaneDistance); 00619 second_pass.setInputCloud(pc.makeShared()); 00620 second_pass.filter(ground); 00621 00622 second_pass.setFilterLimitsNegative (true); 00623 second_pass.filter(nonground); 00624 } 00625 00626 // debug: 00627 // pcl::PCDWriter writer; 00628 // if (pc_ground.size() > 0) 00629 // writer.write<pcl::PointXYZ>("ground.pcd",pc_ground, false); 00630 // if (pc_nonground.size() > 0) 00631 // writer.write<pcl::PointXYZ>("nonground.pcd",pc_nonground, false); 00632 } 00633 } 00634 00635 00636 00637 void HumanoidLocalization::prepareGeneralPointCloud(const PointCloud::ConstPtr & msg, PointCloud& pc, std::vector<float>& ranges) const{ 00638 00639 pc.clear(); 00640 // lookup Transfrom Sensor to BaseFootprint 00641 tf::StampedTransform sensorToBaseFootprint; 00642 try{ 00643 m_tfListener.waitForTransform(m_baseFootprintId, msg->header.frame_id, msg->header.stamp, ros::Duration(0.2)); 00644 m_tfListener.lookupTransform(m_baseFootprintId, msg->header.frame_id, msg->header.stamp, sensorToBaseFootprint); 00645 00646 00647 }catch(tf::TransformException& ex){ 00648 ROS_ERROR_STREAM( "Transform error for pointCloudCallback: " << ex.what() << ", quitting callback.\n"); 00649 return; 00650 } 00651 00652 /*** filter PointCloud and fill pc and ranges ***/ 00653 00654 // pass-through filter to get rid of near and far ranges 00655 pcl::PassThrough<pcl::PointXYZ> pass; 00656 pass.setInputCloud (msg); 00657 pass.setFilterFieldName ("z"); 00658 pass.setFilterLimits (m_filterMinRange, m_filterMaxRange); 00659 pass.filter (pc); 00660 00661 // identify ground plane 00662 PointCloud ground, nonground; 00663 double m_groundFilterDistance = 0.04; // TODO: Parameter 00664 double m_groundFilterAngle = 0.15; // TODO: Parameter 00665 double m_groundFilterPlaneDistance = 0.07; // TODO: Parameter 00666 bool m_filteredPointCloud = true; // TODO: Parameter 00667 int m_numFloorPoints = 20; // TODO: Parameter 00668 int m_numNonFloorPoints = 80; // TODO: Parameter 00669 00670 if (m_filteredPointCloud) 00671 { 00672 Eigen::Matrix4f matSensorToBaseFootprint, matBaseFootprintToSensor; 00673 pcl_ros::transformAsMatrix(sensorToBaseFootprint, matSensorToBaseFootprint); 00674 pcl_ros::transformAsMatrix(sensorToBaseFootprint.inverse(), matBaseFootprintToSensor); 00675 // TODO: This is stupid! Why transform the point cloud and not just the normal vector? 00676 pcl::transformPointCloud(pc, pc, matSensorToBaseFootprint ); 00677 filterGroundPlane(pc, ground, nonground, m_groundFilterDistance, m_groundFilterAngle, m_groundFilterPlaneDistance); 00678 // transform clouds back to sensor for integration 00679 pcl::transformPointCloud(ground, ground, matBaseFootprintToSensor); 00680 pcl::transformPointCloud(nonground, nonground, matBaseFootprintToSensor); 00681 pc.clear(); // clear pc again and refill it 00682 int numFloorPoints = filterUniform( ground, pc, m_numFloorPoints ); 00683 int numNonFloorPoints = filterUniform( nonground, pc, m_numNonFloorPoints ); 00684 ROS_INFO("PointCloudGroundFiltering done. Added %d non-ground points and %d ground points (from %zu). Cloud size is %zu", numNonFloorPoints, numFloorPoints, ground.size(), pc.size()); 00685 } 00686 else 00687 { 00688 ROS_ERROR("No ground filtering is not implemented yet!"); 00689 return; 00690 } 00691 // create sparse ranges.. 00692 ranges.resize(pc.size()); 00693 for (unsigned int i=0; i<pc.size(); ++i) 00694 { 00695 pcl::PointXYZ p = pc.at(i); 00696 ranges[i] = sqrt(p.x*p.x + p.y*p.y + p.z*p.z); 00697 } 00698 00699 } 00700 00701 00702 unsigned HumanoidLocalization::computeBeamStep(unsigned numBeams) const{ 00703 unsigned step = 1; 00704 if (m_numSensorBeams > 1){ 00705 // from "amcl_node" 00706 step = (numBeams -1) / (m_numSensorBeams - 1); 00707 if (step < 1) 00708 step = 1; 00709 } else if (m_numSensorBeams == 1){ 00710 step = numBeams; 00711 } 00712 00713 return step; 00714 } 00715 00716 void HumanoidLocalization::pointCloudCallback(const PointCloud::ConstPtr & msg) { 00717 ROS_DEBUG("PointCloud received (time: %f)", msg->header.stamp.toSec()); 00718 00719 if (!m_initialized){ 00720 ROS_WARN("Loclization not initialized yet, skipping PointCloud callback."); 00721 return; 00722 } 00723 00724 double timediff = (msg->header.stamp - m_lastPointCloudTime).toSec(); 00725 if (m_receivedSensorData && timediff < 0){ 00726 ROS_WARN("Ignoring received PointCloud data that is %f s older than previous data!", timediff); 00727 return; 00728 } 00729 00730 00732 tf::Stamped<tf::Pose> odomPose; 00733 // check if odometry available, skip scan if not. 00734 if (!m_motionModel->lookupOdomPose(msg->header.stamp, odomPose)) 00735 return; 00736 00737 00738 bool sensor_integrated = false; 00739 00740 // TODO #1: Make this nicer: head rotations for integration check 00741 // TODO #2: Initialization of m_headYawRotationLastScan, etc needs to be set correctly 00742 bool isAboveHeadMotionThreshold = false; 00743 double headYaw, headPitch, headRoll; 00744 tf::StampedTransform torsoToSensor; 00745 if (!m_motionModel->lookupLocalTransform(msg->header.frame_id, msg->header.stamp, torsoToSensor)) 00746 return; //TODO: should we apply applyOdomTransformTemporal, before returning 00747 00748 // TODO #3: Invert transform?: tf::Transform torsoToSensor(localSensorFrame.inverse()); 00749 00750 torsoToSensor.getBasis().getRPY(headRoll, headPitch, headYaw); 00751 double headYawRotationSinceScan = std::abs(headYaw - m_headYawRotationLastScan); 00752 double headPitchRotationSinceScan = std::abs(headPitch - m_headPitchRotationLastScan); 00753 00754 if (headYawRotationSinceScan>= m_observationThresholdHeadYawRot || headPitchRotationSinceScan >= m_observationThresholdHeadPitchRot) 00755 isAboveHeadMotionThreshold = true; 00756 // end #1 00757 00758 if (!m_paused && (!m_receivedSensorData || isAboveHeadMotionThreshold || isAboveMotionThreshold(odomPose))) { 00759 00760 // convert laser to point cloud first: 00761 PointCloud pc_filtered; 00762 std::vector<float> rangesSparse; 00763 prepareGeneralPointCloud(msg, pc_filtered, rangesSparse); 00764 00765 double maxRange = 10.0; // TODO #4: What is a maxRange for pointClouds? NaN? maxRange is expected to be a double and integrateMeasurement checks rangesSparse[i] > maxRange 00766 ROS_DEBUG("Updating Pose Estimate from a PointCloud with %zu points and %zu ranges", pc_filtered.size(), rangesSparse.size()); 00767 sensor_integrated = localizeWithMeasurement(pc_filtered, rangesSparse, maxRange); 00768 00769 } 00770 if(!sensor_integrated){ // no observation necessary: propagate particles forward by full interval 00771 // relative odom transform to last odomPose 00772 tf::Transform odomTransform = m_motionModel->computeOdomTransform(odomPose); 00773 m_motionModel->applyOdomTransform(m_particles, odomTransform); 00774 constrainMotion(odomPose); 00775 } 00776 else{ 00777 m_lastLocalizedPose = odomPose; 00778 // TODO #1 00779 m_headYawRotationLastScan = headYaw; 00780 m_headPitchRotationLastScan = headPitch; 00781 } 00782 00783 m_motionModel->storeOdomPose(odomPose); 00784 publishPoseEstimate(msg->header.stamp, sensor_integrated); 00785 m_lastPointCloudTime = msg->header.stamp; 00786 ROS_DEBUG("PointCloud callback complete."); 00787 } 00788 00789 void HumanoidLocalization::imuCallback(const sensor_msgs::ImuConstPtr& msg){ 00790 m_lastIMUMsgBuffer.push_back(*msg); 00791 } 00792 00793 bool HumanoidLocalization::getImuMsg(const ros::Time& stamp, ros::Time& imuStamp, double& angleX, double& angleY) const { 00794 if(m_lastIMUMsgBuffer.empty()) 00795 return false; 00796 00797 typedef boost::circular_buffer<sensor_msgs::Imu>::const_iterator ItT; 00798 const double maxAge = 0.2; 00799 double closestOlderStamp = std::numeric_limits<double>::max(); 00800 double closestNewerStamp = std::numeric_limits<double>::max(); 00801 ItT closestOlder = m_lastIMUMsgBuffer.end(), closestNewer = m_lastIMUMsgBuffer.end(); 00802 for(ItT it = m_lastIMUMsgBuffer.begin(); it != m_lastIMUMsgBuffer.end(); it++) { 00803 const double age = (stamp - it->header.stamp).toSec(); 00804 if(age >= 0.0 && age < closestOlderStamp) { 00805 closestOlderStamp = age; 00806 closestOlder = it; 00807 } else if(age < 0.0 && -age < closestNewerStamp) { 00808 closestNewerStamp = -age; 00809 closestNewer = it; 00810 } 00811 } 00812 00813 if(closestOlderStamp < maxAge && closestNewerStamp < maxAge && closestOlderStamp + closestNewerStamp > 0.0) { 00814 // Linear interpolation 00815 const double weightOlder = closestNewerStamp / (closestNewerStamp + closestOlderStamp); 00816 const double weightNewer = 1.0 - weightOlder; 00817 imuStamp = ros::Time(weightOlder * closestOlder->header.stamp.toSec() 00818 + weightNewer * closestNewer->header.stamp.toSec()); 00819 double olderX, olderY, newerX, newerY; 00820 getRP(closestOlder->orientation, olderX, olderY); 00821 getRP(closestNewer->orientation, newerX, newerY); 00822 angleX = weightOlder * olderX + weightNewer * newerX; 00823 angleY = weightOlder * olderY + weightNewer * newerY; 00824 ROS_DEBUG("Msg: %.3f, Interpolate [%.3f .. %.3f .. %.3f]\n", stamp.toSec(), closestOlder->header.stamp.toSec(), 00825 imuStamp.toSec(), closestNewer->header.stamp.toSec()); 00826 return true; 00827 } else if(closestOlderStamp < maxAge || closestNewerStamp < maxAge) { 00828 // Return closer one 00829 ItT it = (closestOlderStamp < closestNewerStamp) ? closestOlder : closestNewer; 00830 imuStamp = it->header.stamp; 00831 getRP(it->orientation, angleX, angleY); 00832 return true; 00833 } else { 00834 if(closestOlderStamp < closestNewerStamp) 00835 ROS_WARN("Closest IMU message is %.2f seconds too old, skipping pose integration", closestOlderStamp); 00836 else 00837 ROS_WARN("Closest IMU message is %.2f seconds too new, skipping pose integration", closestNewerStamp); 00838 return false; 00839 } 00840 } 00841 00842 void HumanoidLocalization::initPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg){ 00843 tf::Pose pose; 00844 tf::poseMsgToTF(msg->pose.pose, pose); 00845 00846 if (msg->header.frame_id != m_globalFrameId){ 00847 ROS_WARN("Frame ID of \"initialpose\" (%s) is different from the global frame %s", msg->header.frame_id.c_str(), m_globalFrameId.c_str()); 00848 } 00849 00850 std::vector<double> heights; 00851 double poseHeight = 0.0; 00852 if (std::abs(pose.getOrigin().getZ()) < 0.01){ 00853 m_mapModel->getHeightlist(pose.getOrigin().getX(), pose.getOrigin().getY(), 0.6, heights); 00854 if (heights.size() == 0){ 00855 ROS_WARN("No ground level to stand on found at map position, assuming 0"); 00856 heights.push_back(0.0); 00857 } 00858 00859 bool poseHeightOk = false; 00860 if(m_initPoseRealZRP) { 00861 ros::Time stamp(msg->header.stamp); 00862 if(stamp.isZero()) { 00863 // Header stamp is not set (e.g. RViz), use stamp from latest pose message instead 00864 tf::Stamped<tf::Pose> lastOdomPose; 00865 m_motionModel->getLastOdomPose(lastOdomPose); 00866 stamp = lastOdomPose.stamp_; 00867 } 00868 poseHeightOk = lookupPoseHeight(stamp, poseHeight); 00869 if(!poseHeightOk) { 00870 ROS_WARN("Could not determine current pose height, falling back to init_pose_z"); 00871 } 00872 } 00873 if(!poseHeightOk) { 00874 ROS_INFO("Use pose height from init_pose_z"); 00875 poseHeight = m_initPose(2); 00876 } 00877 } 00878 00879 00880 Matrix6d initCov; 00881 if ((std::abs(msg->pose.covariance.at(6*0+0) - 0.25) < 0.1) && (std::abs(msg->pose.covariance.at(6*1+1) -0.25) < 0.1) 00882 && (std::abs(msg->pose.covariance.at(6*3+3) - M_PI/12.0 * M_PI/12.0)<0.1)){ 00883 ROS_INFO("Covariance originates from RViz, using default parameters instead"); 00884 initCov = Matrix6d::Zero(); 00885 initCov.diagonal() = m_initNoiseStd.cwiseProduct(m_initNoiseStd); 00886 00887 // manually set r&p, rviz values are 0 00888 bool ok = false; 00889 const double yaw = tf::getYaw(pose.getRotation()); 00890 if(m_initPoseRealZRP) { 00891 bool useOdometry = true; 00892 if(m_useIMU) { 00893 if(m_lastIMUMsgBuffer.empty()) { 00894 ROS_WARN("Could not determine current roll and pitch because IMU message buffer is empty."); 00895 } else { 00896 double roll, pitch; 00897 if(msg->header.stamp.isZero()) { 00898 // Header stamp is not set (e.g. RViz), use stamp from latest IMU message instead 00899 getRP(m_lastIMUMsgBuffer.back().orientation, roll, pitch); 00900 ok = true; 00901 } else { 00902 ros::Time imuStamp; 00903 ok = getImuMsg(msg->header.stamp, imuStamp, roll, pitch); 00904 } 00905 if(ok) { 00906 ROS_INFO("roll and pitch not set in initPoseCallback, use IMU values (roll = %f, pitch = %f) instead", roll, pitch); 00907 pose.setRotation(tf::createQuaternionFromRPY(roll, pitch, yaw)); 00908 useOdometry = false; 00909 } else { 00910 ROS_WARN("Could not determine current roll and pitch from IMU, falling back to odometry roll and pitch"); 00911 useOdometry = true; 00912 } 00913 } 00914 } 00915 00916 if(useOdometry) { 00917 double roll, pitch, dropyaw; 00918 tf::Stamped<tf::Pose> lastOdomPose; 00919 ok = m_motionModel->getLastOdomPose(lastOdomPose); 00920 if(ok) { 00921 lastOdomPose.getBasis().getRPY(roll, pitch, dropyaw); 00922 pose.setRotation(tf::createQuaternionFromRPY(roll, pitch, yaw)); 00923 ROS_INFO("roll and pitch not set in initPoseCallback, use odometry values (roll = %f, pitch = %f) instead", roll, pitch); 00924 } else { 00925 ROS_WARN("Could not determine current roll and pitch from odometry, falling back to init_pose_{roll,pitch} parameters"); 00926 } 00927 } 00928 } 00929 00930 if(!ok) { 00931 ROS_INFO("roll and pitch not set in initPoseCallback, use init_pose_{roll,pitch} parameters instead"); 00932 pose.setRotation(tf::createQuaternionFromRPY(m_initPose(3), m_initPose(4), yaw)); 00933 } 00934 } else{ 00935 for(int j=0; j < initCov.cols(); ++j){ 00936 for (int i = 0; i < initCov.rows(); ++i){ 00937 initCov(i,j) = msg->pose.covariance.at(i*initCov.cols() +j); 00938 } 00939 } 00940 } 00941 00942 // sample from initial pose covariance: 00943 Matrix6d initCovL = initCov.llt().matrixL(); 00944 tf::Transform transformNoise; // transformation on original pose from noise 00945 unsigned idx = 0; 00946 for(Particles::iterator it = m_particles.begin(); it != m_particles.end(); ++it){ 00947 Vector6d poseNoise; 00948 for (unsigned i = 0; i < 6; ++i){ 00949 poseNoise(i) = m_rngNormal(); 00950 } 00951 Vector6d poseCovNoise = initCovL * poseNoise; // is now drawn according to covariance noise 00952 // if a variance is set to 0 => no noise! 00953 for (unsigned i = 0; i < 6; ++i){ 00954 if (std::abs(initCov(i,i)) < 0.00001) 00955 poseCovNoise(i) = 0.0; 00956 } 00957 00958 00959 transformNoise.setOrigin(tf::Vector3(poseCovNoise(0), poseCovNoise(1), poseCovNoise(2))); 00960 tf::Quaternion q; 00961 q.setRPY(poseCovNoise(3), poseCovNoise(4),poseCovNoise(5)); 00962 00963 transformNoise.setRotation(q); 00964 it->pose = pose; 00965 00966 if (heights.size() > 0){ 00967 // distribute particles evenly between levels: 00968 it->pose.getOrigin().setZ(heights.at(int(double(idx)/m_particles.size() * heights.size())) + poseHeight); 00969 } 00970 00971 it->pose *= transformNoise; 00972 00973 it->weight = 1.0/m_particles.size(); 00974 idx++; 00975 } 00976 00977 ROS_INFO("Pose reset around mean (%f %f %f)", pose.getOrigin().getX(), pose.getOrigin().getY(), pose.getOrigin().getZ()); 00978 00979 // reset internal state: 00980 m_motionModel->reset(); 00981 m_receivedSensorData = false; 00982 m_initialized = true; 00983 00984 publishPoseEstimate(msg->header.stamp, false); 00985 } 00986 00987 bool HumanoidLocalization::globalLocalizationCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) 00988 { 00989 00990 initGlobal(); 00991 00992 return true; 00993 } 00994 00995 void HumanoidLocalization::normalizeWeights() { 00996 00997 double wmin = std::numeric_limits<double>::max(); 00998 double wmax = -std::numeric_limits<double>::max(); 00999 01000 for (unsigned i=0; i < m_particles.size(); ++i){ 01001 double weight = m_particles[i].weight; 01002 assert (!isnan(weight)); 01003 if (weight < wmin) 01004 wmin = weight; 01005 if (weight > wmax){ 01006 wmax = weight; 01007 m_bestParticleIdx = i; 01008 } 01009 } 01010 if (wmin > wmax){ 01011 ROS_ERROR_STREAM("Error in weights: min=" << wmin <<", max="<<wmax<<", 1st particle weight="<< m_particles[1].weight<< std::endl); 01012 01013 } 01014 01015 double min_normalized_value; 01016 if (m_minParticleWeight > 0.0) 01017 min_normalized_value = std::max(log(m_minParticleWeight), wmin - wmax); 01018 else 01019 min_normalized_value = wmin - wmax; 01020 01021 double max_normalized_value = 0.0; // = log(1.0); 01022 double dn = max_normalized_value-min_normalized_value; 01023 double dw = wmax-wmin; 01024 if (dw == 0.0) dw = 1; 01025 double scale = dn/dw; 01026 if (scale < 0.0){ 01027 ROS_WARN("normalizeWeights: scale is %f < 0, dw=%f, dn=%f", scale, dw, dn ); 01028 } 01029 double offset = -wmax*scale; 01030 double weights_sum = 0.0; 01031 01032 #pragma omp parallel 01033 { 01034 01035 #pragma omp for 01036 for (unsigned i = 0; i < m_particles.size(); ++i){ 01037 double w = m_particles[i].weight; 01038 w = exp(scale*w+offset); 01039 assert(!isnan(w)); 01040 m_particles[i].weight = w; 01041 #pragma omp atomic 01042 weights_sum += w; 01043 } 01044 01045 assert(weights_sum > 0.0); 01046 // normalize sum to 1: 01047 #pragma omp for 01048 for (unsigned i = 0; i < m_particles.size(); ++i){ 01049 m_particles[i].weight /= weights_sum; 01050 } 01051 01052 } 01053 } 01054 01055 double HumanoidLocalization::getCumParticleWeight() const{ 01056 double cumWeight=0.0; 01057 01058 //compute the cumulative weights 01059 for (Particles::const_iterator it = m_particles.begin(); it != m_particles.end(); ++it){ 01060 cumWeight += it->weight; 01061 } 01062 01063 return cumWeight; 01064 } 01065 01066 void HumanoidLocalization::resample(unsigned numParticles){ 01067 01068 if (numParticles <= 0) 01069 numParticles = m_numParticles; 01070 01071 //compute the interval 01072 double interval=getCumParticleWeight()/numParticles; 01073 01074 //compute the initial target weight 01075 double target=interval*m_rngUniform(); 01076 01077 //compute the resampled indexes 01078 double cumWeight=0; 01079 std::vector<unsigned> indices(numParticles); 01080 01081 unsigned n=0; 01082 for (unsigned i = 0; i < m_particles.size(); ++i){ 01083 cumWeight += m_particles[i].weight; 01084 while(cumWeight > target && n < numParticles){ 01085 if (m_bestParticleIdx >= 0 && i == unsigned(m_bestParticleIdx)){ 01086 m_bestParticleIdx = n; 01087 } 01088 01089 indices[n++]=i; 01090 target+=interval; 01091 } 01092 } 01093 // indices now contains the indices to draw from the particles distribution 01094 01095 Particles oldParticles = m_particles; 01096 m_particles.resize(numParticles); 01097 m_poseArray.poses.resize(numParticles); 01098 double newWeight = 1.0/numParticles; 01099 #pragma omp parallel for 01100 for (unsigned i = 0; i < numParticles; ++i){ 01101 m_particles[i].pose = oldParticles[indices[i]].pose; 01102 m_particles[i].weight = newWeight; 01103 } 01104 } 01105 01106 void HumanoidLocalization::initGlobal(){ 01107 ROS_INFO("Initializing with uniform distribution"); 01108 01109 m_mapModel->initGlobal(m_particles, m_initPose, m_initNoiseStd, m_rngUniform, m_rngNormal); 01110 01111 01112 ROS_INFO("Global localization done"); 01113 m_motionModel->reset(); 01114 m_receivedSensorData = false; 01115 m_initialized = true; 01116 01117 publishPoseEstimate(ros::Time::now(), false); 01118 01119 } 01120 01121 void HumanoidLocalization::publishPoseEstimate(const ros::Time& time, bool publish_eval){ 01122 01124 // send all hypotheses as arrows: 01126 01127 m_poseArray.header.stamp = time; 01128 01129 if (m_poseArray.poses.size() != m_particles.size()) 01130 m_poseArray.poses.resize(m_particles.size()); 01131 01132 #pragma omp parallel for 01133 for (unsigned i = 0; i < m_particles.size(); ++i){ 01134 tf::poseTFToMsg(m_particles[i].pose, m_poseArray.poses[i]); 01135 } 01136 01137 m_poseArrayPub.publish(m_poseArray); 01138 01140 // send best particle as pose and one array: 01142 geometry_msgs::PoseWithCovarianceStamped p; 01143 p.header.stamp = time; 01144 p.header.frame_id = m_globalFrameId; 01145 01146 tf::Pose bestParticlePose; 01147 if (m_bestParticleAsMean) 01148 bestParticlePose = getMeanParticlePose(); 01149 else 01150 bestParticlePose = getBestParticlePose(); 01151 01152 tf::poseTFToMsg(bestParticlePose,p.pose.pose); 01153 m_posePub.publish(p); 01154 01155 if (publish_eval){ 01156 m_poseEvalPub.publish(p); 01157 } 01158 01159 geometry_msgs::PoseArray bestPose; 01160 bestPose.header = p.header; 01161 bestPose.poses.resize(1); 01162 tf::poseTFToMsg(bestParticlePose, bestPose.poses[0]); 01163 m_bestPosePub.publish(bestPose); 01164 01166 // send incremental odom pose (synced to localization) 01168 tf::Stamped<tf::Pose> lastOdomPose; 01169 if (m_motionModel->getLastOdomPose(lastOdomPose)){ 01170 geometry_msgs::PoseStamped odomPoseMsg; 01171 tf::poseStampedTFToMsg(lastOdomPose, odomPoseMsg); 01172 m_poseOdomPub.publish(odomPoseMsg); 01173 } 01174 01175 01177 // Send tf odom->map 01179 tf::Stamped<tf::Pose> odomToMapTF; 01180 try{ 01181 tf::Stamped<tf::Pose> baseToMapTF(bestParticlePose.inverse(),time, m_baseFrameId); 01182 m_tfListener.transformPose(m_odomFrameId, baseToMapTF, odomToMapTF); 01183 } catch (const tf::TransformException& e){ 01184 ROS_WARN("Failed to subtract base to odom transform, will not publish pose estimate: %s", e.what()); 01185 return; 01186 } 01187 01188 tf::Transform latestTF(tf::Quaternion(odomToMapTF.getRotation()), tf::Point(odomToMapTF.getOrigin())); 01189 01190 // We want to send a transform that is good up until a 01191 // tolerance time so that odom can be used 01192 // see ROS amcl_node 01193 01194 ros::Duration transformTolerance(m_transformTolerance); 01195 ros::Time transformExpiration = (time + transformTolerance); 01196 01197 tf::StampedTransform tmp_tf_stamped(latestTF.inverse(), transformExpiration, m_globalFrameId, m_odomFrameId); 01198 01199 m_tfBroadcaster.sendTransform(tmp_tf_stamped); 01200 01201 } 01202 01203 unsigned HumanoidLocalization::getBestParticleIdx() const{ 01204 if (m_bestParticleIdx < 0 || m_bestParticleIdx >= m_numParticles){ 01205 ROS_WARN("Index (%d) of best particle not valid, using 0 instead", m_bestParticleIdx); 01206 return 0; 01207 } 01208 01209 return m_bestParticleIdx; 01210 } 01211 01212 tf::Pose HumanoidLocalization::getParticlePose(unsigned particleIdx) const{ 01213 return m_particles.at(particleIdx).pose; 01214 } 01215 01216 tf::Pose HumanoidLocalization::getBestParticlePose() const{ 01217 return getParticlePose(getBestParticleIdx()); 01218 } 01219 01220 tf::Pose HumanoidLocalization::getMeanParticlePose() const{ 01221 tf::Pose meanPose = tf::Pose::getIdentity(); 01222 01223 double totalWeight = 0.0; 01224 01225 meanPose.setBasis(tf::Matrix3x3(0,0,0,0,0,0,0,0,0)); 01226 for (Particles::const_iterator it = m_particles.begin(); it != m_particles.end(); ++it){ 01227 meanPose.getOrigin() += it->pose.getOrigin() * it->weight; 01228 meanPose.getBasis()[0] += it->pose.getBasis()[0]; 01229 meanPose.getBasis()[1] += it->pose.getBasis()[1]; 01230 meanPose.getBasis()[2] += it->pose.getBasis()[2]; 01231 totalWeight += it->weight; 01232 } 01233 assert(!isnan(totalWeight)); 01234 01235 //assert(totalWeight == 1.0); 01236 01237 // just in case weights are not normalized: 01238 meanPose.getOrigin() /= totalWeight; 01239 // TODO: only rough estimate of mean rotation, asserts normalized weights! 01240 meanPose.getBasis() = meanPose.getBasis().scaled(tf::Vector3(1.0/m_numParticles, 1.0/m_numParticles, 1.0/m_numParticles)); 01241 01242 // Apparently we need to normalize again 01243 meanPose.setRotation(meanPose.getRotation().normalized()); 01244 01245 return meanPose; 01246 } 01247 01248 double HumanoidLocalization::nEff() const{ 01249 01250 double sqrWeights=0.0; 01251 for (Particles::const_iterator it=m_particles.begin(); it!=m_particles.end(); ++it){ 01252 sqrWeights+=(it->weight * it->weight); 01253 } 01254 01255 if (sqrWeights > 0.0) 01256 return 1./sqrWeights; 01257 else 01258 return 0.0; 01259 } 01260 01261 void HumanoidLocalization::toLogForm(){ 01262 // TODO: linear offset needed? 01263 #pragma omp parallel for 01264 for (unsigned i = 0; i < m_particles.size(); ++i){ 01265 assert(m_particles[i].weight > 0.0); 01266 m_particles[i].weight = log(m_particles[i].weight); 01267 } 01268 } 01269 01270 void HumanoidLocalization::pauseLocalizationCallback(const std_msgs::BoolConstPtr& msg){ 01271 if (msg->data){ 01272 if (!m_paused){ 01273 m_paused = true; 01274 ROS_INFO("Localization paused"); 01275 } else{ 01276 ROS_WARN("Received a msg to pause localizatzion, but is already paused."); 01277 } 01278 } else{ 01279 if (m_paused){ 01280 m_paused = false; 01281 ROS_INFO("Localization resumed"); 01282 // force laser integration: 01283 m_receivedSensorData = false; 01284 } else { 01285 ROS_WARN("Received a msg to resume localization, is not paused."); 01286 } 01287 01288 } 01289 01290 } 01291 01292 bool HumanoidLocalization::pauseLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) 01293 { 01294 if (!m_paused){ 01295 m_paused = true; 01296 ROS_INFO("Localization paused"); 01297 } else{ 01298 ROS_WARN("Received a request to pause localizatzion, but is already paused."); 01299 } 01300 01301 return true; 01302 } 01303 01304 bool HumanoidLocalization::resumeLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) 01305 { 01306 if (m_paused){ 01307 m_paused = false; 01308 ROS_INFO("Localization resumed"); 01309 // force next laser integration: 01310 m_receivedSensorData = false; 01311 } else { 01312 ROS_WARN("Received a request to resume localization, but is not paused."); 01313 } 01314 01315 return true; 01316 } 01317 01318 bool HumanoidLocalization::lookupPoseHeight(const ros::Time& t, double& poseHeight) const{ 01319 tf::StampedTransform tf; 01320 if (m_motionModel->lookupLocalTransform(m_baseFootprintId, t, tf)){ 01321 poseHeight = tf.getOrigin().getZ(); 01322 return true; 01323 } else 01324 return false; 01325 } 01326 01327 } 01328