use default C++ and boost::placeholders::_1
This commit is contained in:
parent
dcc1099012
commit
d544b59e82
|
@ -1,9 +1,6 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(ros_rtsp)
|
||||
|
||||
## Compile as C++11, supported in ROS Kinetic and newer
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
## Find catkin macros and libraries
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
|
|
|
@ -159,7 +159,7 @@ void Image2RTSPNodelet::url_connected(string url) {
|
|||
|
||||
if (num_of_clients[url]==0) {
|
||||
// Subscribe to the ROS topic
|
||||
subs[url] = nh.subscribe<sensor_msgs::Image>(source, 1, boost::bind(&Image2RTSPNodelet::imageCallback, this, _1, url));
|
||||
subs[url] = nh.subscribe<sensor_msgs::Image>(source, 1, boost::bind(&Image2RTSPNodelet::imageCallback, this, boost::placeholders::_1, url));
|
||||
}
|
||||
num_of_clients[url]++;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue