Merge pull request #19 from lucasw/build_ubuntu2204

Use default C++ and use boost::placeholders::_1 to build on Ubuntu 22.04
This commit is contained in:
CircusMonkey 2022-12-20 12:53:29 +10:00 committed by GitHub
commit 4ccce0332d
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 1 additions and 4 deletions

View File

@ -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

View File

@ -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]++;
}