Skip to content

Commit

Permalink
[ROS-O] various patches (#1225)
Browse files Browse the repository at this point in the history
* do not specify obsolete c++11 standard

this breaks with current versions of log4cxx.

* update pluginlib include paths

the non-hpp headers have been deprecated since kinetic

* use lambdas in favor of boost::bind

Using boost's _1 as a global system is deprecated since C++11.
The ROS packages in Debian removed the implicit support for the global symbols,
so this code fails to compile there without the patch.
  • Loading branch information
v4hn committed Nov 9, 2022
1 parent 47c9c62 commit f94f7b0
Show file tree
Hide file tree
Showing 21 changed files with 51 additions and 51 deletions.
4 changes: 0 additions & 4 deletions amcl/CMakeLists.txt
Expand Up @@ -4,10 +4,6 @@ project(amcl)
include(CheckIncludeFile)
include(CheckSymbolExists)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 11)
endif()

find_package(catkin REQUIRED
COMPONENTS
diagnostic_updater
Expand Down
2 changes: 1 addition & 1 deletion base_local_planner/src/odometry_helper_ros.cpp
Expand Up @@ -94,7 +94,7 @@ void OdometryHelperRos::setOdomTopic(std::string odom_topic)
if( odom_topic_ != "" )
{
ros::NodeHandle gn;
odom_sub_ = gn.subscribe<nav_msgs::Odometry>( odom_topic_, 1, boost::bind( &OdometryHelperRos::odomCallback, this, _1 ));
odom_sub_ = gn.subscribe<nav_msgs::Odometry>( odom_topic_, 1, [this](auto& msg){ odomCallback(msg); });
}
else
{
Expand Down
10 changes: 7 additions & 3 deletions base_local_planner/src/trajectory_planner_ros.cpp
Expand Up @@ -48,7 +48,7 @@

#include <ros/console.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

#include <base_local_planner/goal_functions.h>
#include <nav_msgs/Path.h>
Expand Down Expand Up @@ -256,11 +256,15 @@ namespace base_local_planner {
max_vel_x, min_vel_x, max_vel_th_, min_vel_th_, min_in_place_vel_th_, backup_vel,
dwa, heading_scoring, heading_scoring_timestep, meter_scoring, simple_attractor, y_vels, stop_time_buffer, sim_period_, angular_sim_granularity);

map_viz_.initialize(name, global_frame_, boost::bind(&TrajectoryPlanner::getCellCosts, tc_, _1, _2, _3, _4, _5, _6));
map_viz_.initialize(name,
global_frame_,
[this](int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost){
return tc_->getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost);
});
initialized_ = true;

dsrv_ = new dynamic_reconfigure::Server<BaseLocalPlannerConfig>(private_nh);
dynamic_reconfigure::Server<BaseLocalPlannerConfig>::CallbackType cb = boost::bind(&TrajectoryPlannerROS::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<BaseLocalPlannerConfig>::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);

} else {
Expand Down
2 changes: 1 addition & 1 deletion carrot_planner/src/carrot_planner.cpp
Expand Up @@ -36,7 +36,7 @@
*********************************************************************/
#include <angles/angles.h>
#include <carrot_planner/carrot_planner.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <tf2/convert.h>
#include <tf2/utils.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
Expand Down
2 changes: 1 addition & 1 deletion clear_costmap_recovery/src/clear_costmap_recovery.cpp
Expand Up @@ -35,7 +35,7 @@
* Author: Eitan Marder-Eppstein
*********************************************************************/
#include <clear_costmap_recovery/clear_costmap_recovery.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <boost/pointer_cast.hpp>
#include <vector>

Expand Down
6 changes: 3 additions & 3 deletions costmap_2d/plugins/inflation_layer.cpp
Expand Up @@ -40,7 +40,7 @@
#include <costmap_2d/costmap_math.h>
#include <costmap_2d/footprint.h>
#include <boost/thread.hpp>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

PLUGINLIB_EXPORT_CLASS(costmap_2d::InflationLayer, costmap_2d::Layer)

Expand Down Expand Up @@ -83,8 +83,8 @@ void InflationLayer::onInitialize()
seen_size_ = 0;
need_reinflation_ = false;

dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb = boost::bind(
&InflationLayer::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb =
[this](auto& config, auto level){ reconfigureCB(config, level); };

if (dsrv_ != NULL){
dsrv_->clearCallback();
Expand Down
17 changes: 7 additions & 10 deletions costmap_2d/plugins/obstacle_layer.cpp
Expand Up @@ -39,7 +39,7 @@
#include <costmap_2d/costmap_math.h>
#include <tf2_ros/message_filter.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <sensor_msgs/point_cloud2_iterator.h>

PLUGINLIB_EXPORT_CLASS(costmap_2d::ObstacleLayer, costmap_2d::Layer)
Expand Down Expand Up @@ -158,12 +158,11 @@ void ObstacleLayer::onInitialize()

if (inf_is_valid)
{
filter->registerCallback(boost::bind(&ObstacleLayer::laserScanValidInfCallback, this, _1,
observation_buffers_.back()));
filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ laserScanValidInfCallback(msg, buffer); });
}
else
{
filter->registerCallback(boost::bind(&ObstacleLayer::laserScanCallback, this, _1, observation_buffers_.back()));
filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ laserScanCallback(msg, buffer); });
}

observation_subscribers_.push_back(sub);
Expand All @@ -183,8 +182,7 @@ void ObstacleLayer::onInitialize()

boost::shared_ptr < tf2_ros::MessageFilter<sensor_msgs::PointCloud>
> filter(new tf2_ros::MessageFilter<sensor_msgs::PointCloud>(*sub, *tf_, global_frame_, 50, g_nh));
filter->registerCallback(
boost::bind(&ObstacleLayer::pointCloudCallback, this, _1, observation_buffers_.back()));
filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ pointCloudCallback(msg, buffer); });

observation_subscribers_.push_back(sub);
observation_notifiers_.push_back(filter);
Expand All @@ -201,8 +199,7 @@ void ObstacleLayer::onInitialize()

boost::shared_ptr < tf2_ros::MessageFilter<sensor_msgs::PointCloud2>
> filter(new tf2_ros::MessageFilter<sensor_msgs::PointCloud2>(*sub, *tf_, global_frame_, 50, g_nh));
filter->registerCallback(
boost::bind(&ObstacleLayer::pointCloud2Callback, this, _1, observation_buffers_.back()));
filter->registerCallback([this,buffer=observation_buffers_.back()](auto& msg){ pointCloud2Callback(msg, buffer); });

observation_subscribers_.push_back(sub);
observation_notifiers_.push_back(filter);
Expand All @@ -224,8 +221,8 @@ void ObstacleLayer::onInitialize()
void ObstacleLayer::setupDynamicReconfigure(ros::NodeHandle& nh)
{
dsrv_ = new dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>(nh);
dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb = boost::bind(
&ObstacleLayer::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb =
[this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);
}

Expand Down
6 changes: 3 additions & 3 deletions costmap_2d/plugins/static_layer.cpp
Expand Up @@ -38,7 +38,7 @@
*********************************************************************/
#include <costmap_2d/static_layer.h>
#include <costmap_2d/costmap_math.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <tf2/convert.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

Expand Down Expand Up @@ -118,8 +118,8 @@ void StaticLayer::onInitialize()
}

dsrv_ = new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb = boost::bind(
&StaticLayer::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb =
[this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);
}

Expand Down
6 changes: 3 additions & 3 deletions costmap_2d/plugins/voxel_layer.cpp
Expand Up @@ -36,7 +36,7 @@
* David V. Lu!!
*********************************************************************/
#include <costmap_2d/voxel_layer.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <sensor_msgs/point_cloud2_iterator.h>

#define VOXEL_BITS 16
Expand Down Expand Up @@ -67,8 +67,8 @@ void VoxelLayer::onInitialize()
void VoxelLayer::setupDynamicReconfigure(ros::NodeHandle& nh)
{
voxel_dsrv_ = new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb = boost::bind(
&VoxelLayer::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb =
[this](auto& config, auto level){ reconfigureCB(config, level); };
voxel_dsrv_->setCallback(cb);
}

Expand Down
2 changes: 1 addition & 1 deletion costmap_2d/src/costmap_2d_cloud.cpp
Expand Up @@ -199,7 +199,7 @@ int main(int argc, char** argv)
ros::Publisher pub_marked = n.advertise < sensor_msgs::PointCloud > ("voxel_marked_cloud", 2);
ros::Publisher pub_unknown = n.advertise < sensor_msgs::PointCloud > ("voxel_unknown_cloud", 2);
ros::Subscriber sub = n.subscribe < costmap_2d::VoxelGrid
> ("voxel_grid", 1, boost::bind(voxelCallback, pub_marked, pub_unknown, _1));
> ("voxel_grid", 1, [&pub_marked,&pub_unknown](auto& msg){ voxelCallback(pub_marked, pub_unknown, msg); });

ros::spin();

Expand Down
2 changes: 1 addition & 1 deletion costmap_2d/src/costmap_2d_markers.cpp
Expand Up @@ -146,7 +146,7 @@ int main(int argc, char** argv)
ROS_DEBUG("Startup");

ros::Publisher pub = n.advertise < visualization_msgs::Marker > ("visualization_marker", 1);
ros::Subscriber sub = n.subscribe < costmap_2d::VoxelGrid > ("voxel_grid", 1, boost::bind(voxelCallback, pub, _1));
ros::Subscriber sub = n.subscribe < costmap_2d::VoxelGrid > ("voxel_grid", 1, [&pub](auto& msg){ voxelCallback(pub, msg); });
g_marker_ns = n.resolveName("voxel_grid");

ros::spin();
Expand Down
3 changes: 1 addition & 2 deletions costmap_2d/src/costmap_2d_ros.cpp
Expand Up @@ -165,8 +165,7 @@ Costmap2DROS::Costmap2DROS(const std::string& name, tf2_ros::Buffer& tf) :
stopped_ = false;

dsrv_ = new dynamic_reconfigure::Server<Costmap2DConfig>(ros::NodeHandle("~/" + name));
dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = boost::bind(&Costmap2DROS::reconfigureCB, this, _1,
_2);
dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);
}

Expand Down
6 changes: 5 additions & 1 deletion dwa_local_planner/src/dwa_planner.cpp
Expand Up @@ -154,7 +154,11 @@ namespace dwa_local_planner {


private_nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
map_viz_.initialize(name, planner_util->getGlobalFrame(), boost::bind(&DWAPlanner::getCellCosts, this, _1, _2, _3, _4, _5, _6));
map_viz_.initialize(name,
planner_util->getGlobalFrame(),
[this](int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost){
return getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost);
});

private_nh.param("global_frame_id", frame_id_, std::string("odom"));

Expand Down
6 changes: 3 additions & 3 deletions dwa_local_planner/src/dwa_planner_ros.cpp
Expand Up @@ -41,7 +41,7 @@

#include <ros/console.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

#include <base_local_planner/goal_functions.h>
#include <nav_msgs/Path.h>
Expand Down Expand Up @@ -131,7 +131,7 @@ namespace dwa_local_planner {
nav_core::warnRenamedParameter(private_nh, "theta_stopped_vel", "rot_stopped_vel");

dsrv_ = new dynamic_reconfigure::Server<DWAPlannerConfig>(private_nh);
dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = boost::bind(&DWAPlannerROS::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);
}
else{
Expand Down Expand Up @@ -297,7 +297,7 @@ namespace dwa_local_planner {
&planner_util_,
odom_helper_,
current_pose_,
boost::bind(&DWAPlanner::checkTrajectory, dp_, _1, _2, _3));
[this](auto pos, auto vel, auto vel_samples){ return dp_->checkTrajectory(pos, vel, vel_samples); });
} else {
bool isOk = dwaComputeVelocityCommands(current_pose_, cmd_vel);
if (isOk) {
Expand Down
4 changes: 2 additions & 2 deletions fake_localization/fake_localization.cpp
Expand Up @@ -123,12 +123,12 @@ class FakeOdomNode
stuff_sub_ = nh.subscribe("base_pose_ground_truth", 100, &FakeOdomNode::stuffFilter, this);
filter_sub_ = new message_filters::Subscriber<nav_msgs::Odometry>(nh, "", 100);
filter_ = new tf2_ros::MessageFilter<nav_msgs::Odometry>(*filter_sub_, *m_tfBuffer, base_frame_id_, 100, nh);
filter_->registerCallback(boost::bind(&FakeOdomNode::update, this, _1));
filter_->registerCallback([this](auto& msg){ update(msg); });

// subscription to "2D Pose Estimate" from RViz:
m_initPoseSub = new message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>(nh, "initialpose", 1);
m_initPoseFilter = new tf2_ros::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>(*m_initPoseSub, *m_tfBuffer, global_frame_id_, 1, nh);
m_initPoseFilter->registerCallback(boost::bind(&FakeOdomNode::initPoseReceived, this, _1));
m_initPoseFilter->registerCallback([this](auto& msg){ initPoseReceived(msg); });
}

~FakeOdomNode(void)
Expand Down
6 changes: 3 additions & 3 deletions global_planner/src/planner_core.cpp
Expand Up @@ -36,7 +36,7 @@
* David V. Lu!!
*********************************************************************/
#include <global_planner/planner_core.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <costmap_2d/cost_values.h>
#include <costmap_2d/costmap_2d.h>

Expand Down Expand Up @@ -149,8 +149,8 @@ void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2D* costmap,
make_plan_srv_ = private_nh.advertiseService("make_plan", &GlobalPlanner::makePlanService, this);

dsrv_ = new dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>(ros::NodeHandle("~/" + name));
dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb = boost::bind(
&GlobalPlanner::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb =
[this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);

initialized_ = true;
Expand Down
6 changes: 3 additions & 3 deletions map_server/test/rtest.cpp
Expand Up @@ -97,7 +97,7 @@ TEST_F(MapClientTest, call_service)
/* Try to retrieve the map via topic, and compare to ground truth */
TEST_F(MapClientTest, subscribe_topic)
{
ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>("map", 1, boost::bind(&MapClientTest::mapCallback, this, _1));
ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>("map", 1, [this](auto& map){ mapCallback(map); });

// Try a few times, because the server may not be up yet.
int i=20;
Expand All @@ -120,7 +120,7 @@ TEST_F(MapClientTest, subscribe_topic)
/* Try to retrieve the metadata via topic, and compare to ground truth */
TEST_F(MapClientTest, subscribe_topic_metadata)
{
ros::Subscriber sub = n_->subscribe<nav_msgs::MapMetaData>("map_metadata", 1, boost::bind(&MapClientTest::mapMetaDataCallback, this, _1));
ros::Subscriber sub = n_->subscribe<nav_msgs::MapMetaData>("map_metadata", 1, [this](auto& map_metadata){ mapMetaDataCallback(map_metadata); });

// Try a few times, because the server may not be up yet.
int i=20;
Expand All @@ -140,7 +140,7 @@ TEST_F(MapClientTest, subscribe_topic_metadata)
/* Change the map, retrieve the map via topic, and compare to ground truth */
TEST_F(MapClientTest, change_map)
{
ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>("map", 1, boost::bind(&MapClientTest::mapCallback, this, _1));
ros::Subscriber sub = n_->subscribe<nav_msgs::OccupancyGrid>("map", 1, [this](auto& map){ mapCallback(map); });

// Try a few times, because the server may not be up yet.
for (int i = 20; i > 0 && !got_map_; i--)
Expand Down
6 changes: 3 additions & 3 deletions move_base/src/move_base.cpp
Expand Up @@ -58,7 +58,7 @@ namespace move_base {
planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL),
runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) {

as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false);
as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", [this](auto& goal){ executeCb(goal); }, false);

ros::NodeHandle private_nh("~");
ros::NodeHandle nh;
Expand Down Expand Up @@ -104,7 +104,7 @@ namespace move_base {
//they won't get any useful information back about its status, but this is useful for tools
//like nav_view and rviz
ros::NodeHandle simple_nh("move_base_simple");
goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&MoveBase::goalCB, this, _1));
goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, [this](auto& goal){ goalCB(goal); });

//we'll assume the radius of the robot to be consistent with what's specified for the costmaps
private_nh.param("local_costmap/inscribed_radius", inscribed_radius_, 0.325);
Expand Down Expand Up @@ -175,7 +175,7 @@ namespace move_base {
as_->start();

dsrv_ = new dynamic_reconfigure::Server<move_base::MoveBaseConfig>(ros::NodeHandle("~"));
dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = boost::bind(&MoveBase::reconfigureCB, this, _1, _2);
dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); };
dsrv_->setCallback(cb);
}

Expand Down
2 changes: 1 addition & 1 deletion move_slow_and_clear/src/move_slow_and_clear.cpp
Expand Up @@ -35,7 +35,7 @@
* Author: Eitan Marder-Eppstein
*********************************************************************/
#include <move_slow_and_clear/move_slow_and_clear.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <costmap_2d/obstacle_layer.h>

PLUGINLIB_EXPORT_CLASS(move_slow_and_clear::MoveSlowAndClear, nav_core::RecoveryBehavior)
Expand Down
2 changes: 1 addition & 1 deletion navfn/src/navfn_ros.cpp
Expand Up @@ -35,7 +35,7 @@
* Author: Eitan Marder-Eppstein
*********************************************************************/
#include <navfn/navfn_ros.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <costmap_2d/cost_values.h>
#include <costmap_2d/costmap_2d.h>
#include <sensor_msgs/point_cloud2_iterator.h>
Expand Down
2 changes: 1 addition & 1 deletion rotate_recovery/src/rotate_recovery.cpp
Expand Up @@ -35,7 +35,7 @@
* Author: Eitan Marder-Eppstein
*********************************************************************/
#include <rotate_recovery/rotate_recovery.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <nav_core/parameter_magic.h>
#include <tf2/utils.h>
#include <ros/ros.h>
Expand Down

0 comments on commit f94f7b0

Please sign in to comment.