|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
18 #ifndef DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_H_
19 #define DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_H_
34 const boost::optional<Eigen::Isometry3d&> target_T_source_initial_estimate = boost::none);
38 pcl::PointCloud<pcl::PointXYZINormal>::Ptr DownsampleAndFilterCloud(
39 const pcl::PointCloud<pcl::PointXYZI>::Ptr& cloud)
const;
43 pcl::PointCloud<pcl::PointXYZINormal>::Ptr previous_point_cloud_with_normals_;
44 pcl::PointCloud<pcl::PointXYZINormal>::Ptr latest_point_cloud_with_normals_;
50 #endif // DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_H_
Definition: point_to_plane_icp_depth_odometry.h:27
boost::optional< PoseWithCovarianceAndCorrespondences > DepthImageCallback(const localization_measurements::DepthImageMeasurement &depth_image_measurement) final
Definition: point_to_plane_icp_depth_odometry.cc:65
Definition: depth_image_features_and_points.h:34
Definition: depth_odometry.h:29
PointToPlaneICPDepthOdometry(const PointToPlaneICPDepthOdometryParams ¶ms)
Definition: point_to_plane_icp_depth_odometry.cc:29
boost::optional< PoseWithCovarianceAndCorrespondences > DepthImageCallbackWithEstimate(const localization_measurements::DepthImageMeasurement &depth_image_measurement, const boost::optional< Eigen::Isometry3d & > target_T_source_initial_estimate=boost::none)
Definition: point_to_plane_icp_depth_odometry.cc:70
Definition: depth_image_measurement.h:32
const PointToPlaneICPDepthOdometryParams & params() const
Definition: point_to_plane_icp_depth_odometry.h:35
double Time
Definition: time.h:23
Definition: point_to_plane_icp_depth_odometry_params.h:27