23 #include <pcl/point_types.h>    24 #include <pcl/conversions.h>    42     ROS_ERROR(
"raycasting/z_max needs to be > 0.0");
    46     ROS_ERROR(
"raycasting/z_rand needs to be > 0.0");
    51       if (omp_get_thread_num() == 0){
    52         ROS_INFO(
"Using %d threads in RaycastingModel", omp_get_num_threads());
    62   assert(pc.size() == ranges.size());
    65     ROS_ERROR(
"Map file is not set in raycasting");
    69 #pragma omp parallel for    70   for (
unsigned i=0; i < particles.size(); ++i){
    71     Eigen::Matrix4f globalLaserOrigin;
    72     tf::Transform globalLaserOriginTf = particles[i].pose * base_to_laser;
    80     pcl::transformPointCloud(pc, pc_transformed, globalLaserOrigin);
    83     PointCloud::const_iterator pc_it = pc_transformed.begin();
    84     std::vector<float>::const_iterator ranges_it = ranges.begin();
    85     for ( ; pc_it != pc_transformed.end(); ++pc_it, ++ranges_it){
    89       if (*ranges_it <= max_range){
    93         direction = direction - originP;
    99         if(
m_map->castRay(originP,direction, end, 
true, 1.5*max_range)){
   100           assert(
m_map->isNodeOccupied(
m_map->search(end)));
   101           float raycastRange = (originP - end).norm();
   102           float z = raycastRange - *ranges_it;
   105              sigma_scaled = (*ranges_it) * (*ranges_it) * (
m_sigmaHit);
   108           p = 
m_zHit / (
SQRT_2_PI * sigma_scaled) * exp(-(z * z) / (2 * sigma_scaled * sigma_scaled));
   111           if (*ranges_it <= raycastRange)
   127       particles[i].weight += log(p);
   142   if (!
m_map->castRay(origin, direction, end, 
true, 2*direction.
norm()))
   145   heightError =  std::max(0.0, std::abs((origin-end).
z() - footprintToBase.
getOrigin().
z()) - 
m_map->getResolution());
 
boost::shared_ptr< octomap::OcTree > m_map
 
boost::mt19937 EngineT
Boost RNG engine: 
 
void transformAsMatrix(const tf::Transform &bt, Eigen::Matrix4f &out_mat)
 
Particle consists of a pose and a weight. 
 
static octomap::point3d pointTfToOctomap(const tf::Point &ptTf)
 
TFSIMD_FORCE_INLINE const tfScalar & x() const 
 
TFSIMD_FORCE_INLINE const tfScalar & z() const 
 
static const double SQRT_2_PI
sqrt(2*pi) 
 
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
 
TFSIMD_FORCE_INLINE const tfScalar & z() const 
 
virtual void integrateMeasurement(Particles &particles, const PointCloud &pc, const std::vector< float > &ranges, float max_range, const tf::Transform &baseToSensor)
 
bool getHeightError(const Particle &p, const tf::StampedTransform &footprintToBase, double &heightError) const 
 
RaycastingModel(ros::NodeHandle *nh, boost::shared_ptr< MapModel > mapModel, EngineT *rngEngine)
 
std::vector< Particle > Particles
 
pcl::PointCloud< pcl::PointXYZ > PointCloud
 
virtual ~RaycastingModel()