diff --git a/CMakeLists.txt b/CMakeLists.txt index 7260b4c..dbec271 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) project(video_stream_opencv) -add_definitions(-std=c++11) find_package(catkin REQUIRED COMPONENTS roscpp diff --git a/launch/rtsp_stream.launch b/launch/rtsp_stream.launch index db370f2..842a938 100644 --- a/launch/rtsp_stream.launch +++ b/launch/rtsp_stream.launch @@ -1,11 +1,13 @@ + + - + diff --git a/src/video_stream.cpp b/src/video_stream.cpp index 88ff61e..62ce7d3 100644 --- a/src/video_stream.cpp +++ b/src/video_stream.cpp @@ -441,18 +441,18 @@ virtual void onInit() { // set parameters from dynamic reconfigure server dyn_srv = boost::make_shared >(*pnh); - auto f = boost::bind(&VideoStreamNodelet::configCallback, this, _1, _2); + auto f = boost::bind(&VideoStreamNodelet::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); dyn_srv->setCallback(f); subscriber_num = 0; image_transport::SubscriberStatusCallback connect_cb = - boost::bind(&VideoStreamNodelet::connectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::connectionCallback, this, boost::placeholders::_1); ros::SubscriberStatusCallback info_connect_cb = - boost::bind(&VideoStreamNodelet::infoConnectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::infoConnectionCallback, this, boost::placeholders::_1); image_transport::SubscriberStatusCallback disconnect_cb = - boost::bind(&VideoStreamNodelet::disconnectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::disconnectionCallback, this, boost::placeholders::_1); ros::SubscriberStatusCallback info_disconnect_cb = - boost::bind(&VideoStreamNodelet::infoDisconnectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::infoDisconnectionCallback, this, boost::placeholders::_1); pub = image_transport::ImageTransport(*nh).advertiseCamera( "image_raw", 1, connect_cb, disconnect_cb, @@ -468,5 +468,5 @@ virtual ~VideoStreamNodelet() { }; } // namespace -#include +#include PLUGINLIB_EXPORT_CLASS(video_stream_opencv::VideoStreamNodelet, nodelet::Nodelet)