diff --git a/.travis.yml b/.travis.yml index 6cc6b35..8ff3b06 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,6 +5,8 @@ services: matrix: include: + - arch: amd64 + env : DOCKER_IMAGE=ros:noetic-perception-focal SPINNAKER_VERSION=2.6.0.160 - arch: amd64 env : DOCKER_IMAGE=ros:melodic-perception-bionic SPINNAKER_VERSION=2.0.0.147 - arch: amd64 @@ -18,7 +20,7 @@ matrix: - arch: arm64 env : DOCKER_IMAGE=arm64v8/ros:kinetic-perception-xenial SPINNAKER_VERSION=2.0.0.147 - arch: arm64 - env : DOCKER_IMAGE=arm64v8/ros:melodic-perception-bionic SPINNAKER_VERSION=2.0.0.147 + env : DOCKER_IMAGE=arm64v8/ros:melodic-perception-bionic SPINNAKER_VERSION=2.0.0.147 before_install: - echo "$DOCKER_PASSWORD" | docker login -u "$DOCKER_USERNAME" --password-stdin diff --git a/CMakeLists.txt b/CMakeLists.txt index 3df184f..787c565 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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) diff --git a/include/spinnaker_sdk_camera_driver/capture.h b/include/spinnaker_sdk_camera_driver/capture.h index 5539ed8..a0916ab 100755 --- a/include/spinnaker_sdk_camera_driver/capture.h +++ b/include/spinnaker_sdk_camera_driver/capture.h @@ -4,7 +4,6 @@ #include "std_include.h" #include "serialization.h" #include "camera.h" -#include "spinnaker_configure.h" #include #include //ROS diff --git a/include/spinnaker_sdk_camera_driver/spinnaker_configure.h.in b/include/spinnaker_sdk_camera_driver/spinnaker_configure.h.in index 3589f3b..57d57c7 100644 --- a/include/spinnaker_sdk_camera_driver/spinnaker_configure.h.in +++ b/include/spinnaker_sdk_camera_driver/spinnaker_configure.h.in @@ -1 +1,2 @@ #cmakedefine trigger_msgs_FOUND +#define OPENCV_VERSION @OpenCV_VERSION_MAJOR@ diff --git a/include/spinnaker_sdk_camera_driver/std_include.h b/include/spinnaker_sdk_camera_driver/std_include.h index 24c196b..00eb2a1 100755 --- a/include/spinnaker_sdk_camera_driver/std_include.h +++ b/include/spinnaker_sdk_camera_driver/std_include.h @@ -4,9 +4,11 @@ // Spinnaker SDK #include "Spinnaker.h" #include "SpinGenApi/SpinnakerGenApi.h" - +#include "spinnaker_configure.h" // OpenCV -#include +#if (OPENCV_VERSION < 4) + #include +#endif #include // ROS @@ -44,7 +46,6 @@ #include - // gflags //#include diff --git a/src/camera.cpp b/src/camera.cpp index 9b7010c..31c7b3e 100755 --- a/src/camera.cpp +++ b/src/camera.cpp @@ -88,14 +88,8 @@ int acquisition::Camera::get_frame_id() { Mat acquisition::Camera::grab_mat_frame() { - try{ - ImagePtr pResultImage = grab_frame(); - return convert_to_mat(pResultImage); - } - catch(Spinnaker::Exception &e){ - ros::shutdown(); - } - + ImagePtr pResultImage = grab_frame(); + return convert_to_mat(pResultImage); } diff --git a/src/capture.cpp b/src/capture.cpp index 19c2660..aff64fd 100755 --- a/src/capture.cpp +++ b/src/capture.cpp @@ -45,6 +45,7 @@ acquisition::Capture::Capture() { } void acquisition::Capture::onInit() { + NODELET_INFO_STREAM("OpenCV Version: "<getNodeHandle(); nh_pvt_ = this->getPrivateNodeHandle(); @@ -957,25 +958,29 @@ void acquisition::Capture::get_mat_images() { int frameID; int fid_mismatch = 0; - - for (int i=0; i nframes_) { ROS_INFO_STREAM(nframes_ << " frames recorded. Terminating..."); - cvDestroyAllWindows(); + destroyAllWindows(); break; } }