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

fback_flow: add option to set 'queue_size' #83

Merged
merged 1 commit into from
Mar 18, 2019
Merged
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
12 changes: 10 additions & 2 deletions src/nodelet/fback_flow_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
Config config_;
boost::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;
ros::Time prev_stamp_;

Expand Down Expand Up @@ -122,6 +123,12 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
}
}

// Check if clock is jumped back
if (ros::Time::isSimTime() && prev_stamp_ > msg->header.stamp) {
NODELET_WARN_STREAM("Detected jump back in time of " << msg->header.stamp << ". Clearing optical flow cache.");
prevgray = cv::Mat();
}

// Do the work
if ( frame.channels() > 1 ) {
cv::cvtColor( frame, gray, cv::COLOR_BGR2GRAY );
Expand Down Expand Up @@ -182,9 +189,9 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", 3, &FBackFlowNodelet::imageCallbackWithInfo, this);
cam_sub_ = it_->subscribeCamera("image", queue_size_, &FBackFlowNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", 3, &FBackFlowNodelet::imageCallback, this);
img_sub_ = it_->subscribe("image", queue_size_, &FBackFlowNodelet::imageCallback, this);
}

void unsubscribe()
Expand All @@ -200,6 +207,7 @@ class FBackFlowNodelet : public opencv_apps::Nodelet
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_) {
always_subscribe_ = true;
Expand Down