Skip to content

Commit b7f71bd

Browse files
committed
Use the std library instead of the boost library
1 parent 3945f0b commit b7f71bd

File tree

3 files changed

+12
-10
lines changed

3 files changed

+12
-10
lines changed

scanmatcher/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,6 @@ find_package(pcl_conversions REQUIRED)
3434
find_package(lidarslam_msgs REQUIRED)
3535
find_package(ndt_omp_ros2 REQUIRED)
3636
find_package(PCL REQUIRED)
37-
find_package(Boost REQUIRED COMPONENTS system)
3837
find_package(OpenMP)
3938

4039
if (OPENMP_FOUND)

scanmatcher/include/scanmatcher/scanmatcher_component.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -68,8 +68,8 @@ extern "C" {
6868
#include <pclomp/gicp_omp_impl.hpp>
6969

7070
#include <mutex>
71-
#include <boost/thread.hpp>
72-
#include <boost/thread/future.hpp>
71+
#include <thread>
72+
#include <future>
7373

7474
#include <pcl_conversions/pcl_conversions.h>
7575

@@ -101,9 +101,9 @@ class ScanMatcherComponent : public rclcpp::Node
101101
rclcpp::Time last_map_time_;
102102
bool mapping_flag_{false};
103103
bool is_map_updated_{false};
104-
boost::thread mapping_thread_;
105-
boost::packaged_task<void> mapping_task_;
106-
boost::unique_future<void> mapping_future_;
104+
std::thread mapping_thread_;
105+
std::packaged_task<void()> mapping_task_;
106+
std::future<void> mapping_future_;
107107

108108
geometry_msgs::msg::PoseStamped corrent_pose_stamped_;
109109
pcl::PointCloud<pcl::PointXYZI> map_;

scanmatcher/src/scanmatcher_component.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -276,14 +276,17 @@ void ScanMatcherComponent::receiveCloud(
276276
const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_ptr,
277277
rclcpp::Time stamp)
278278
{
279-
280-
if (mapping_flag_ && mapping_future_.has_value()) {
279+
if (mapping_flag_ && mapping_future_.valid()) {
280+
auto status = mapping_future_.wait_for(0s);
281+
if (status == std::future_status::ready) {
281282
if (is_map_updated_ == true) {
282283
pcl::PointCloud<pcl::PointXYZI>::Ptr targeted_cloud_ptr(new pcl::PointCloud<pcl::PointXYZI>(targeted_cloud_));
283284
registration_->setInputTarget(targeted_cloud_ptr);
284285
is_map_updated_ = false;
285286
}
286287
mapping_flag_ = false;
288+
mapping_thread_.detach();
289+
}
287290
}
288291

289292
pcl::PointCloud<pcl::PointXYZI>::Ptr filtered_cloud_ptr(new pcl::PointCloud<pcl::PointXYZI>());
@@ -399,9 +402,9 @@ void ScanMatcherComponent::publishMapAndPose(
399402
geometry_msgs::msg::PoseStamped corrent_pose_stamped;
400403
corrent_pose_stamped = corrent_pose_stamped_;
401404
previous_position_ = position;
402-
mapping_task_ = boost::packaged_task<void>(boost::bind(&ScanMatcherComponent::updateMap, this, cloud_ptr, final_transformation, corrent_pose_stamped));
405+
mapping_task_ = std::packaged_task<void()>(std::bind(&ScanMatcherComponent::updateMap, this, cloud_ptr, final_transformation, corrent_pose_stamped));
403406
mapping_future_ = mapping_task_.get_future();
404-
mapping_thread_ = boost::thread(boost::move(boost::ref(mapping_task_)));
407+
mapping_thread_ = std::thread(std::move(std::ref(mapping_task_)));
405408
mapping_flag_ = true;
406409
}
407410
}

0 commit comments

Comments
 (0)