Skip to content

Fix some bug:refer to README for details #158

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

Open
wants to merge 2 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
23 changes: 23 additions & 0 deletions .vscode/c_cpp_properties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
{
"configurations": [
{
"browse": {
"databaseFilename": "${default}",
"limitSymbolsToIncludedHeaders": false
},
"includePath": [
"/home/fredlyu/driver/ws_spinnaker/devel/include/**",
"/opt/ros/noetic/include/**",
"/home/fredlyu/driver/ws_spinnaker/src/spinnaker_camera_driver/include",
"/opt/spinnaker/include",
"/usr/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "gnu11",
"cppStandard": "c++14"
}
],
"version": 4
}
16 changes: 16 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
{
"python.autoComplete.extraPaths": [
"/home/fredlyu/driver/ws_spinnaker/devel/lib/python3/dist-packages",
"/home/fredlyu/driver/ws_orbbec/devel/lib/python3/dist-packages",
"/home/fredlyu/slam/ws_livox_ros_driver_for_r3live/devel/lib/python3/dist-packages",
"/home/fredlyu/slam/ws_kalibr/devel/lib/python3/dist-packages",
"/opt/ros/noetic/lib/python3/dist-packages"
],
"python.analysis.extraPaths": [
"/home/fredlyu/driver/ws_spinnaker/devel/lib/python3/dist-packages",
"/home/fredlyu/driver/ws_orbbec/devel/lib/python3/dist-packages",
"/home/fredlyu/slam/ws_livox_ros_driver_for_r3live/devel/lib/python3/dist-packages",
"/home/fredlyu/slam/ws_kalibr/devel/lib/python3/dist-packages",
"/opt/ros/noetic/lib/python3/dist-packages"
]
}
9 changes: 9 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,12 @@
适配了Ubuntu20.04以及Opencv3以上版本;该仓库所用SpinnakerSDK版本为3.0.0.118
主要修改了以下部分:
- opencv: cv.h -> opencv2.opencv.hpp
- opencv: cvDestroyAllWindows -> destroyAllWindows()
- opencv: CV_WINDOW_NORMAL -> WINDOW_NORMAL
- opencv: CV_WINDOW_KEEPRATIO -> WINDOW_KEEPRATIO
- spinnakerSDK: ImagePtr::Convert() -> ImageProcessor::Convert()
- 修改了硬触发外部通道: Line3 -> Line0(Opto-isolated input)(capture.cpp:748-749)
------------------------------------------------------------------------------
master:
[![Build Status](https://travis-ci.org/neufieldrobotics/spinnaker_sdk_camera_driver.svg?branch=master)](https://travis-ci.org/neufieldrobotics/spinnaker_sdk_camera_driver)
dev: [![Build Status](https://travis-ci.org/neufieldrobotics/spinnaker_sdk_camera_driver.svg?branch=dev)](https://travis-ci.org/neufieldrobotics/spinnaker_sdk_camera_driver)
Expand Down
2 changes: 1 addition & 1 deletion include/spinnaker_sdk_camera_driver/std_include.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include "SpinGenApi/SpinnakerGenApi.h"

// OpenCV
#include <cv.h>
#include <opencv2/opencv.hpp>
#include <opencv2/highgui/highgui.hpp>

// ROS
Expand Down
4 changes: 2 additions & 2 deletions launch/acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@

<!-- acquisition spinnaker params-->
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="color" default="true" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
<arg name="external_trigger" default="true" doc="External trigger (No camera is master)"/>
<arg name="gain" default="0" doc="Gain setting. Gain should be positive (full range - 0 - 18 dB for blackfly-s camera)
or zero (auto gain). if gain > max, it will be set to max allowed value.
Default is 0, auto gain which is set according to target grey value or autoexposure settings"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/acquisition_external_trigger.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

<!-- acquisition spinnaker params-->
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="color" default="true" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<arg name="external_trigger" default="true" doc="External trigger (No camera is master)"/>
<arg name="gain" default="0" doc="Gain setting. Gain should be positive (full range - 0 - 18 dB for blackfly-s camera)
Expand Down
2 changes: 1 addition & 1 deletion launch/node_acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<!-- acquisition.launch -->

<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="color" default="true" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4, AutoExposureTargetGreyValueAuto will be set to continuous(auto) also available as dynamic reconfigurable parameter" />
Expand Down
2 changes: 1 addition & 1 deletion params/external_trigger_params.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cam_ids:
- 17197559
- 22240274
cam_aliases:
- cam0
skip: 20
Expand Down
4 changes: 2 additions & 2 deletions params/test_params.yaml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
cam_ids:
- 17197559
- 22240274
cam_aliases:
- cam0
master_cam: 17197559
master_cam: 22240274
skip: 20
delay: 1.0

Expand Down
12 changes: 10 additions & 2 deletions src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,17 @@ Mat acquisition::Camera::convert_to_mat(ImagePtr pImage) {

ImagePtr convertedImage;
if (COLOR_)
convertedImage = pImage->Convert(PixelFormat_BGR8); //, NEAREST_NEIGHBOR);
{
// convertedImage = pImage->Convert(PixelFormat_BGR8); //, NEAREST_NEIGHBOR);
ImageProcessor processor;
convertedImage = processor.Convert(pImage, PixelFormat_BGR8);
}
else
convertedImage = pImage->Convert(PixelFormat_Mono8); //, NEAREST_NEIGHBOR);
{
ImageProcessor processor;
convertedImage = processor.Convert(pImage, PixelFormat_Mono8);
}

unsigned int XPadding = convertedImage->GetXPadding();
unsigned int YPadding = convertedImage->GetYPadding();
unsigned int rowsize = convertedImage->GetWidth();
Expand Down
14 changes: 7 additions & 7 deletions src/capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -745,8 +745,8 @@ void acquisition::Capture::init_cameras(bool soft = false) {
// in master slave setup. Also in the mode when another sensor such as IMU triggers
// the camera
cams[i].setEnumValue("TriggerMode", "On");
cams[i].setEnumValue("LineSelector", "Line3");
cams[i].setEnumValue("TriggerSource", "Line3");
cams[i].setEnumValue("LineSelector", "Line0");
cams[i].setEnumValue("TriggerSource", "Line0");
cams[i].setEnumValue("TriggerSelector", "FrameStart");
cams[i].setEnumValue("LineMode", "Input");

Expand Down Expand Up @@ -996,8 +996,8 @@ void acquisition::Capture::run_soft_trig() {
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 @@ -1046,7 +1046,7 @@ void acquisition::Capture::run_soft_trig() {
}
}

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

if ( (key & 255)!=255 ) {
Expand All @@ -1070,7 +1070,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 +1098,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