Skip to content

Commit

Permalink
Use default CXX, need to specify boost::placeholders::_1 instead of j…
Browse files Browse the repository at this point in the history
…ust _1 (#750)
  • Loading branch information
lucasw committed May 24, 2022
1 parent 87b8d6b commit 3d94b08
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 7 deletions.
2 changes: 0 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,6 @@ if(NOT EIGEN3_FOUND)
set(EIGEN_PACKAGE Eigen)
endif()

set(CMAKE_CXX_STANDARD 14)

if(NOT MSVC)
set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Werror")
endif()
Expand Down
14 changes: 9 additions & 5 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1112,7 +1112,8 @@ namespace RobotLocalization
{
topicSubs_.push_back(
nh_.subscribe<nav_msgs::Odometry>(odomTopic, odomQueueSize,
boost::bind(&RosFilter::odometryCallback, this, _1, odomTopicName, poseCallbackData, twistCallbackData),
boost::bind(&RosFilter::odometryCallback, this, boost::placeholders::_1,
odomTopicName, poseCallbackData, twistCallbackData),
ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayOdom)));
}
else
Expand Down Expand Up @@ -1229,7 +1230,8 @@ namespace RobotLocalization

topicSubs_.push_back(
nh_.subscribe<geometry_msgs::PoseWithCovarianceStamped>(poseTopic, poseQueueSize,
boost::bind(&RosFilter::poseCallback, this, _1, callbackData, worldFrameId_, baseLinkFrameId_, false),
boost::bind(&RosFilter::poseCallback, this, boost::placeholders::_1,
callbackData, worldFrameId_, baseLinkFrameId_, false),
ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayPose)));

if (differential)
Expand Down Expand Up @@ -1306,7 +1308,8 @@ namespace RobotLocalization

topicSubs_.push_back(
nh_.subscribe<geometry_msgs::TwistWithCovarianceStamped>(twistTopic, twistQueueSize,
boost::bind(&RosFilter<T>::twistCallback, this, _1, callbackData, baseLinkFrameId_),
boost::bind(&RosFilter<T>::twistCallback, this, boost::placeholders::_1,
callbackData, baseLinkFrameId_),
ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayTwist)));

twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx];
Expand Down Expand Up @@ -1476,8 +1479,9 @@ namespace RobotLocalization

topicSubs_.push_back(
nh_.subscribe<sensor_msgs::Imu>(imuTopic, imuQueueSize,
boost::bind(&RosFilter<T>::imuCallback, this, _1, imuTopicName, poseCallbackData, twistCallbackData,
accelCallbackData), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayImu)));
boost::bind(&RosFilter<T>::imuCallback, this, boost::placeholders::_1,
imuTopicName, poseCallbackData, twistCallbackData,
accelCallbackData), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayImu)));
}
else
{
Expand Down

0 comments on commit 3d94b08

Please sign in to comment.