Skip to content

Commit

Permalink
Remove use of boost from polygon_filter
Browse files Browse the repository at this point in the history
  • Loading branch information
traversaro authored Jan 13, 2025
1 parent 46a42b6 commit 4de6463
Showing 1 changed file with 6 additions and 5 deletions.
11 changes: 6 additions & 5 deletions include/laser_filters/polygon_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@
#ifndef POLYGON_FILTER_H
#define POLYGON_FILTER_H

#include <mutex>

#include <filters/filter_base.hpp>

#include <sensor_msgs/msg/laser_scan.hpp>
Expand All @@ -54,7 +56,6 @@
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/buffer.h>
#include <boost/thread.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rcl_interfaces/msg/set_parameters_result.hpp>

Expand Down Expand Up @@ -286,7 +287,7 @@ class LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::msg::
protected:
rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
boost::recursive_mutex own_mutex_;
std::recursive_mutex own_mutex_;
// configuration
std::string polygon_frame_;
geometry_msgs::msg::Polygon polygon_;
Expand All @@ -302,7 +303,7 @@ class LaserScanPolygonFilterBase : public filters::FilterBase<sensor_msgs::msg::
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handle_;
virtual rcl_interfaces::msg::SetParametersResult reconfigureCB(std::vector<rclcpp::Parameter> parameters)
{
boost::recursive_mutex::scoped_lock lock(own_mutex_);
std::lock_guard<std::recursive_mutex> lock(own_mutex_);
auto result = rcl_interfaces::msg::SetParametersResult();
result.successful = true;

Expand Down Expand Up @@ -373,7 +374,7 @@ class LaserScanPolygonFilter : public LaserScanPolygonFilterBase {
{
auto start = std::chrono::high_resolution_clock::now();

boost::recursive_mutex::scoped_lock lock(own_mutex_);
std::lock_guard<std::recursive_mutex> lock(own_mutex_);

publishPolygon();

Expand Down Expand Up @@ -488,7 +489,7 @@ class StaticLaserScanPolygonFilter : public LaserScanPolygonFilterBase {

bool update(const sensor_msgs::msg::LaserScan& input_scan, sensor_msgs::msg::LaserScan& output_scan) override
{
boost::recursive_mutex::scoped_lock lock(own_mutex_);
std::lock_guard<std::recursive_mutex> lock(own_mutex_);
publishPolygon();

if (!is_polygon_transformed_)
Expand Down

0 comments on commit 4de6463

Please sign in to comment.