Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

use boost::placeholders::_1 instead of deprecated _1 #105

Open
wants to merge 2 commits into
base: noetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion hector_geotiff/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
cmake_minimum_required(VERSION 3.0.2)
project(hector_geotiff)
set(CMAKE_CXX_STANDARD 14)

find_package(catkin REQUIRED COMPONENTS hector_map_tools hector_nav_msgs nav_msgs pluginlib roscpp std_msgs)

Expand Down
2 changes: 1 addition & 1 deletion hector_geotiff/src/geotiff_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
#include <ros/ros.h>
#include <ros/console.h>

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

#include <memory>
#include <boost/algorithm/string.hpp>
Expand Down
2 changes: 1 addition & 1 deletion hector_geotiff_plugins/src/trajectory_geotiff_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,5 +119,5 @@ void TrajectoryMapWriter::draw(MapWriterInterface *interface)
} // namespace

//register this planner as a MapWriterPluginInterface plugin
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(hector_geotiff_plugins::TrajectoryMapWriter, hector_geotiff::MapWriterPluginInterface)
2 changes: 1 addition & 1 deletion hector_mapping/src/HectorMappingRos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ HectorMappingRos::HectorMappingRos()

initial_pose_sub_ = new message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>(node_, "initialpose", 2);
initial_pose_filter_ = new tf::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>(*initial_pose_sub_, tf_, p_map_frame_, 2);
initial_pose_filter_->registerCallback(boost::bind(&HectorMappingRos::initialPoseCallback, this, _1));
initial_pose_filter_->registerCallback(boost::bind(&HectorMappingRos::initialPoseCallback, this, boost::placeholders::_1));


map__publish_thread_ = new boost::thread(boost::bind(&HectorMappingRos::publishMapLoop, this, p_map_pub_period_));
Expand Down