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 default CXX, use boost::placeholders::_1 instead of _1 #750

Merged
merged 1 commit into from
May 24, 2022
Merged
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
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)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why did this need to be removed?

Copy link
Author

@lucasw lucasw May 20, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's a log4cxx 0.12 issue that results in

/usr/include/log4cxx/boost-std-configuration.h:10:18: error: ‘shared_mutex’ in namespace ‘std’ does not name a type
   10 |     typedef std::shared_mutex shared_mutex;
      |                  ^~~~~~~~~~~~```

when building with < C++17.

Ubuntu 20.04 noetic already defaults to C++14 and has an older log4cxx, newer systems with newer log4cxx default to C++17, and no need to support older systems in this noetic branch, so removing it seems cleanest, but I can see setting it to 17 instead. Also putting it into a separate commit in this PR, or a separate PR (or don't accept if at all if you prefer, it's easy to maintain a fork with one line of difference but much nicer for others with the newer log4cxx not to have to).

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm fine with the branch assuming whatever standard is adopted by the ROS release in question. Thanks for the info!


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