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

Feature/ubuntu 20.4 #151

Open
wants to merge 4 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
4 changes: 3 additions & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
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@
7 changes: 4 additions & 3 deletions include/spinnaker_sdk_camera_driver/std_include.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,11 @@
// Spinnaker SDK
#include "Spinnaker.h"
#include "SpinGenApi/SpinnakerGenApi.h"

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

// ROS
Expand Down Expand Up @@ -44,7 +46,6 @@
#include <pwd.h>



// gflags
//#include <gflags/gflags.h>

Expand Down
10 changes: 2 additions & 8 deletions src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

}

Expand Down
57 changes: 34 additions & 23 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() {
NODELET_INFO_STREAM("OpenCV Version: "<<OPENCV_VERSION);
NODELET_INFO("Initializing nodelet");
nh_ = this->getNodeHandle();
nh_pvt_ = this->getPrivateNodeHandle();
Expand Down Expand Up @@ -957,25 +958,29 @@ void acquisition::Capture::get_mat_images() {
int frameID;
int fid_mismatch = 0;


for (int i=0; i<numCameras_; i++) {
//ROS_INFO_STREAM("CAM ID IS "<< i);
frames_[i] = cams[i].grab_mat_frame();
//ROS_INFO("sucess");
time_stamps_[i] = cams[i].get_time_stamp();
try{
for (int i=0; i<numCameras_; i++) {
//ROS_INFO_STREAM("CAM ID IS "<< i);
frames_[i] = cams[i].grab_mat_frame();
//ROS_INFO("sucess");
time_stamps_[i] = cams[i].get_time_stamp();


if (i==0)
frameID = cams[i].get_frame_id();
else
if (cams[i].get_frame_id() != frameID)
fid_mismatch = 1;

if (i == numCameras_-1)
ss << cams[i].get_frame_id() << "]";
else
ss << cams[i].get_frame_id() << ", ";

if (i==0)
frameID = cams[i].get_frame_id();
else
if (cams[i].get_frame_id() != frameID)
fid_mismatch = 1;

if (i == numCameras_-1)
ss << cams[i].get_frame_id() << "]";
else
ss << cams[i].get_frame_id() << ", ";

}
}
catch(Spinnaker::Exception &e){
ros::shutdown();
}
mesg.header.stamp = ros::Time::now();
mesg.time = ros::Time::now();
Expand All @@ -990,14 +995,21 @@ void acquisition::Capture::get_mat_images() {
}

void acquisition::Capture::run_soft_trig() {
#if (OPENCV_VERSION < 4)
auto WINDOW_NORMAL = CV_WINDOW_NORMAL;
auto WINDOW_KEEPRATIO = CV_WINDOW_KEEPRATIO;
auto destroyAllWindows = cvDestroyAllWindows;
auto waitKey = cvWaitKey;
#endif


achieved_time_ = ros::Time::now().toSec();
ROS_INFO("*** ACQUISITION ***");

start_acquisition();

// Camera directories created at first save

if (LIVE_)namedWindow("Acquisition", CV_WINDOW_NORMAL | CV_WINDOW_KEEPRATIO);
if (LIVE_)namedWindow("Acquisition", WINDOW_NORMAL | WINDOW_KEEPRATIO);

int count = 0;

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

int key = cvWaitKey(1);
int key = waitKey(1);
ROS_DEBUG_STREAM("Key press: "<<(key & 255)<<endl);

if ( (key & 255)!=255 ) {
Expand All @@ -1070,7 +1081,7 @@ void acquisition::Capture::run_soft_trig() {
}
} else if( (key & 255)==27 ) { // ESC
ROS_INFO_STREAM("Terminating...");
cvDestroyAllWindows();
destroyAllWindows();
ros::shutdown();
break;
}
Expand Down Expand Up @@ -1098,7 +1109,7 @@ void acquisition::Capture::run_soft_trig() {
ROS_INFO_STREAM(" Recorded frames "<<count<<" / "<<nframes_);
if (count > nframes_) {
ROS_INFO_STREAM(nframes_ << " frames recorded. Terminating...");
cvDestroyAllWindows();
destroyAllWindows();
break;
}
}
Expand Down