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

[ROS-O] drop obsolete use of boost::bind and _1 #167

Open
wants to merge 3 commits into
base: ros1
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
8 changes: 6 additions & 2 deletions fetch_calibration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@ cmake_minimum_required(VERSION 3.0.2)
project(fetch_calibration)

find_package(catkin)
catkin_python_setup()
catkin_package()

install(DIRECTORY config
Expand All @@ -13,7 +12,12 @@ install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

install(
catkin_install_python(
PROGRAMS scripts/camera_reconfigure.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

catkin_install_python(
PROGRAMS scripts/calibrate_robot
DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
)
2 changes: 0 additions & 2 deletions fetch_calibration/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,6 @@
<url type="repository">https://github.com/fetchrobotics/fetch_ros</url>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend condition="$ROS_PYTHON_VERSION == 2">python-setuptools</buildtool_depend>
<buildtool_depend condition="$ROS_PYTHON_VERSION == 3">python3-setuptools</buildtool_depend>

<exec_depend version_gte="0.5.1">robot_calibration</exec_depend>
</package>
10 changes: 0 additions & 10 deletions fetch_calibration/setup.py

This file was deleted.

2 changes: 1 addition & 1 deletion fetch_depth_layer/src/depth_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ void FetchDepthLayer::onInitialize()
depth_image_sub_.reset(new message_filters::Subscriber<sensor_msgs::Image>(private_nh, camera_depth_topic, 10));
depth_image_filter_ = boost::shared_ptr< tf2_ros::MessageFilter<sensor_msgs::Image> >(
new tf2_ros::MessageFilter<sensor_msgs::Image>(*depth_image_sub_, *tf_, global_frame_, 10, private_nh));
depth_image_filter_->registerCallback(boost::bind(&FetchDepthLayer::depthImageCallback, this, _1));
depth_image_filter_->registerCallback([this](auto msg){ depthImageCallback(msg); });
observation_subscribers_.push_back(depth_image_sub_);
observation_notifiers_.push_back(depth_image_filter_);
observation_notifiers_.back()->setTolerance(ros::Duration(0.05));
Expand Down
2 changes: 0 additions & 2 deletions fetch_ikfast_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
cmake_minimum_required(VERSION 3.0.2)
project(fetch_ikfast_plugin)

add_compile_options(-std=c++14)

find_package(catkin REQUIRED COMPONENTS
moveit_core
pluginlib
Expand Down