Skip to content

Commit bbc883d

Browse files
authored
Merge pull request #209 from traversaro/patch-6
Remove use of boost from polygon_filter
2 parents 46a42b6 + 4de6463 commit bbc883d

File tree

1 file changed

+6
-5
lines changed

1 file changed

+6
-5
lines changed

include/laser_filters/polygon_filter.h

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,8 @@
4343
#ifndef POLYGON_FILTER_H
4444
#define POLYGON_FILTER_H
4545

46+
#include <mutex>
47+
4648
#include <filters/filter_base.hpp>
4749

4850
#include <sensor_msgs/msg/laser_scan.hpp>
@@ -54,7 +56,6 @@
5456
#include <rclcpp_lifecycle/lifecycle_node.hpp>
5557
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
5658
#include <tf2_ros/buffer.h>
57-
#include <boost/thread.hpp>
5859
#include <rclcpp/rclcpp.hpp>
5960
#include <rcl_interfaces/msg/set_parameters_result.hpp>
6061

@@ -286,7 +287,7 @@ class LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::msg::
286287
protected:
287288
rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;
288289
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
289-
boost::recursive_mutex own_mutex_;
290+
std::recursive_mutex own_mutex_;
290291
// configuration
291292
std::string polygon_frame_;
292293
geometry_msgs::msg::Polygon polygon_;
@@ -302,7 +303,7 @@ class LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::msg::
302303
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handle_;
303304
virtual rcl_interfaces::msg::SetParametersResult reconfigureCB(std::vector<rclcpp::Parameter> parameters)
304305
{
305-
boost::recursive_mutex::scoped_lock lock(own_mutex_);
306+
std::lock_guard<std::recursive_mutex> lock(own_mutex_);
306307
auto result = rcl_interfaces::msg::SetParametersResult();
307308
result.successful = true;
308309

@@ -373,7 +374,7 @@ class LaserScanPolygonFilter : public LaserScanPolygonFilterBase {
373374
{
374375
auto start = std::chrono::high_resolution_clock::now();
375376

376-
boost::recursive_mutex::scoped_lock lock(own_mutex_);
377+
std::lock_guard<std::recursive_mutex> lock(own_mutex_);
377378

378379
publishPolygon();
379380

@@ -488,7 +489,7 @@ class StaticLaserScanPolygonFilter : public LaserScanPolygonFilterBase {
488489

489490
bool update(const sensor_msgs::msg::LaserScan& input_scan, sensor_msgs::msg::LaserScan& output_scan) override
490491
{
491-
boost::recursive_mutex::scoped_lock lock(own_mutex_);
492+
std::lock_guard<std::recursive_mutex> lock(own_mutex_);
492493
publishPolygon();
493494

494495
if (!is_polygon_transformed_)

0 commit comments

Comments
 (0)