Skip to content

Commit

Permalink
feat(ndt_scan_matcher): add nearest voxel transfromation probability (#…
Browse files Browse the repository at this point in the history
…364)

* feat(ndt_scan_matcher): add nearest voxel transfromation probability

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* add calculateTransformationProbability funcs

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* add calculateTransformationProbability funcs

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* add converged_param_nearest_voxel_transformation_probability

Signed-off-by: Yamato Ando <yamato.ando@gmail.com>

* fix error

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* refactoring convergence conditions

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* fix error

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* remove debug code

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* remove debug code

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* ci(pre-commit): autofix

* fix typo

Signed-off-by: Yamato Ando <yamato.ando@gmail.com>

* ci(pre-commit): autofix

* rename likelihood

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

* ci(pre-commit): autofix

* avoid a warning unused parameter

Signed-off-by: YamatoAndo <yamato.ando@gmail.com>

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
YamatoAndo and pre-commit-ci[bot] authored Mar 31, 2022
1 parent d434d40 commit 3a9bbf2
Show file tree
Hide file tree
Showing 12 changed files with 198 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,19 @@
# The number of iterations required to calculate alignment
max_iterations: 30

# Converged param type
# 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD
# NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD is only available when NDTImplementType::OMP is selected
converged_param_type: 1

# If converged_param_type is 0
# Threshold for deciding whether to trust the estimation result
converged_param_transform_probability: 3.0

# If converged_param_type is 1
# Threshold for deciding whether to trust the estimation result
converged_param_nearest_voxel_transformation_likelihood: 2.3

# The number of particles to estimate initial pose
initial_estimate_particles_num: 100

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<include file="$(find-pkg-share ndt_scan_matcher)/launch/ndt_scan_matcher.launch.xml">
<arg name="input_map_points_topic" value="/map/pointcloud_map"/>
<arg name="input_sensor_points_topic" value="/localization/util/downsample/pointcloud"/>
<arg name="input/pointcloud" value="/localization/util/downsample/pointcloud"/>
<arg name="input_initial_pose_topic" value="/localization/pose_twist_fusion_filter/pose_with_covariance_without_yawbias"/>


Expand Down
6 changes: 6 additions & 0 deletions localization/ndt/include/ndt/base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ class NormalDistributionsTransformBase
virtual double getStepSize() const = 0;
virtual double getTransformationEpsilon() = 0;
virtual double getTransformationProbability() const = 0;
virtual double getNearestVoxelTransformationLikelihood() const = 0;
virtual double getFitnessScore() = 0;
virtual boost::shared_ptr<const pcl::PointCloud<PointTarget>> getInputTarget() const = 0;
virtual boost::shared_ptr<const pcl::PointCloud<PointSource>> getInputSource() const = 0;
Expand All @@ -54,6 +55,11 @@ class NormalDistributionsTransformBase
virtual Eigen::Matrix<double, 6, 6> getHessian() const = 0;

virtual boost::shared_ptr<pcl::search::KdTree<PointTarget>> getSearchMethodTarget() const = 0;

virtual double calculateTransformationProbability(
const pcl::PointCloud<PointSource> & trans_cloud) const = 0;
virtual double calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const = 0;
};

#include "ndt/impl/base.hpp"
Expand Down
23 changes: 23 additions & 0 deletions localization/ndt/include/ndt/impl/omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,13 @@ double NormalDistributionsTransformOMP<PointSource, PointTarget>::getTransformat
return ndt_ptr_->getTransformationProbability();
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformOMP<
PointSource, PointTarget>::getNearestVoxelTransformationLikelihood() const
{
return ndt_ptr_->getNearestVoxelTransformationLikelihood();
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformOMP<PointSource, PointTarget>::getFitnessScore()
{
Expand Down Expand Up @@ -157,6 +164,22 @@ NormalDistributionsTransformOMP<PointSource, PointTarget>::getSearchMethodTarget
return ndt_ptr_->getSearchMethodTarget();
}

template <class PointSource, class PointTarget>
double
NormalDistributionsTransformOMP<PointSource, PointTarget>::calculateTransformationProbability(
const pcl::PointCloud<PointSource> & trans_cloud) const
{
return ndt_ptr_->calculateTransformationProbability(trans_cloud);
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformOMP<PointSource, PointTarget>::
calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const
{
return ndt_ptr_->calculateNearestVoxelTransformationLikelihood(trans_cloud);
}

template <class PointSource, class PointTarget>
void NormalDistributionsTransformOMP<PointSource, PointTarget>::setNumThreads(int n)
{
Expand Down
27 changes: 27 additions & 0 deletions localization/ndt/include/ndt/impl/pcl_generic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,14 @@ double NormalDistributionsTransformPCLGeneric<
return ndt_ptr_->getTransformationProbability();
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLGeneric<
PointSource, PointTarget>::getNearestVoxelTransformationLikelihood() const
{
// return ndt_ptr_->getNearestVoxelTransformationLikelihood();
return 0.0;
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLGeneric<PointSource, PointTarget>::getFitnessScore()
{
Expand Down Expand Up @@ -160,4 +168,23 @@ NormalDistributionsTransformPCLGeneric<PointSource, PointTarget>::getSearchMetho
return ndt_ptr_->getSearchMethodTarget();
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLGeneric<PointSource, PointTarget>::
calculateTransformationProbability(const pcl::PointCloud<PointSource> & trans_cloud) const
{
(void)trans_cloud;
// return ndt_ptr_->calculateTransformationProbability(trans_cloud);
return 0.0;
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLGeneric<PointSource, PointTarget>::
calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const
{
(void)trans_cloud;
// return ndt_ptr_->calculateNearestVoxelTransformationLikelihood(trans_cloud);
return 0.0;
}

#endif // NDT__IMPL__PCL_GENERIC_HPP_
27 changes: 27 additions & 0 deletions localization/ndt/include/ndt/impl/pcl_modified.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,14 @@ double NormalDistributionsTransformPCLModified<
return ndt_ptr_->getTransformationProbability();
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLModified<
PointSource, PointTarget>::getNearestVoxelTransformationLikelihood() const
{
// return ndt_ptr_->getTransformationLikelihood();
return 0.0;
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLModified<PointSource, PointTarget>::getFitnessScore()
{
Expand Down Expand Up @@ -160,4 +168,23 @@ NormalDistributionsTransformPCLModified<PointSource, PointTarget>::getSearchMeth
return ndt_ptr_->getSearchMethodTarget();
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLModified<PointSource, PointTarget>::
calculateTransformationProbability(const pcl::PointCloud<PointSource> & trans_cloud) const
{
(void)trans_cloud;
// return ndt_ptr_->calculateTransformationProbability(trans_cloud);
return 0.0;
}

template <class PointSource, class PointTarget>
double NormalDistributionsTransformPCLModified<PointSource, PointTarget>::
calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const
{
(void)trans_cloud;
// return ndt_ptr_->calculateNearestVoxelTransformationLikelihood(trans_cloud);
return 0.0;
}

#endif // NDT__IMPL__PCL_MODIFIED_HPP_
6 changes: 6 additions & 0 deletions localization/ndt/include/ndt/omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ class NormalDistributionsTransformOMP
double getStepSize() const override;
double getTransformationEpsilon() override;
double getTransformationProbability() const override;
double getNearestVoxelTransformationLikelihood() const override;
double getFitnessScore() override;
boost::shared_ptr<const pcl::PointCloud<PointTarget>> getInputTarget() const override;
boost::shared_ptr<const pcl::PointCloud<PointSource>> getInputSource() const override;
Expand All @@ -58,6 +59,11 @@ class NormalDistributionsTransformOMP

boost::shared_ptr<pcl::search::KdTree<PointTarget>> getSearchMethodTarget() const override;

double calculateTransformationProbability(
const pcl::PointCloud<PointSource> & trans_cloud) const override;
double calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const override;

// only OMP Impl
void setNumThreads(int n);
void setNeighborhoodSearchMethod(pclomp::NeighborSearchMethod method);
Expand Down
6 changes: 6 additions & 0 deletions localization/ndt/include/ndt/pcl_generic.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ class NormalDistributionsTransformPCLGeneric
double getStepSize() const override;
double getTransformationEpsilon() override;
double getTransformationProbability() const override;
double getNearestVoxelTransformationLikelihood() const override;
double getFitnessScore() override;
boost::shared_ptr<const pcl::PointCloud<PointTarget>> getInputTarget() const override;
boost::shared_ptr<const pcl::PointCloud<PointSource>> getInputSource() const override;
Expand All @@ -58,6 +59,11 @@ class NormalDistributionsTransformPCLGeneric

boost::shared_ptr<pcl::search::KdTree<PointTarget>> getSearchMethodTarget() const override;

double calculateTransformationProbability(
const pcl::PointCloud<PointSource> & trans_cloud) const override;
double calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const override;

private:
boost::shared_ptr<pcl::NormalDistributionsTransform<PointSource, PointTarget>> ndt_ptr_;
};
Expand Down
6 changes: 6 additions & 0 deletions localization/ndt/include/ndt/pcl_modified.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ class NormalDistributionsTransformPCLModified
double getStepSize() const override;
double getTransformationEpsilon() override;
double getTransformationProbability() const override;
double getNearestVoxelTransformationLikelihood() const override;
double getFitnessScore() override;
boost::shared_ptr<const pcl::PointCloud<PointTarget>> getInputTarget() const override;
boost::shared_ptr<const pcl::PointCloud<PointSource>> getInputSource() const override;
Expand All @@ -59,6 +60,11 @@ class NormalDistributionsTransformPCLModified

boost::shared_ptr<pcl::search::KdTree<PointTarget>> getSearchMethodTarget() const override;

double calculateTransformationProbability(
const pcl::PointCloud<PointSource> & trans_cloud) const override;
double calculateNearestVoxelTransformationLikelihood(
const pcl::PointCloud<PointSource> & trans_cloud) const override;

private:
boost::shared_ptr<pcl::NormalDistributionsTransformModified<PointSource, PointTarget>> ndt_ptr_;
};
Expand Down
10 changes: 10 additions & 0 deletions localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,19 @@
# The number of iterations required to calculate alignment
max_iterations: 30

# Converged param type
# 0=TRANSFORM_PROBABILITY, 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD
# NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD is only available when NDTImplementType::OMP is selected
converged_param_type: 1

# If converged_param_type is 0
# Threshold for deciding whether to trust the estimation result
converged_param_transform_probability: 3.0

# If converged_param_type is 1
# Threshold for deciding whether to trust the estimation result
converged_param_nearest_voxel_transformation_likelihood: 2.3

# The number of particles to estimate initial pose
initial_estimate_particles_num: 100

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,10 @@
#include <vector>

enum class NDTImplementType { PCL_GENERIC = 0, PCL_MODIFIED = 1, OMP = 2 };
enum class ConvergedParamType {
TRANSFORM_PROBABILITY = 0,
NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD = 1
};

template <typename PointSource, typename PointTarget>
std::shared_ptr<NormalDistributionsTransformBase<PointSource, PointTarget>> getNDT(
Expand Down Expand Up @@ -134,6 +138,8 @@ class NDTScanMatcher : public rclcpp::Node
initial_pose_with_covariance_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr exe_time_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr transform_probability_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr
nearest_voxel_transformation_likelihood_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Int32Stamped>::SharedPtr iteration_num_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr
initial_to_result_distance_pub_;
Expand All @@ -159,7 +165,11 @@ class NDTScanMatcher : public rclcpp::Node
std::string base_frame_;
std::string ndt_base_frame_;
std::string map_frame_;

ConvergedParamType converged_param_type_;
double converged_param_transform_probability_;
double converged_param_nearest_voxel_transformation_likelihood_;

int initial_estimate_particles_num_;
double initial_pose_timeout_sec_;
double initial_pose_distance_tolerance_m_;
Expand Down
Loading

0 comments on commit 3a9bbf2

Please sign in to comment.