Skip to content

Commit

Permalink
Merge pull request ros-perception#171 from ros-o/obese-devel
Browse files Browse the repository at this point in the history
[ROS-O] various cleanup
  • Loading branch information
jonbinney authored Nov 14, 2022
2 parents d141e3b + 0c0a383 commit 2294462
Show file tree
Hide file tree
Showing 15 changed files with 21 additions and 25 deletions.
9 changes: 2 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
cmake_minimum_required(VERSION 3.0.2)
project(laser_filters)

set(CMAKE_CXX_STANDARD 11)

##############################################################################
# Find dependencies
##############################################################################
Expand Down Expand Up @@ -84,11 +82,8 @@ if (CATKIN_ENABLE_TESTING)

find_package(rostest)

add_executable(test_scan_filter_chain test/test_scan_filter_chain.cpp)
target_link_libraries(test_scan_filter_chain laser_scan_filters ${rostest_LIBRARIES} ${GTEST_LIBRARIES})
add_dependencies(test_scan_filter_chain gtest)

add_rostest(test/test_scan_filter_chain.launch)
add_rostest_gtest(test_scan_filter_chain test/test_scan_filter_chain.launch test/test_scan_filter_chain.cpp)
target_link_libraries(test_scan_filter_chain laser_scan_filters ${catkin_LIBRARIES})
add_rostest(test/test_polygon_filter.launch)
add_rostest(test/test_speckle_filter.launch)

Expand Down
2 changes: 1 addition & 1 deletion include/laser_filters/range_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class LaserScanRangeFilter : public filters::FilterBase<sensor_msgs::LaserScan>
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<RangeFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<RangeFilterConfig>::CallbackType f;
f = boost::bind(&LaserScanRangeFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

getParam("lower_threshold", config_.lower_threshold);
Expand Down
1 change: 1 addition & 0 deletions include/laser_filters/speckle_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ namespace laser_filters
class WindowValidator
{
public:
virtual ~WindowValidator() = default;
virtual bool checkWindowValid(const sensor_msgs::LaserScan& scan, size_t idx, size_t window, double max_range_difference) = 0;
};

Expand Down
2 changes: 1 addition & 1 deletion src/box_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ bool laser_filters::LaserScanBoxFilter::configure(){
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<BoxFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<BoxFilterConfig>::CallbackType f;
f = boost::bind(&LaserScanBoxFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

up_and_running_ = true;
Expand Down
4 changes: 2 additions & 2 deletions src/generic_laser_filter_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,13 +66,13 @@ class GenericLaserScanFilterNode
filter_chain_.configure("");

// Setup tf::MessageFilter for input
tf_filter_.registerCallback(boost::bind(&GenericLaserScanFilterNode::callback, this, _1));
tf_filter_.registerCallback(boost::bind(&GenericLaserScanFilterNode::callback, this, boost::placeholders::_1));
tf_filter_.setTolerance(ros::Duration(0.03));

// Advertise output
output_pub_ = nh_.advertise<sensor_msgs::LaserScan>("output", 1000);

deprecation_timer_ = nh_.createTimer(ros::Duration(5.0), boost::bind(&GenericLaserScanFilterNode::deprecation_warn, this, _1));
deprecation_timer_ = nh_.createTimer(ros::Duration(5.0), [this](auto& event){ deprecation_warn(event); });
}

void deprecation_warn(const ros::TimerEvent& e)
Expand Down
2 changes: 1 addition & 1 deletion src/intensity_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ bool LaserScanIntensityFilter::configure()
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<IntensityFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<IntensityFilterConfig>::CallbackType f;
f = boost::bind(&LaserScanIntensityFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

getParam("lower_threshold", config_.lower_threshold);
Expand Down
2 changes: 1 addition & 1 deletion src/laser_scan_filters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#include "sensor_msgs/LaserScan.h"
#include <filters/filter_base.hpp>

#include "pluginlib/class_list_macros.h"
#include "pluginlib/class_list_macros.hpp"


PLUGINLIB_EXPORT_CLASS(laser_filters::LaserMedianFilter, filters::FilterBase<sensor_msgs::LaserScan>)
Expand Down
2 changes: 1 addition & 1 deletion src/pointcloud_filters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,6 @@

#include "sensor_msgs/PointCloud.h"
#include "laser_filters/point_cloud_footprint_filter.h"
#include "pluginlib/class_list_macros.h"
#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(laser_filters::PointCloudFootprintFilter, filters::FilterBase<sensor_msgs::PointCloud>)
2 changes: 1 addition & 1 deletion src/polygon_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -257,7 +257,7 @@ bool LaserScanPolygonFilterBase::configure()
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<laser_filters::PolygonFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<laser_filters::PolygonFilterConfig>::CallbackType f;
f = boost::bind(&laser_filters::LaserScanPolygonFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

bool polygon_set = getParam("polygon", polygon_xmlrpc);
Expand Down
2 changes: 1 addition & 1 deletion src/scan_shadows_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ bool ScanShadowsFilter::configure()
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<laser_filters::ScanShadowsFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<laser_filters::ScanShadowsFilterConfig>::CallbackType f;
f = boost::bind(&laser_filters::ScanShadowsFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

if (!filters::FilterBase<sensor_msgs::LaserScan>::getParam(std::string("min_angle"), min_angle_))
Expand Down
6 changes: 3 additions & 3 deletions src/scan_to_cloud_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@

#if BUILDING_NODELET
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

#define LASER_INFO NODELET_INFO
#define LASER_WARN NODELET_WARN
Expand Down Expand Up @@ -156,7 +156,7 @@ class ScanToCloudFilterChain
channel_options_ |= laser_geometry::channel_option::Viewpoint;

filter_.setTargetFrame(target_frame_);
filter_.registerCallback(boost::bind(&ScanToCloudFilterChain::scanCallback, this, _1));
filter_.registerCallback(boost::bind(&ScanToCloudFilterChain::scanCallback, this, boost::placeholders::_1));
filter_.setTolerance(ros::Duration(tf_tolerance_));

if (using_scan_topic_deprecated_)
Expand Down Expand Up @@ -187,7 +187,7 @@ class ScanToCloudFilterChain
else
scan_filter_chain_.configure("scan_filter_chain", private_nh);

deprecation_timer_ = nh.createTimer(ros::Duration(5.0), boost::bind(&ScanToCloudFilterChain::deprecation_warn, this, _1));
deprecation_timer_ = nh.createTimer(ros::Duration(5.0), [this](auto& event){ this->deprecation_warn(event); });

LASER_INFO("Scan to cloud filter initialized.");
}
Expand Down
6 changes: 3 additions & 3 deletions src/scan_to_scan_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,19 +97,19 @@ class ScanToScanFilterChain
tf_filter_->setTolerance(ros::Duration(tf_filter_tolerance_));

// Setup tf::MessageFilter generates callback
tf_filter_->registerCallback(boost::bind(&ScanToScanFilterChain::callback, this, _1));
tf_filter_->registerCallback(boost::bind(&ScanToScanFilterChain::callback, this, boost::placeholders::_1));
}
else
{
// Pass through if no tf_message_filter_target_frame
scan_sub_.registerCallback(boost::bind(&ScanToScanFilterChain::callback, this, _1));
scan_sub_.registerCallback(boost::bind(&ScanToScanFilterChain::callback, this, boost::placeholders::_1));
}

// Advertise output
output_pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan_filtered", 1000);

// Set up deprecation printout
deprecation_timer_ = nh_.createTimer(ros::Duration(5.0), boost::bind(&ScanToScanFilterChain::deprecation_warn, this, _1));
deprecation_timer_ = nh_.createTimer(ros::Duration(5.0), boost::bind(&ScanToScanFilterChain::deprecation_warn, this, boost::placeholders::_1));
}

// Destructor
Expand Down
2 changes: 1 addition & 1 deletion src/sector_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ bool LaserScanSectorFilter::configure()
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<SectorFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<SectorFilterConfig>::CallbackType f;
f = boost::bind(&LaserScanSectorFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

getParam("angle_min", config_.angle_min);
Expand Down
2 changes: 1 addition & 1 deletion src/speckle_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ bool LaserScanSpeckleFilter::configure()
ros::NodeHandle private_nh("~" + getName());
dyn_server_.reset(new dynamic_reconfigure::Server<laser_filters::SpeckleFilterConfig>(own_mutex_, private_nh));
dynamic_reconfigure::Server<laser_filters::SpeckleFilterConfig>::CallbackType f;
f = boost::bind(&laser_filters::LaserScanSpeckleFilter::reconfigureCB, this, _1, _2);
f = [this](auto& config, auto level){ reconfigureCB(config, level); };
dyn_server_->setCallback(f);

getParam("filter_type", config_.filter_type);
Expand Down
2 changes: 1 addition & 1 deletion test/test_scan_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#include <filters/filter_chain.hpp>
#include <ros/ros.h>
#include "sensor_msgs/LaserScan.h"
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>


sensor_msgs::LaserScan gen_msg(){
Expand Down

0 comments on commit 2294462

Please sign in to comment.