Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(ndt_scan_matcher): refactor callbackSensorPoints #1757

Merged
Show file tree
Hide file tree
Changes from 44 commits
Commits
Show all changes
48 commits
Select commit Hold shift + click to select a range
1520063
now works
kminoda Sep 1, 2022
1d4a236
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
0176154
refactored alignUsingMonteCarlo
kminoda Sep 1, 2022
b701782
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 1, 2022
ba99dc9
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
a36b93d
output from screen to log
kminoda Sep 1, 2022
36da95b
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 1, 2022
b1b6cdc
lowerCamelCase to snake_case
kminoda Sep 1, 2022
696d5a7
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
24baaa5
remove iteration_num_max from NdtResult
kminoda Sep 1, 2022
46ab9a4
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 1, 2022
739c8fe
minor fix
kminoda Sep 1, 2022
06f4b94
remove publish_scalars
kminoda Sep 1, 2022
d32d443
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
c0be8fb
move publish_tf out from publish_pose
kminoda Sep 1, 2022
f6f06d2
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 1, 2022
d39db9a
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
01dd603
simplified the function transform_sensor_points
kminoda Sep 1, 2022
dda7cfa
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 1, 2022
6bb69d3
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
95872a0
WIP pose_array_interpolator
kminoda Sep 1, 2022
6994058
added pose_array_interpolator class
kminoda Sep 1, 2022
0f6467e
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 1, 2022
7ad8d52
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 1, 2022
c60c436
remove unnecessary code
kminoda Sep 1, 2022
223fc13
resolve conflict
kminoda Sep 1, 2022
caf72fd
removed std::pow(*, 2)
kminoda Sep 7, 2022
b255b43
reflected comments
kminoda Sep 7, 2022
96402d9
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 7, 2022
b0bc5dc
minor fix in publish_point_cloud (seperated pcd transform and publish)
kminoda Sep 7, 2022
e274fec
removed unnecessary commentout
kminoda Sep 7, 2022
13d2435
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 7, 2022
4a46c45
changed Eigen::Vector3f to Eigen::Vector3d
kminoda Sep 7, 2022
f236330
Merge branch 'main' into refactor/ndt_scan_matcher_callbackSensorPoints
kminoda Sep 21, 2022
9e4c790
Merge branch 'main' into refactor/ndt_scan_matcher_callbackSensorPoints
kminoda Sep 21, 2022
0a2bcef
reverted No pose warning for initial pose
kminoda Sep 21, 2022
11c1eda
from_HOGE_to_FUGA to HOGE_to_FUGA
kminoda Sep 21, 2022
0e31356
validate_* functions should not change member variables implicitely
kminoda Sep 21, 2022
5de545c
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 21, 2022
d4b05d3
removed member function that implicitely changes the member variables
kminoda Sep 21, 2022
c90c77d
Merge branch 'refactor/ndt_scan_matcher_callbackSensorPoints' of gith…
kminoda Sep 21, 2022
c438c00
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 21, 2022
75632bf
remote 'ros' and 'eigen' prefix from utiility function name
kminoda Sep 21, 2022
d8a91cf
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 21, 2022
f80b03f
debugged
kminoda Sep 21, 2022
e79f5b9
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 21, 2022
a41b7c4
added a name for each validation booleans
kminoda Sep 24, 2022
24b77a2
ci(pre-commit): autofix
pre-commit-ci[bot] Sep 24, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions localization/ndt_scan_matcher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ ament_auto_add_executable(ndt_scan_matcher
src/ndt_scan_matcher_node.cpp
src/ndt_scan_matcher_core.cpp
src/util_func.cpp
src/pose_array_interpolator.cpp
)

ament_auto_package(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <string>

visualization_msgs::msg::MarkerArray makeDebugMarkers(
visualization_msgs::msg::MarkerArray make_debug_markers(
const builtin_interfaces::msg::Time & stamp, const std::string & map_frame_,
const geometry_msgs::msg::Vector3 & scale, const Particle & particle, const size_t i);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,17 @@ enum class ConvergedParamType {
NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD = 1
};

struct NdtResult
{
geometry_msgs::msg::Pose pose;
float transform_probability;
float nearest_voxel_transformation_likelihood;
int iteration_num;
std::vector<geometry_msgs::msg::Pose> transformation_array;
};

template <typename PointSource, typename PointTarget>
std::shared_ptr<NormalDistributionsTransformBase<PointSource, PointTarget>> getNDT(
std::shared_ptr<NormalDistributionsTransformBase<PointSource, PointTarget>> get_ndt(
const NDTImplementType & ndt_mode)
{
std::shared_ptr<NormalDistributionsTransformBase<PointSource, PointTarget>> ndt_ptr;
Expand Down Expand Up @@ -107,40 +116,59 @@ class NDTScanMatcher : public rclcpp::Node
NDTScanMatcher();

private:
void serviceNDTAlign(
void service_ndt_align(
const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req,
tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res);

void callbackMapPoints(sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud2_msg_ptr);
void callbackSensorPoints(sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud2_msg_ptr);
void callbackInitialPose(
void callback_map_points(sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud2_msg_ptr);
void callback_sensor_points(sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud2_msg_ptr);
void callback_initial_pose(
geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr);
void callbackRegularizationPose(
void callback_regularization_pose(
geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr);

geometry_msgs::msg::PoseWithCovarianceStamped alignUsingMonteCarlo(
NdtResult align(const geometry_msgs::msg::Pose & initial_pose_msg);
geometry_msgs::msg::PoseWithCovarianceStamped align_using_monte_carlo(
const std::shared_ptr<NormalDistributionsTransformBase<PointSource, PointTarget>> & ndt_ptr,
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov);

void updateTransforms();

void publishTF(
const std::string & child_frame_id, const geometry_msgs::msg::PoseStamped & pose_msg);
bool getTransform(
void transform_sensor_measurement(
const std::string source_frame, const std::string target_frame,
const pcl::shared_ptr<pcl::PointCloud<PointSource>> sensor_points_input_ptr,
pcl::shared_ptr<pcl::PointCloud<PointSource>> sensor_points_output_ptr);
void update_transforms();

void publish_tf(
const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg);
void publish_pose(
const rclcpp::Time & sensor_ros_time, const geometry_msgs::msg::Pose & result_pose_msg,
const bool is_converged);
void publish_point_cloud(
const rclcpp::Time & sensor_ros_time, const std::string & frame_id,
const std::shared_ptr<const pcl::PointCloud<PointSource>> & sensor_points_mapTF_ptr);
void publish_marker(
const rclcpp::Time & sensor_ros_time, const std::vector<geometry_msgs::msg::Pose> & pose_array);
void publish_initial_to_result_distances(
const rclcpp::Time & sensor_ros_msg, const geometry_msgs::msg::Pose & result_pose_msg,
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_cov_msg,
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg,
const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_new_msg);

bool get_transform(
const std::string & target_frame, const std::string & source_frame,
const geometry_msgs::msg::TransformStamped::SharedPtr & transform_stamped_ptr);

bool validateTimeStampDifference(
const rclcpp::Time & target_time, const rclcpp::Time & reference_time,
const double time_tolerance_sec);
bool validatePositionDifference(
const geometry_msgs::msg::Point & target_point,
const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_);
bool validate_num_iteration(const int iter_num, const int max_iter_num);
bool validate_score(
const double score, const double score_threshold, const std::string score_name);
bool validate_converged_param(
const double & transform_probability, const double & nearest_voxel_transformation_likelihood);

std::optional<Eigen::Matrix4f> interpolateRegularizationPose(
std::optional<Eigen::Matrix4f> interpolate_regularization_pose(
const rclcpp::Time & sensor_ros_time);
void add_regularization_pose(const rclcpp::Time & sensor_ros_time);

void timerDiagnostic();
void timer_diagnostic();

rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr initial_pose_sub_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr map_points_sub_;
Expand Down Expand Up @@ -197,7 +225,7 @@ class NDTScanMatcher : public rclcpp::Node

std::deque<geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr>
initial_pose_msg_ptr_array_;
std::mutex ndt_map_mtx_;
std::mutex ndt_ptr_mtx_;
std::mutex initial_pose_array_mtx_;

OMPParams omp_params_;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
// Copyright 2015-2019 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NDT_SCAN_MATCHER__POSE_ARRAY_INTERPOLATOR_HPP_
#define NDT_SCAN_MATCHER__POSE_ARRAY_INTERPOLATOR_HPP_

#include "ndt_scan_matcher/util_func.hpp"

#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>

#include <deque>

class PoseArrayInterpolator
{
private:
using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped;

public:
PoseArrayInterpolator(
rclcpp::Node * node, const rclcpp::Time target_ros_time,
const std::deque<PoseWithCovarianceStamped::ConstSharedPtr> & pose_msg_ptr_array,
const double & pose_timeout_sec, const double & pose_distance_tolerance_meters);

PoseArrayInterpolator(
rclcpp::Node * node, const rclcpp::Time target_ros_time,
const std::deque<PoseWithCovarianceStamped::ConstSharedPtr> & pose_msg_ptr_array);

PoseWithCovarianceStamped get_current_pose();
PoseWithCovarianceStamped get_old_pose();
PoseWithCovarianceStamped get_new_pose();
bool is_success();

private:
rclcpp::Logger logger_;
rclcpp::Clock clock_;
const PoseWithCovarianceStamped::SharedPtr current_pose_ptr_;
PoseWithCovarianceStamped::SharedPtr old_pose_ptr_;
PoseWithCovarianceStamped::SharedPtr new_pose_ptr_;
bool success_;

bool validate_time_stamp_difference(
const rclcpp::Time & target_time, const rclcpp::Time & reference_time,
const double time_tolerance_sec) const;
bool validate_position_difference(
const geometry_msgs::msg::Point & target_point,
const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_) const;
};

#endif // NDT_SCAN_MATCHER__POSE_ARRAY_INTERPOLATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -36,41 +36,44 @@
#include <vector>

// ref by http://takacity.blog.fc2.com/blog-entry-69.html
std_msgs::msg::ColorRGBA ExchangeColorCrc(double x);
std_msgs::msg::ColorRGBA exchange_color_crc(double x);

double calcDiffForRadian(const double lhs_rad, const double rhs_rad);
double calc_diff_for_radian(const double lhs_rad, const double rhs_rad);

// x: roll, y: pitch, z: yaw
geometry_msgs::msg::Vector3 getRPY(const geometry_msgs::msg::Pose & pose);
geometry_msgs::msg::Vector3 getRPY(const geometry_msgs::msg::PoseStamped & pose);
geometry_msgs::msg::Vector3 getRPY(const geometry_msgs::msg::PoseWithCovarianceStamped & pose);
geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose);
geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose);
geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose);

geometry_msgs::msg::Twist calcTwist(
geometry_msgs::msg::Twist calc_twist(
const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b);

void getNearestTimeStampPose(
void get_nearest_timestamp_pose(
const std::deque<geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr> &
pose_cov_msg_ptr_array,
const rclcpp::Time & time_stamp,
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & output_old_pose_cov_msg_ptr,
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & output_new_pose_cov_msg_ptr);

geometry_msgs::msg::PoseStamped interpolatePose(
geometry_msgs::msg::PoseStamped interpolate_pose(
const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b,
const rclcpp::Time & time_stamp);

geometry_msgs::msg::PoseStamped interpolatePose(
geometry_msgs::msg::PoseStamped interpolate_pose(
const geometry_msgs::msg::PoseWithCovarianceStamped & pose_a,
const geometry_msgs::msg::PoseWithCovarianceStamped & pose_b, const rclcpp::Time & time_stamp);

void popOldPose(
void pop_old_pose(
std::deque<geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr> &
pose_cov_msg_ptr_array,
const rclcpp::Time & time_stamp);

Eigen::Affine3d fromRosPoseToEigen(const geometry_msgs::msg::Pose & ros_pose);
Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose);
Eigen::Matrix4f pose_to_matrix4f(const geometry_msgs::msg::Pose & ros_pose);
geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_matrix);
Eigen::Vector3d point_to_vector3d(const geometry_msgs::msg::Point & ros_pos);

std::vector<geometry_msgs::msg::Pose> createRandomPoseArray(
std::vector<geometry_msgs::msg::Pose> create_random_pose_array(
const geometry_msgs::msg::PoseWithCovarianceStamped & base_pose_with_cov, const int particle_num);

template <class T>
Expand All @@ -81,4 +84,6 @@ T transform(const T & input, const geometry_msgs::msg::TransformStamped & transf
return output;
}

double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2);

#endif // NDT_SCAN_MATCHER__UTIL_FUNC_HPP_
14 changes: 7 additions & 7 deletions localization/ndt_scan_matcher/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "ndt_scan_matcher/util_func.hpp"

visualization_msgs::msg::MarkerArray makeDebugMarkers(
visualization_msgs::msg::MarkerArray make_debug_markers(
const builtin_interfaces::msg::Time & stamp, const std::string & map_frame_,
const geometry_msgs::msg::Vector3 & scale, const Particle & particle, const size_t i)
{
Expand All @@ -34,32 +34,32 @@ visualization_msgs::msg::MarkerArray makeDebugMarkers(

marker.ns = "initial_pose_transform_probability_color_marker";
marker.pose = particle.initial_pose;
marker.color = ExchangeColorCrc(particle.score / 4.5);
marker.color = exchange_color_crc(particle.score / 4.5);
marker_array.markers.push_back(marker);

marker.ns = "initial_pose_iteration_color_marker";
marker.pose = particle.initial_pose;
marker.color = ExchangeColorCrc((1.0 * particle.iteration) / 30.0);
marker.color = exchange_color_crc((1.0 * particle.iteration) / 30.0);
marker_array.markers.push_back(marker);

marker.ns = "initial_pose_index_color_marker";
marker.pose = particle.initial_pose;
marker.color = ExchangeColorCrc((1.0 * i) / 100);
marker.color = exchange_color_crc((1.0 * i) / 100);
marker_array.markers.push_back(marker);

marker.ns = "result_pose_transform_probability_color_marker";
marker.pose = particle.result_pose;
marker.color = ExchangeColorCrc(particle.score / 4.5);
marker.color = exchange_color_crc(particle.score / 4.5);
marker_array.markers.push_back(marker);

marker.ns = "result_pose_iteration_color_marker";
marker.pose = particle.result_pose;
marker.color = ExchangeColorCrc((1.0 * particle.iteration) / 30.0);
marker.color = exchange_color_crc((1.0 * particle.iteration) / 30.0);
marker_array.markers.push_back(marker);

marker.ns = "result_pose_index_color_marker";
marker.pose = particle.result_pose;
marker.color = ExchangeColorCrc((1.0 * i) / 100);
marker.color = exchange_color_crc((1.0 * i) / 100);
marker_array.markers.push_back(marker);

return marker_array;
Expand Down
Loading