NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <localization_common/logger.h>
#include <point_cloud_common/organized_neighbor2.h>
#include <point_cloud_common/organized_neighbor2_impl.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Point3.h>
#include <pcl/features/fpfh.h>
#include <pcl/features/integral_image_normal.h>
#include <pcl/features/normal_3d.h>
#include <pcl/features/impl/normal_3d.hpp>
#include <pcl/filters/fast_bilateral.h>
#include <pcl/filters/impl/fast_bilateral.hpp>
#include <pcl/filters/normal_space.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/impl/kdtree_flann.hpp>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/search/impl/kdtree.hpp>
#include <pcl/search/impl/search.hpp>
#include <limits>
#include <vector>
Go to the source code of this file.
Namespaces | |
point_cloud_common | |
Functions | |
template<typename PointType , typename PointWithNormalType > | |
void | point_cloud_common::EstimateNormals (const typename pcl::PointCloud< PointType >::Ptr cloud, const double search_radius, pcl::PointCloud< PointWithNormalType > &cloud_with_normals) |
template<typename PointType , typename PointWithNormalType > | |
void | point_cloud_common::EstimateOrganizedNormals (const typename pcl::PointCloud< PointType >::Ptr cloud, const typename pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >::NormalEstimationMethod method, const bool depth_dependent_smoothing, const double max_depth_change_factor, const double normal_smoothing_size, pcl::PointCloud< PointWithNormalType > &cloud_with_normals) |
template<typename PointType > | |
void | point_cloud_common::NormalSpaceSubsampling (typename pcl::PointCloud< PointType >::Ptr cloud, const int bins_per_axis, const int num_samples) |
Eigen::Matrix4f | point_cloud_common::RansacIA (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr source_cloud, const pcl::PointCloud< pcl::PointXYZINormal >::Ptr target_cloud) |
pcl::PointCloud< pcl::FPFHSignature33 >::Ptr | point_cloud_common::EstimateHistogramFeatures (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr cloud_with_normals) |
Eigen::Matrix< double, 1, 6 > | point_cloud_common::PointToPlaneJacobian (const gtsam::Point3 &source_point, const gtsam::Vector3 &normal, const gtsam::Pose3 &target_T_source) |
Eigen::Matrix< double, 3, 6 > | point_cloud_common::PointToPointJacobian (const gtsam::Point3 &source_point, const gtsam::Pose3 &target_T_source) |
Eigen::Isometry3d | point_cloud_common::RelativeTransformUmeyama (const std::vector< Eigen::Vector3d > &source_points, const std::vector< Eigen::Vector3d > &target_points) |
template<typename PointType > | |
boost::optional< Eigen::Vector3d > | point_cloud_common::GetNormal (const Eigen::Vector3d &point, const pcl::PointCloud< PointType > &cloud, const pcl::search::KdTree< PointType > &kdtree, const double search_radius=0.03) |
template<typename PointType > | |
bool | point_cloud_common::computePointNormal (const pcl::PointCloud< PointType > &cloud, const std::vector< int > &indices, float &normal_x, float &normal_y, float &normal_z, float &curvature) |
boost::optional< Eigen::Matrix< double, 6, 6 > > | point_cloud_common::PointToPointCovariance (const std::vector< Eigen::Vector3d > &source_points, const Eigen::Isometry3d &target_T_source) |
boost::optional< Eigen::Matrix< double, 6, 6 > > | point_cloud_common::PointToPlaneCovariance (const std::vector< Eigen::Vector3d > &source_points, const std::vector< Eigen::Vector3d > &target_normals, const Eigen::Isometry3d &target_T_source) |
template<typename PointType > | |
Eigen::Vector3d | point_cloud_common::Vector3d (const PointType &point) |
template<typename PointType > | |
Eigen::Vector3d | point_cloud_common::NormalVector3d (const PointType &point_with_normal) |
pcl::PointXYZI | point_cloud_common::Interpolate (const pcl::PointXYZI &point_a, const pcl::PointXYZI &point_b, const double alpha) |
template<typename PointType > | |
bool | point_cloud_common::ValidPoint (const PointType &point)=delete |
template<> | |
bool | point_cloud_common::ValidPoint< pcl::PointXYZ > (const pcl::PointXYZ &point) |
template<> | |
bool | point_cloud_common::ValidPoint< pcl::PointXYZI > (const pcl::PointXYZI &point) |
template<> | |
bool | point_cloud_common::ValidPoint< pcl::PointNormal > (const pcl::PointNormal &point) |
template<> | |
bool | point_cloud_common::ValidPoint< pcl::PointXYZINormal > (const pcl::PointXYZINormal &point) |
template<typename Type > | |
bool | point_cloud_common::ApproxZero (const Type &point, const double epsilon=1e-5) |
template<typename PointXYZType > | |
bool | point_cloud_common::NonzeroPointXYZ (const PointXYZType &point) |
template<typename PointXYZType > | |
bool | point_cloud_common::ValidPointXYZ (const PointXYZType &point) |
template<typename PointNormalType > | |
bool | point_cloud_common::ValidNormal (const PointNormalType &point) |
template<typename PointIntensityType > | |
bool | point_cloud_common::ValidIntensity (const PointIntensityType &point) |
template<typename PointType > | |
void | point_cloud_common::RemoveInvalidAndZeroPoints (pcl::PointCloud< PointType > &cloud) |
template<typename PointType > | |
void | point_cloud_common::ReplaceZerosWithNans (typename pcl::PointCloud< PointType > &cloud) |
template<typename PointType > | |
pcl::PointCloud< PointType >::Ptr | point_cloud_common::DownsamplePointCloud (const typename pcl::PointCloud< PointType >::Ptr cloud, const double leaf_size) |
template<typename PointType > | |
pcl::PointCloud< PointType >::Ptr | point_cloud_common::BilateralFilterOrganizedCloud (const typename pcl::PointCloud< PointType >::Ptr cloud, const double sigma_s, const double sigma_r) |
template<typename PointType > | |
void | point_cloud_common::FilterCorrespondences (const typename pcl::PointCloud< PointType > &input_cloud, const typename pcl::PointCloud< PointType > &target_cloud, pcl::Correspondences &correspondences) |
template<typename PointType > | |
pcl::PointCloud< PointType >::Ptr | point_cloud_common::FilteredPointCloud (const typename pcl::PointCloud< PointType >::Ptr unfiltered_cloud) |
template<typename PointType , typename PointWithNormalType > | |
pcl::PointCloud< PointWithNormalType >::Ptr | point_cloud_common::FilteredPointCloudWithNormals (const typename pcl::PointCloud< PointType >::Ptr unfiltered_cloud, const double search_radius) |