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

feat(ndt_scan_matcher): smooth ndt map update #6394

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -36,44 +36,47 @@
#include <memory>
#include <optional>
#include <string>
#include <thread>
#include <vector>

class MapUpdateModule
{
using PointSource = pcl::PointXYZ;
using PointTarget = pcl::PointXYZ;
using NormalDistributionsTransform =
pclomp::MultiGridNormalDistributionsTransform<PointSource, PointTarget>;
using NdtType = pclomp::MultiGridNormalDistributionsTransform<PointSource, PointTarget>;
using NdtPtrType = std::shared_ptr<NdtType>;

public:
MapUpdateModule(
rclcpp::Node * node, std::mutex * ndt_ptr_mutex,
std::shared_ptr<NormalDistributionsTransform> ndt_ptr,
rclcpp::Node * node, std::mutex * ndt_ptr_mutex, NdtPtrType & ndt_ptr,
HyperParameters::DynamicMapLoading param);

private:
friend class NDTScanMatcher;

void update_ndt(
const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithID> & maps_to_add,
const std::vector<std::string> & map_ids_to_remove);
// Update the specified NDT
void update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt);
void update_map(const geometry_msgs::msg::Point & position);
[[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position) const;
[[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position);
void publish_partial_pcd_map();

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr loaded_pcd_pub_;

rclcpp::Client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>::SharedPtr
pcd_loader_client_;

std::shared_ptr<NormalDistributionsTransform> ndt_ptr_;
NdtPtrType & ndt_ptr_;
std::mutex * ndt_ptr_mutex_;
rclcpp::Logger logger_;
rclcpp::Clock::SharedPtr clock_;

std::optional<geometry_msgs::msg::Point> last_update_position_ = std::nullopt;

HyperParameters::DynamicMapLoading param_;

// Indicate if there is a prefetch thread waiting for being collected
NdtPtrType secondary_ndt_ptr_;
bool need_rebuild_;
SakodaShintaro marked this conversation as resolved.
Show resolved Hide resolved
};

#endif // NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_
98 changes: 74 additions & 24 deletions localization/ndt_scan_matcher/src/map_update_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
#include "ndt_scan_matcher/map_update_module.hpp"

MapUpdateModule::MapUpdateModule(
rclcpp::Node * node, std::mutex * ndt_ptr_mutex,
std::shared_ptr<NormalDistributionsTransform> ndt_ptr, HyperParameters::DynamicMapLoading param)
: ndt_ptr_(std::move(ndt_ptr)),
rclcpp::Node * node, std::mutex * ndt_ptr_mutex, NdtPtrType & ndt_ptr,
HyperParameters::DynamicMapLoading param)
: ndt_ptr_(ndt_ptr),
ndt_ptr_mutex_(ndt_ptr_mutex),
logger_(node->get_logger()),
clock_(node->get_clock()),
Expand All @@ -28,29 +28,90 @@

pcd_loader_client_ =
node->create_client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>("pcd_loader_service");

secondary_ndt_ptr_.reset(new NdtType);

if (ndt_ptr_) {
anhnv3991 marked this conversation as resolved.
Show resolved Hide resolved
*secondary_ndt_ptr_ = *ndt_ptr_;
SakodaShintaro marked this conversation as resolved.
Show resolved Hide resolved
} else {
RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Attempt to update a null NDT pointer.");

Check warning on line 37 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L37

Added line #L37 was not covered by tests
}

// Initially, a direct map update on ndt_ptr_ is needed.
// ndt_ptr_'s mutex is locked until it is fully rebuilt.
// From the second update, the update is done on secondary_ndt_ptr_,
// and ndt_ptr_ is only locked when swapping its pointer with
// secondary_ndt_ptr_.
need_rebuild_ = true;
}

bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & position) const
bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & position)

Check warning on line 48 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L48

Added line #L48 was not covered by tests
{
if (last_update_position_ == std::nullopt) {
return false;
}

const double dx = position.x - last_update_position_.value().x;
const double dy = position.y - last_update_position_.value().y;
const double distance = std::hypot(dx, dy);
if (distance + param_.lidar_radius > param_.map_radius) {
RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Dynamic map loading is not keeping up.");
// If the map does not keep up with the current position,
// lock ndt_ptr_ entirely until it is fully rebuilt.
need_rebuild_ = true;

Check warning on line 61 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L61

Added line #L61 was not covered by tests
}

return distance > param_.update_distance;
}

void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position)
{
// If the current position is super far from the previous loading position,
// lock and rebuild ndt_ptr_
if (need_rebuild_) {
ndt_ptr_mutex_->lock();
auto param = ndt_ptr_->getParams();

Check warning on line 73 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L72-L73

Added lines #L72 - L73 were not covered by tests

ndt_ptr_.reset(new NdtType);

ndt_ptr_->setParams(param);

update_ndt(position, *ndt_ptr_);
ndt_ptr_mutex_->unlock();
need_rebuild_ = false;

Check warning on line 81 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L79-L81

Added lines #L79 - L81 were not covered by tests
} else {
// Load map to the secondary_ndt_ptr, which does not require a mutex lock
// Since the update of the secondary ndt ptr and the NDT align (done on
// the main ndt_ptr_) overlap, the latency of updating/alignment reduces partly.
// If the updating is done the main ndt_ptr_, either the update or the NDT
// align will be blocked by the other.
update_ndt(position, *secondary_ndt_ptr_);

Check warning on line 88 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L88

Added line #L88 was not covered by tests

ndt_ptr_mutex_->lock();
auto input_source = ndt_ptr_->getInputSource();
ndt_ptr_ = secondary_ndt_ptr_;

Check warning on line 92 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L90-L92

Added lines #L90 - L92 were not covered by tests
ndt_ptr_->setInputSource(input_source);
ndt_ptr_mutex_->unlock();

Check warning on line 94 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L94

Added line #L94 was not covered by tests
SakodaShintaro marked this conversation as resolved.
Show resolved Hide resolved
}

secondary_ndt_ptr_.reset(new NdtType);
*secondary_ndt_ptr_ = *ndt_ptr_;

Check warning on line 98 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L98

Added line #L98 was not covered by tests

// Memorize the position of the last update
last_update_position_ = position;

// Publish the new ndt maps
publish_partial_pcd_map();
}

Check warning on line 105 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L104-L105

Added lines #L104 - L105 were not covered by tests

void MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt)

Check warning on line 107 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L107

Added line #L107 was not covered by tests
{
auto request = std::make_shared<autoware_map_msgs::srv::GetDifferentialPointCloudMap::Request>();

request->area.center_x = static_cast<float>(position.x);
request->area.center_y = static_cast<float>(position.y);
request->area.radius = static_cast<float>(param_.map_radius);
request->cached_ids = ndt_ptr_->getCurrentMapIDs();
request->cached_ids = ndt.getCurrentMapIDs();

Check warning on line 114 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L114

Added line #L114 was not covered by tests

while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) {
RCLCPP_INFO(logger_, "Waiting for pcd loader service. Check the pointcloud_map_loader.");
Expand All @@ -69,60 +130,49 @@
}
status = result.wait_for(std::chrono::seconds(1));
}
update_ndt(result.get()->new_pointcloud_with_ids, result.get()->ids_to_remove);
last_update_position_ = position;
}

void MapUpdateModule::update_ndt(
const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithID> & maps_to_add,
const std::vector<std::string> & map_ids_to_remove)
{
auto & maps_to_add = result.get()->new_pointcloud_with_ids;
auto & map_ids_to_remove = result.get()->ids_to_remove;

RCLCPP_INFO(
logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size());
if (maps_to_add.empty() && map_ids_to_remove.empty()) {
RCLCPP_INFO(logger_, "Skip map update");
return;
}
const auto exe_start_time = std::chrono::system_clock::now();

const auto exe_start_time = std::chrono::system_clock::now();

Check warning on line 144 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L144

Added line #L144 was not covered by tests
const size_t add_size = maps_to_add.size();

// Perform heavy processing outside of the lock scope
std::vector<pcl::shared_ptr<pcl::PointCloud<PointTarget>>> points_pcl(add_size);

for (size_t i = 0; i < add_size; i++) {
points_pcl[i] = pcl::make_shared<pcl::PointCloud<PointTarget>>();
pcl::fromROSMsg(maps_to_add[i].pointcloud, *points_pcl[i]);
}

(*ndt_ptr_mutex_).lock();

// Add pcd
for (size_t i = 0; i < add_size; i++) {
ndt_ptr_->addTarget(points_pcl[i], maps_to_add[i].cell_id);
ndt.addTarget(points_pcl[i], maps_to_add[i].cell_id);
}

// Remove pcd
for (const std::string & map_id_to_remove : map_ids_to_remove) {
ndt_ptr_->removeTarget(map_id_to_remove);
ndt.removeTarget(map_id_to_remove);

Check warning on line 161 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/ndt_scan_matcher/src/map_update_module.cpp#L161

Added line #L161 was not covered by tests
}

ndt_ptr_->createVoxelKdtree();

(*ndt_ptr_mutex_).unlock();
ndt.createVoxelKdtree();

const auto exe_end_time = std::chrono::system_clock::now();
const auto duration_micro_sec =
std::chrono::duration_cast<std::chrono::microseconds>(exe_end_time - exe_start_time).count();
const auto exe_time = static_cast<double>(duration_micro_sec) / 1000.0;
RCLCPP_INFO(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time);

Check warning on line 170 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

MapUpdateModule::update_ndt has a cyclomatic complexity of 10, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

publish_partial_pcd_map();
}

void MapUpdateModule::publish_partial_pcd_map()
{
pcl::PointCloud<PointTarget> map_pcl = ndt_ptr_->getVoxelPCD();

sensor_msgs::msg::PointCloud2 map_msg;
anhnv3991 marked this conversation as resolved.
Show resolved Hide resolved
pcl::toROSMsg(map_pcl, map_msg);
map_msg.header.frame_id = "map";
Expand Down
Loading