|
| 1 | +#include <picknik_registration/ndt_registration.hpp> |
| 2 | +#include <pcl/registration/ndt.h> |
| 3 | +#include <tl_expected/expected.hpp> |
| 4 | +#include <moveit_studio_behavior_interface/async_behavior_base.hpp> |
| 5 | +#include <moveit_studio_behavior_interface/check_for_error.hpp> |
| 6 | +// #include <moveit_studio_vision/geometry_types.hpp> |
| 7 | +#include <geometry_msgs/msg/pose_stamped.hpp> |
| 8 | +#include <sensor_msgs/msg/point_cloud2.hpp> |
| 9 | +#include <std_msgs/msg/header.hpp> |
| 10 | +#include <tf2_eigen/tf2_eigen.hpp> |
| 11 | +#include <tl_expected/expected.hpp> |
| 12 | +#include <moveit_studio_vision_msgs/msg/mask3_d.hpp> |
| 13 | +#include <pcl_conversions/pcl_conversions.h> |
| 14 | +#include <moveit_studio_vision/common/get_all_indices.hpp> |
| 15 | +#include <moveit_studio_vision/common/select_point_indices.hpp> |
| 16 | +#include <moveit_studio_vision/pointcloud/point_cloud_tools.hpp> |
| 17 | +#include <pcl/filters/approximate_voxel_grid.h> |
| 18 | +#include <pcl/point_types.h> |
| 19 | +#include <pcl/point_cloud.h> |
| 20 | +#include <pcl/features/normal_3d.h> |
| 21 | +#include <pcl/features/fpfh.h> |
| 22 | +#include <pcl/keypoints/uniform_sampling.h> |
| 23 | +#include <pcl/registration/sample_consensus_prerejective.h> |
| 24 | +#include <pcl/search/kdtree.h> |
| 25 | + |
| 26 | +namespace picknik_registration |
| 27 | +{ |
| 28 | +namespace |
| 29 | +{ |
| 30 | + |
| 31 | +std::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB>> |
| 32 | +getFilteredPointCloudFromMessage(const sensor_msgs::msg::PointCloud2& cloud_msg) |
| 33 | +{ |
| 34 | + const auto cloud = std::make_shared<pcl::PointCloud<pcl::PointXYZRGB>>(); |
| 35 | + pcl::fromROSMsg(cloud_msg, *cloud); |
| 36 | + |
| 37 | + const pcl::PointIndices valid_indices = moveit_studio::selectPointIndices(*cloud, moveit_studio::point_cloud_tools::getAllIndices(cloud), |
| 38 | + moveit_studio::NeitherNanNorNearZeroPointValidator<pcl::PointXYZRGB>); |
| 39 | + auto filtered_cloud = std::make_shared<pcl::PointCloud<pcl::PointXYZRGB>>(); |
| 40 | + pcl::copyPointCloud(*cloud, valid_indices, *filtered_cloud); |
| 41 | + |
| 42 | + return filtered_cloud; |
| 43 | +} |
| 44 | + |
| 45 | +} // namespace |
| 46 | + |
| 47 | +NDTRegistration::NDTRegistration( |
| 48 | + const std::string& name, const BT::NodeConfiguration& config, |
| 49 | + const std::shared_ptr<moveit_studio::behaviors::BehaviorContext>& shared_resources) |
| 50 | + : moveit_studio::behaviors::AsyncBehaviorBase(name, config, shared_resources) |
| 51 | +{ |
| 52 | +} |
| 53 | + |
| 54 | + |
| 55 | +BT::PortsList NDTRegistration::providedPorts() |
| 56 | +{ |
| 57 | + return { BT::InputPort<sensor_msgs::msg::PointCloud2>("base_point_cloud", "{point_cloud}", |
| 58 | + "Point cloud to align with the target point cloud."), |
| 59 | + BT::InputPort<sensor_msgs::msg::PointCloud2>("target_point_cloud", "{target_point_cloud}", |
| 60 | + "Point cloud to which align the base point cloud."), |
| 61 | + BT::InputPort<int>("max_iterations", 30, |
| 62 | + "Maximum number of attempts to find the transform. Setting a higher number of iterations " |
| 63 | + "will allow the solver to converge even if the initial estimate of the transform was far " |
| 64 | + "from the actual transform, but it may take longer to complete."), |
| 65 | + BT::InputPort<double>("transformation_epsilon", 0.001, |
| 66 | + "Minimum transformation difference for termination condition <double>"), |
| 67 | + BT::InputPort<double>("step_size", 0.1, |
| 68 | + "Maximum step size for More-Thuente line search <double>"), |
| 69 | + BT::InputPort<double>("resolution", 1.0, |
| 70 | + "Resolution of NDT grid structure (VoxelGridCovariance) <double>"), |
| 71 | + BT::InputPort<double>("inlier_threshold", 1.0, |
| 72 | + "Resolution of NDT grid structure (VoxelGridCovariance) <double>"), |
| 73 | + BT::OutputPort<geometry_msgs::msg::PoseStamped>("target_pose_in_base_frame", "{target_pose}", |
| 74 | + "The pose of the target point cloud relative to the frame " |
| 75 | + "of the base point cloud.") }; |
| 76 | +} |
| 77 | +BT::KeyValueVector NDTRegistration::metadata() |
| 78 | +{ |
| 79 | + return { {"description", "Finds the pose of a target point cloud relative to the base frame of a base point cloud using the Normal Distributions Transform (NDT) algorithm"} }; |
| 80 | +} |
| 81 | + |
| 82 | + |
| 83 | +tl::expected<bool, std::string> NDTRegistration::doWork() |
| 84 | +{ |
| 85 | + const auto base_point_cloud_msg = getInput<sensor_msgs::msg::PointCloud2>("base_point_cloud"); |
| 86 | + const auto target_point_cloud_msg = getInput<sensor_msgs::msg::PointCloud2>("target_point_cloud"); |
| 87 | + const auto max_iterations = getInput<int>("max_iterations"); |
| 88 | + const auto transformation_epsilon = getInput<double>("transformation_epsilon"); |
| 89 | + const auto step_size = getInput<double>("step_size"); |
| 90 | + const auto resolution = getInput<double>("resolution"); |
| 91 | + |
| 92 | + if (const auto error = |
| 93 | + moveit_studio::behaviors::maybe_error(base_point_cloud_msg, target_point_cloud_msg, max_iterations, transformation_epsilon, step_size, resolution); |
| 94 | + error) |
| 95 | + { |
| 96 | + return tl::make_unexpected("Failed to get required value from input data port: " + error.value()); |
| 97 | + } |
| 98 | + |
| 99 | + const auto base_cloud = getFilteredPointCloudFromMessage(base_point_cloud_msg.value()); |
| 100 | + if (base_cloud->empty()) |
| 101 | + { |
| 102 | + return tl::make_unexpected("Base point cloud has no valid points"); |
| 103 | + } |
| 104 | + const auto target_cloud = getFilteredPointCloudFromMessage(target_point_cloud_msg.value()); |
| 105 | + if (target_cloud->empty()) |
| 106 | + { |
| 107 | + return tl::make_unexpected("Target point cloud has no valid points"); |
| 108 | + } |
| 109 | + // Initializing Normal Distributions Transform (NDT). |
| 110 | + pcl::NormalDistributionsTransform<pcl::PointXYZRGB, pcl::PointXYZRGB> ndt; |
| 111 | + |
| 112 | + // Setting scale dependent NDT parameters |
| 113 | + // Setting minimum transformation difference for termination condition. |
| 114 | + ndt.setTransformationEpsilon (transformation_epsilon.value()); |
| 115 | + // Setting maximum step size for More-Thuente line search. |
| 116 | + ndt.setStepSize (step_size.value()); |
| 117 | + //Setting Resolution of NDT grid structure (VoxelGridCovariance). |
| 118 | + ndt.setResolution (resolution.value()); |
| 119 | + |
| 120 | + // Setting max number of registration iterations. |
| 121 | + ndt.setMaximumIterations (max_iterations.value()); |
| 122 | + |
| 123 | + // Setting point cloud to be aligned. |
| 124 | + ndt.setInputSource (base_cloud); |
| 125 | + // Setting point cloud to be aligned to. |
| 126 | + ndt.setInputTarget (target_cloud); |
| 127 | + |
| 128 | + |
| 129 | + // Calculating required rigid transform to align the input cloud to the target cloud. |
| 130 | + pcl::PointCloud<pcl::PointXYZRGB>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZRGB>); |
| 131 | + ndt.align (*output_cloud); |
| 132 | + |
| 133 | + if (!ndt.hasConverged()) |
| 134 | + { |
| 135 | + return tl::make_unexpected("NDT could not converge to a transform that aligns both point clouds"); |
| 136 | + } |
| 137 | + |
| 138 | + geometry_msgs::msg::PoseStamped out; |
| 139 | + out.pose = tf2::toMsg(Eigen::Isometry3d{ ndt.getFinalTransformation().cast<double>() }); |
| 140 | + out.header.frame_id = base_point_cloud_msg.value().header.frame_id; |
| 141 | + out.header.stamp = base_point_cloud_msg.value().header.stamp; |
| 142 | + setOutput("target_pose_in_base_frame", out); |
| 143 | + |
| 144 | + return true; |
| 145 | +} |
| 146 | + |
| 147 | + |
| 148 | +} // namespace picknik_registration |
0 commit comments