Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include <humanoid_localization/RaycastingModel.h>
00022
00023 #include <pcl/point_types.h>
00024 #include <pcl/ros/conversions.h>
00025 #include <pcl_ros/transforms.h>
00026 #include <octomap_ros/conversions.h>
00027
00028 namespace humanoid_localization{
00029
00030 RaycastingModel::RaycastingModel(ros::NodeHandle* nh, boost::shared_ptr<MapModel> mapModel, EngineT * rngEngine)
00031 : ObservationModel(nh, mapModel, rngEngine)
00032 {
00033
00034 nh->param("raycasting/z_hit", m_zHit, 0.8);
00035 nh->param("raycasting/z_short", m_zShort, 0.1);
00036 nh->param("raycasting/z_max", m_zMax, 0.05);
00037 nh->param("raycasting/z_rand", m_zRand, 0.05);
00038 nh->param("raycasting/sigma_hit", m_sigmaHit, 0.02);
00039 nh->param("raycasting/lambda_short", m_lambdaShort, 0.1);
00040
00041 if (m_zMax <= 0.0){
00042 ROS_ERROR("raycasting/z_max needs to be > 0.0");
00043 }
00044
00045 if (m_zRand <= 0.0){
00046 ROS_ERROR("raycasting/z_rand needs to be > 0.0");
00047 }
00048 #pragma omp parallel
00049 #pragma omp critical
00050 {
00051 if (omp_get_thread_num() == 0){
00052 ROS_INFO("Using %d threads in RaycastingModel", omp_get_num_threads());
00053 }
00054 }
00055 }
00056
00057 RaycastingModel::~RaycastingModel(){
00058
00059 }
00060
00061 void RaycastingModel::integrateMeasurement(Particles& particles, const PointCloud& pc, const std::vector<float>& ranges, float max_range, const tf::Transform& base_to_laser){
00062 assert(pc.size() == ranges.size());
00063
00064 if (!m_map){
00065 ROS_ERROR("Map file is not set in raycasting");
00066 return;
00067 }
00068
00069 #pragma omp parallel for
00070 for (unsigned i=0; i < particles.size(); ++i){
00071 Eigen::Matrix4f globalLaserOrigin;
00072 tf::Transform globalLaserOriginTf = particles[i].pose * base_to_laser;
00073 pcl_ros::transformAsMatrix(globalLaserOriginTf, globalLaserOrigin);
00074
00075
00076 octomap::point3d originP(globalLaserOriginTf.getOrigin().x(),
00077 globalLaserOriginTf.getOrigin().y(),
00078 globalLaserOriginTf.getOrigin().z());
00079 PointCloud pc_transformed;
00080 pcl::transformPointCloud(pc, pc_transformed, globalLaserOrigin);
00081
00082
00083 PointCloud::const_iterator pc_it = pc_transformed.begin();
00084 std::vector<float>::const_iterator ranges_it = ranges.begin();
00085 for ( ; pc_it != pc_transformed.end(); ++pc_it, ++ranges_it){
00086
00087 double p = 0.0;
00088
00089 if (*ranges_it <= max_range){
00090
00091
00092 octomap::point3d direction(pc_it->x , pc_it->y, pc_it->z);
00093 direction = direction - originP;
00094
00095
00096 octomap::point3d end;
00097
00098
00099 if(m_map->castRay(originP,direction, end, true, 1.5*max_range)){
00100 assert(m_map->isNodeOccupied(m_map->search(end)));
00101 float raycastRange = (originP - end).norm();
00102 float z = raycastRange - *ranges_it;
00103 float sigma_scaled = m_sigmaHit;
00104 if (m_use_squared_error)
00105 sigma_scaled = (*ranges_it) * (*ranges_it) * (m_sigmaHit);
00106
00107
00108 p = m_zHit / (SQRT_2_PI * sigma_scaled) * exp(-(z * z) / (2 * sigma_scaled * sigma_scaled));
00109
00110
00111 if (*ranges_it <= raycastRange)
00112 p += m_zShort * m_lambdaShort * exp(-m_lambdaShort* (*ranges_it)) / (1-exp(-m_lambdaShort*raycastRange));
00113
00114
00115 p += m_zRand / max_range;
00116 } else {
00117 p = m_zRand / max_range;
00118 }
00119
00120 } else{
00121 p = m_zMax;
00122 }
00123
00124
00125
00126 assert(p > 0.0);
00127 particles[i].weight += log(p);
00128
00129 }
00130
00131 }
00132
00133
00134 }
00135
00136 bool RaycastingModel::getHeightError(const Particle& p, const tf::StampedTransform& footprintToBase, double& heightError) const{
00137
00138 octomap::point3d direction = octomap::pointTfToOctomap(footprintToBase.inverse().getOrigin());
00139 octomap::point3d origin = octomap::pointTfToOctomap(p.pose.getOrigin());
00140 octomap::point3d end;
00141
00142 if (!m_map->castRay(origin, direction, end, true, 2*direction.norm()))
00143 return false;
00144
00145 heightError = std::max(0.0, std::abs((origin-end).z() - footprintToBase.getOrigin().z()) - m_map->getResolution());
00146
00147
00148 return true;
00149 }
00150
00151 }