43
43
#ifndef POLYGON_FILTER_H
44
44
#define POLYGON_FILTER_H
45
45
46
+ #include < mutex>
47
+
46
48
#include < filters/filter_base.hpp>
47
49
48
50
#include < sensor_msgs/msg/laser_scan.hpp>
54
56
#include < rclcpp_lifecycle/lifecycle_node.hpp>
55
57
#include < tf2_geometry_msgs/tf2_geometry_msgs.hpp>
56
58
#include < tf2_ros/buffer.h>
57
- #include < boost/thread.hpp>
58
59
#include < rclcpp/rclcpp.hpp>
59
60
#include < rcl_interfaces/msg/set_parameters_result.hpp>
60
61
@@ -286,7 +287,7 @@ class LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::msg::
286
287
protected:
287
288
rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;
288
289
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
289
- boost ::recursive_mutex own_mutex_;
290
+ std ::recursive_mutex own_mutex_;
290
291
// configuration
291
292
std::string polygon_frame_;
292
293
geometry_msgs::msg::Polygon polygon_;
@@ -302,7 +303,7 @@ class LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::msg::
302
303
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handle_;
303
304
virtual rcl_interfaces::msg::SetParametersResult reconfigureCB (std::vector<rclcpp::Parameter> parameters)
304
305
{
305
- boost::recursive_mutex::scoped_lock lock (own_mutex_);
306
+ std::lock_guard<std::recursive_mutex> lock (own_mutex_);
306
307
auto result = rcl_interfaces::msg::SetParametersResult ();
307
308
result.successful = true ;
308
309
@@ -373,7 +374,7 @@ class LaserScanPolygonFilter : public LaserScanPolygonFilterBase {
373
374
{
374
375
auto start = std::chrono::high_resolution_clock::now ();
375
376
376
- boost::recursive_mutex::scoped_lock lock (own_mutex_);
377
+ std::lock_guard<std::recursive_mutex> lock (own_mutex_);
377
378
378
379
publishPolygon ();
379
380
@@ -488,7 +489,7 @@ class StaticLaserScanPolygonFilter : public LaserScanPolygonFilterBase {
488
489
489
490
bool update (const sensor_msgs::msg::LaserScan& input_scan, sensor_msgs::msg::LaserScan& output_scan) override
490
491
{
491
- boost::recursive_mutex::scoped_lock lock (own_mutex_);
492
+ std::lock_guard<std::recursive_mutex> lock (own_mutex_);
492
493
publishPolygon ();
493
494
494
495
if (!is_polygon_transformed_)
0 commit comments