Skip to content

Commit

Permalink
Merge pull request #481 from ros-perception/fix/reliably-close-image-…
Browse files Browse the repository at this point in the history
…view

image_view: Making window close reliably shut down node.
  • Loading branch information
SteveMacenski authored Nov 25, 2019
2 parents 5d81e51 + 129fc3d commit 00e7c02
Showing 1 changed file with 12 additions and 17 deletions.
29 changes: 12 additions & 17 deletions image_view/src/nodelets/image_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,14 +101,11 @@ class ImageNodelet : public nodelet::Nodelet
boost::format filename_format_;
int count_;

ros::WallTimer gui_timer_;

virtual void onInit();

void imageCb(const sensor_msgs::ImageConstPtr& msg);

static void mouseCb(int event, int x, int y, int flags, void* param);
static void guiCb(const ros::WallTimerEvent&);

void windowThread();

Expand Down Expand Up @@ -165,12 +162,6 @@ void ImageNodelet::onInit()
local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
filename_format_.parse(format_string);

// Since cv::startWindowThread() triggers a crash in cv::waitKey()
// if OpenCV is compiled against GTK, we call cv::waitKey() from
// the ROS event loop periodically, instead.
/*cv::startWindowThread();*/
gui_timer_ = local_nh.createWallTimer(ros::WallDuration(0.1), ImageNodelet::guiCb);

window_thread_ = boost::thread(&ImageNodelet::windowThread, this);

image_transport::ImageTransport it(nh);
Expand All @@ -195,12 +186,6 @@ void ImageNodelet::imageCb(const sensor_msgs::ImageConstPtr& msg)
}
}

void ImageNodelet::guiCb(const ros::WallTimerEvent&)
{
// Process pending GUI events and return immediately
cv::waitKey(1);
}

void ImageNodelet::mouseCb(int event, int x, int y, int flags, void* param)
{
ImageNodelet *this_ = reinterpret_cast<ImageNodelet*>(param);
Expand Down Expand Up @@ -243,19 +228,29 @@ void ImageNodelet::windowThread()

try
{
while (true)
while (ros::ok())
{
cv::Mat image(queued_image_.pop());
cv::imshow(window_name_, image);
cv::waitKey(1);
shown_image_.set(image);
cv::waitKey(1);

if (cv::getWindowProperty(window_name_, 1) < 0)
{
break;
}
}
}
catch (const boost::thread_interrupted&)
{
}

cv::destroyWindow(window_name_);

if (ros::ok())
{
ros::shutdown();
}
}

} // namespace image_view
Expand Down

0 comments on commit 00e7c02

Please sign in to comment.