Public Member Functions | Public Attributes | List of all members
floam::odom::OdomEstimation Class Reference

#include <odom_estimation.hpp>

Public Member Functions

void addEdgeCostFactor (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, const pcl::PointCloud< pcl::PointXYZ >::Ptr &map, ceres::Problem &problem, ceres::LossFunction *lossFunction)
 function More...
 
void addPointsToMap (const pcl::PointCloud< pcl::PointXYZ >::Ptr &downsampledEdgeCloud, const pcl::PointCloud< pcl::PointXYZ >::Ptr &downsampledSurfCloud)
 
void addSurfCostFactor (const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, const pcl::PointCloud< pcl::PointXYZ >::Ptr &map, ceres::Problem &problem, ceres::LossFunction *lossFunction)
 
void downSamplingToMap (const pcl::PointCloud< pcl::PointXYZ >::Ptr &edgesIn, pcl::PointCloud< pcl::PointXYZ >::Ptr &edgesOut, const pcl::PointCloud< pcl::PointXYZ >::Ptr &surfacesIn, pcl::PointCloud< pcl::PointXYZ >::Ptr &surfacesOut)
 
void getMap (pcl::PointCloud< pcl::PointXYZ >::Ptr &lidarCloudMap)
 
void init (const double &mapResolution)
 
void initMapWithPoints (const pcl::PointCloud< pcl::PointXYZ >::Ptr &edges, const pcl::PointCloud< pcl::PointXYZ >::Ptr &surfaces)
 
 OdomEstimation ()
 constructor / destructor More...
 
void pointAssociateToMap (const std::shared_ptr< pcl::PointXYZ > &pointsIn, std::shared_ptr< pcl::PointXYZ > &pointsOut)
 
void updatePointsToMap (const pcl::PointCloud< pcl::PointXYZ >::Ptr &edges, const pcl::PointCloud< pcl::PointXYZ >::Ptr &surfaces)
 
 ~OdomEstimation ()
 

Public Attributes

pcl::CropBox< pcl::PointXYZ > m_cropBoxFilter
 local map More...
 
Eigen::Map< Eigen::Quaterniond > m_currentRotation = Eigen::Map<Eigen::Quaterniond>(m_parameters)
 
Eigen::Map< Eigen::Vector3d > m_currentTranslation = Eigen::Map<Eigen::Vector3d>(m_parameters + 4)
 
pcl::VoxelGrid< pcl::PointXYZ > m_downSizeFilterEdge
 points downsampling before add to map More...
 
pcl::VoxelGrid< pcl::PointXYZ > m_downSizeFilterSurf
 
pcl::KdTreeFLANN< pcl::PointXYZ >::Ptr m_kdTreeEdgeMap
 kd-tree More...
 
pcl::KdTreeFLANN< pcl::PointXYZ >::Ptr m_kdTreeSurfMap
 
Eigen::Isometry3d m_lastOdom
 
pcl::PointCloud< pcl::PointXYZ >::Ptr m_lidarCloudCornerMap
 corner and surface map objects More...
 
pcl::PointCloud< pcl::PointXYZ >::Ptr m_lidarCloudSurfMap
 
Eigen::Isometry3d m_odom
 Odometry. More...
 
int m_optimizationCount
 optimization count More...
 
double m_parameters [7] = {0, 0, 0, 1, 0, 0, 0}
 Optimization parameters that ceres solvers update each loop. More...
 
floam::lidar::Total m_totals
 totals counters (frames, time) More...
 

Detailed Description

Odometry Estimation Class

Can be used across all lidar types

Definition at line 48 of file odom_estimation.hpp.

Constructor & Destructor Documentation

◆ OdomEstimation()

floam::odom::OdomEstimation::OdomEstimation ( )

constructor / destructor

Definition at line 18 of file odom_estimation.cpp.

◆ ~OdomEstimation()

floam::odom::OdomEstimation::~OdomEstimation ( )
inline

Definition at line 53 of file odom_estimation.hpp.

Member Function Documentation

◆ addEdgeCostFactor()

void floam::odom::OdomEstimation::addEdgeCostFactor ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  map,
ceres::Problem &  problem,
ceres::LossFunction *  lossFunction 
)

function

Definition at line 140 of file odom_estimation.cpp.

◆ addPointsToMap()

void floam::odom::OdomEstimation::addPointsToMap ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  downsampledEdgeCloud,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  downsampledSurfCloud 
)

Definition at line 277 of file odom_estimation.cpp.

◆ addSurfCostFactor()

void floam::odom::OdomEstimation::addSurfCostFactor ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  points,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  map,
ceres::Problem &  problem,
ceres::LossFunction *  lossFunction 
)

Definition at line 211 of file odom_estimation.cpp.

◆ downSamplingToMap()

void floam::odom::OdomEstimation::downSamplingToMap ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  edgesIn,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  edgesOut,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  surfacesIn,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  surfacesOut 
)

Definition at line 128 of file odom_estimation.cpp.

◆ getMap()

void floam::odom::OdomEstimation::getMap ( pcl::PointCloud< pcl::PointXYZ >::Ptr &  lidarCloudMap)

Definition at line 326 of file odom_estimation.cpp.

◆ init()

void floam::odom::OdomEstimation::init ( const double &  mapResolution)

Definition at line 23 of file odom_estimation.cpp.

◆ initMapWithPoints()

void floam::odom::OdomEstimation::initMapWithPoints ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  edges,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  surfaces 
)

TODO(flynneva): make this a parameter

Definition at line 40 of file odom_estimation.cpp.

◆ pointAssociateToMap()

void floam::odom::OdomEstimation::pointAssociateToMap ( const std::shared_ptr< pcl::PointXYZ > &  pointsIn,
std::shared_ptr< pcl::PointXYZ > &  pointsOut 
)

Definition at line 116 of file odom_estimation.cpp.

◆ updatePointsToMap()

void floam::odom::OdomEstimation::updatePointsToMap ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  edges,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  surfaces 
)

TODO(flynneva): make this a parameter

generate map from edges and surfaces

TODO(flynneva): make these parameters

Update odom

Definition at line 51 of file odom_estimation.cpp.

Member Data Documentation

◆ m_cropBoxFilter

pcl::CropBox<pcl::PointXYZ> floam::odom::OdomEstimation::m_cropBoxFilter

local map

Definition at line 82 of file odom_estimation.hpp.

◆ m_currentRotation

Eigen::Map<Eigen::Quaterniond> floam::odom::OdomEstimation::m_currentRotation = Eigen::Map<Eigen::Quaterniond>(m_parameters)

Definition at line 66 of file odom_estimation.hpp.

◆ m_currentTranslation

Eigen::Map<Eigen::Vector3d> floam::odom::OdomEstimation::m_currentTranslation = Eigen::Map<Eigen::Vector3d>(m_parameters + 4)

Definition at line 67 of file odom_estimation.hpp.

◆ m_downSizeFilterEdge

pcl::VoxelGrid<pcl::PointXYZ> floam::odom::OdomEstimation::m_downSizeFilterEdge

points downsampling before add to map

Definition at line 78 of file odom_estimation.hpp.

◆ m_downSizeFilterSurf

pcl::VoxelGrid<pcl::PointXYZ> floam::odom::OdomEstimation::m_downSizeFilterSurf

Definition at line 79 of file odom_estimation.hpp.

◆ m_kdTreeEdgeMap

pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr floam::odom::OdomEstimation::m_kdTreeEdgeMap

kd-tree

Definition at line 70 of file odom_estimation.hpp.

◆ m_kdTreeSurfMap

pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr floam::odom::OdomEstimation::m_kdTreeSurfMap

Definition at line 71 of file odom_estimation.hpp.

◆ m_lastOdom

Eigen::Isometry3d floam::odom::OdomEstimation::m_lastOdom

Definition at line 61 of file odom_estimation.hpp.

◆ m_lidarCloudCornerMap

pcl::PointCloud<pcl::PointXYZ>::Ptr floam::odom::OdomEstimation::m_lidarCloudCornerMap

corner and surface map objects

Definition at line 74 of file odom_estimation.hpp.

◆ m_lidarCloudSurfMap

pcl::PointCloud<pcl::PointXYZ>::Ptr floam::odom::OdomEstimation::m_lidarCloudSurfMap

Definition at line 75 of file odom_estimation.hpp.

◆ m_odom

Eigen::Isometry3d floam::odom::OdomEstimation::m_odom

Odometry.

Definition at line 61 of file odom_estimation.hpp.

◆ m_optimizationCount

int floam::odom::OdomEstimation::m_optimizationCount

optimization count

Definition at line 85 of file odom_estimation.hpp.

◆ m_parameters

double floam::odom::OdomEstimation::m_parameters[7] = {0, 0, 0, 1, 0, 0, 0}

Optimization parameters that ceres solvers update each loop.

Definition at line 64 of file odom_estimation.hpp.

◆ m_totals

floam::lidar::Total floam::odom::OdomEstimation::m_totals

totals counters (frames, time)

Definition at line 88 of file odom_estimation.hpp.


The documentation for this class was generated from the following files:


floam
Author(s): Han Wang
autogenerated on Mon Feb 28 2022 22:25:11