$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/humanoid_localization/src/ObservationModel.cpp $ 00002 // SVN $Id: ObservationModel.cpp 3860 2013-02-06 16:58:53Z 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/ObservationModel.h> 00025 00026 using namespace std; 00027 using namespace tf; 00028 00029 namespace humanoid_localization{ 00030 00031 ObservationModel::ObservationModel(ros::NodeHandle* nh, boost::shared_ptr<MapModel> mapModel, EngineT* rngEngine ) 00032 : m_mapModel(mapModel), 00033 m_rngNormal(*rngEngine, NormalDistributionT(0.0, 1.0)), 00034 m_rngUniform(*rngEngine, UniformDistributionT(0.0, 1.0)), 00035 m_weightRoll(1.0), m_weightPitch(1.0), m_weightZ(1.0), 00036 m_sigmaZ(0.02), m_sigmaRoll(0.05), m_sigmaPitch(0.05) 00037 { 00038 00039 m_map = m_mapModel->getMap(); 00040 00041 nh->param("weight_factor_roll", m_weightRoll, m_weightRoll); 00042 nh->param("weight_factor_pitch", m_weightPitch, m_weightPitch); 00043 nh->param("weight_factor_z", m_weightZ, m_weightZ); 00044 nh->param("motion_sigma_z", m_sigmaZ, m_sigmaZ); 00045 nh->param("motion_sigma_roll", m_sigmaRoll, m_sigmaRoll); 00046 nh->param("motion_sigma_pitch", m_sigmaPitch, m_sigmaPitch); 00047 00048 if (m_sigmaZ <= 0.0 || m_sigmaRoll <= 0.0 || m_sigmaPitch <= 0.0){ 00049 ROS_ERROR("Sigma (std.dev) needs to be > 0 in ObservationModel"); 00050 } 00051 } 00052 00053 ObservationModel::~ObservationModel() { 00054 } 00055 00056 void ObservationModel::integratePoseMeasurement(Particles& particles, double poseRoll, double posePitch, const tf::StampedTransform& footprintToTorso){ 00057 // TODO: move to HumanoidLocalization, skip individual parts if z/rp constrained 00058 double poseHeight = footprintToTorso.getOrigin().getZ(); 00059 ROS_DEBUG("Pose measurement z=%f R=%f P=%f", poseHeight, poseRoll, posePitch); 00060 // TODO cluster xy of particles => speedup 00061 #pragma omp parallel for 00062 for (unsigned i=0; i < particles.size(); ++i){ 00063 // integrate IMU meas.: 00064 double roll, pitch, yaw; 00065 particles[i].pose.getBasis().getRPY(roll, pitch, yaw); 00066 particles[i].weight += m_weightRoll * logLikelihood(poseRoll - roll, m_sigmaRoll); 00067 particles[i].weight += m_weightPitch * logLikelihood(posePitch - pitch, m_sigmaPitch); 00068 00069 // integrate height measurement (z) 00070 double heightError; 00071 if (getHeightError(particles[i],footprintToTorso, heightError)) 00072 particles[i].weight += m_weightZ * logLikelihood(heightError, m_sigmaZ); 00073 00074 00075 } 00076 00077 } 00078 00079 void ObservationModel::setMap(boost::shared_ptr<octomap::OcTree> map){ 00080 m_map = map; 00081 } 00082 00083 }