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

Build on 22.04 #114

Open
wants to merge 3 commits into
base: master
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
1 change: 0 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand Down
4 changes: 3 additions & 1 deletion launch/rtsp_stream.launch
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
<?xml version="1.0"?>
<launch>
<arg name="url" default="rtsp://wowzaec2demo.streamlock.net/vod/mp4:BigBuckBunny_115k.mp4"/>

<!-- launch video stream -->
<include file="$(find video_stream_opencv)/launch/camera.launch" >
<!-- node name and ros graph name -->
<arg name="camera_name" value="rtsp2" />
<!-- url of the video stream -->
<arg name="video_stream_provider" value="rtsp://wowzaec2demo.streamlock.net/vod/mp4:BigBuckBunny_115k.mov" />
<arg name="video_stream_provider" value="$(arg url)" />
<!-- set camera fps to (does nothing on a stream)-->
<!-- <arg name="set_camera_fps" value="30"/> -->
<!-- set buffer queue size of frame capturing to -->
Expand Down
12 changes: 6 additions & 6 deletions src/video_stream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -441,18 +441,18 @@ virtual void onInit() {

// set parameters from dynamic reconfigure server
dyn_srv = boost::make_shared<dynamic_reconfigure::Server<VideoStreamConfig> >(*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,
Expand All @@ -468,5 +468,5 @@ virtual ~VideoStreamNodelet() {
};
} // namespace

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(video_stream_opencv::VideoStreamNodelet, nodelet::Nodelet)