Skip to content
Open
Show file tree
Hide file tree
Changes from 2 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: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ find_package(trigger_msgs)
find_package(Spinnaker REQUIRED)
message("spinnaker lib : " ${Spinnaker_LIBRARIES})
find_package(OpenCV REQUIRED)

# use LibUnwind only for x86_64 or x86_32 architecture
# do not use LibUnwind for arm architecture
if(${CMAKE_SYSTEM_PROCESSOR} MATCHES x86_64 OR x86_32)
Expand Down
1 change: 0 additions & 1 deletion include/spinnaker_sdk_camera_driver/capture.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
#include "std_include.h"
#include "serialization.h"
#include "camera.h"
#include "spinnaker_configure.h"
#include <boost/archive/binary_oarchive.hpp>
#include <boost/filesystem.hpp>
//ROS
Expand Down
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
#cmakedefine trigger_msgs_FOUND
#define OPENCV_VERSION @OpenCV_VERSION_MAJOR@
10 changes: 7 additions & 3 deletions include/spinnaker_sdk_camera_driver/std_include.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,14 @@
// Spinnaker SDK
#include "Spinnaker.h"
#include "SpinGenApi/SpinnakerGenApi.h"

#include "spinnaker_configure.h"
// OpenCV
#include <cv.h>
#include <opencv2/highgui/highgui.hpp>
#if (OPENCV_VERSION < 4)
#include <cv.h>
#else
#include <opencv2/highgui/highgui.hpp>
#endif


// ROS
#include <ros/ros.h>
Expand Down
20 changes: 18 additions & 2 deletions src/capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ acquisition::Capture::Capture() {
}

void acquisition::Capture::onInit() {
cout<<CV_VERSION_MAJOR<<endl;
NODELET_INFO("Initializing nodelet");
nh_ = this->getNodeHandle();
nh_pvt_ = this->getPrivateNodeHandle();
Expand Down Expand Up @@ -996,8 +997,11 @@ void acquisition::Capture::run_soft_trig() {
start_acquisition();

// Camera directories created at first save
#if (OPENCV_VERSION < 4)
if (LIVE_)namedWindow("Acquisition", CV_WINDOW_NORMAL | CV_WINDOW_KEEPRATIO);
#else
if (LIVE_)namedWindow("Acquisition", WINDOW_NORMAL | WINDOW_KEEPRATIO);
#endif

int count = 0;

Expand Down Expand Up @@ -1045,8 +1049,11 @@ void acquisition::Capture::run_soft_trig() {
displayOverlay("Acquisition", title);
}
}

#if (OPENCV_VERSION < 4)
int key = cvWaitKey(1);
#else
int key = waitKey(1);
#endif
ROS_DEBUG_STREAM("Key press: "<<(key & 255)<<endl);

if ( (key & 255)!=255 ) {
Expand All @@ -1070,7 +1077,12 @@ void acquisition::Capture::run_soft_trig() {
}
} else if( (key & 255)==27 ) { // ESC
ROS_INFO_STREAM("Terminating...");
#if (OPENCV_VERSION < 4)
cvDestroyAllWindows();
#else
destroyAllWindows();
#endif

ros::shutdown();
break;
}
Expand Down Expand Up @@ -1098,7 +1110,11 @@ void acquisition::Capture::run_soft_trig() {
ROS_INFO_STREAM(" Recorded frames "<<count<<" / "<<nframes_);
if (count > nframes_) {
ROS_INFO_STREAM(nframes_ << " frames recorded. Terminating...");
#if (OPENCV_VERSION < 4)
cvDestroyAllWindows();
#else
destroyAllWindows();
#endif
break;
}
}
Expand Down