Skip to content
Merged
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
71 changes: 51 additions & 20 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,15 @@ find_package(catkin REQUIRED COMPONENTS
###
# Find Packages
find_package(OpenCV REQUIRED)
find_package(LibUnwind 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)
message("uses LibUnwind for x86_64 or x86_32 architecture")
find_package(LibUnwind REQUIRED)
endif(${CMAKE_SYSTEM_PROCESSOR} MATCHES x86_64 OR x86_32)
if(${CMAKE_SYSTEM_PROCESSOR} MATCHES arm)
message("Detected ARM architecture")
endif(${CMAKE_SYSTEM_PROCESSOR} MATCHES arm)

find_package(Boost REQUIRED)
if(Boost_FOUND)
Expand All @@ -57,25 +65,48 @@ generate_messages(
DEPENDENCIES
std_msgs
)

catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS roscpp std_msgs message_runtime nodelet
DEPENDS OpenCV LibUnwind
)

include_directories(
${PROJECT_INCLUDE_DIR}
${catkin_INCLUDE_DIRS}
${SPINNAKER_INCLUDE_DIR}
${OpenCV_INCLUDE_DIRS}
${Boost_INCLUDE_DIR}
${LibUnwind_INCLUDE_DIRS}
)

link_directories( ${SPINNAKER_LIB_DIR} )

set (LIBS ${LibUnwind_LIBRARIES} Spinnaker ${OpenCV_LIBS} ${Boost_GENERAL})
## setting catkin_package, include_directories and libs based on architecture
if(${CMAKE_SYSTEM_PROCESSOR} MATCHES x86_64 OR x86_32)
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS roscpp std_msgs message_runtime nodelet
DEPENDS OpenCV LibUnwind
)

include_directories(
${PROJECT_INCLUDE_DIR}
${catkin_INCLUDE_DIRS}
${SPINNAKER_INCLUDE_DIR}
${OpenCV_INCLUDE_DIRS}
${Boost_INCLUDE_DIR}
${LibUnwind_INCLUDE_DIRS}
)

link_directories( ${SPINNAKER_LIB_DIR} )

set (LIBS ${LibUnwind_LIBRARIES} Spinnaker ${OpenCV_LIBS} ${Boost_GENERAL})

endif(${CMAKE_SYSTEM_PROCESSOR} MATCHES x86_64 OR x86_32)
if(${CMAKE_SYSTEM_PROCESSOR} MATCHES arm)
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS roscpp std_msgs message_runtime nodelet
DEPENDS OpenCV
)

include_directories(
${PROJECT_INCLUDE_DIR}
${catkin_INCLUDE_DIRS}
${SPINNAKER_INCLUDE_DIR}
${OpenCV_INCLUDE_DIRS}
${Boost_INCLUDE_DIR}
)

link_directories( ${SPINNAKER_LIB_DIR} )

set (LIBS Spinnaker ${OpenCV_LIBS} ${Boost_GENERAL})

endif(${CMAKE_SYSTEM_PROCESSOR} MATCHES arm)

add_library (acquilib SHARED
src/capture.cpp
Expand Down
2 changes: 1 addition & 1 deletion cfg/spinnaker_cam.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ gen = ParameterGenerator()


gen.add("target_grey_val", double_t, 1, "Set Target Grey Value", 50, 4, 90)
gen.add("exposure_time", int_t, 3, "Set Exposure time (0:auto)", 0, 0, 15000)
gen.add("exposure_time", int_t, 2, "Set Exposure time (0:auto)", 0, 0, 15000)


exit(gen.generate(PACKAGE, "spinnaker_sdk_camera_driver", "spinnaker_cam"))
7 changes: 4 additions & 3 deletions include/spinnaker_sdk_camera_driver/capture.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,11 +137,12 @@ namespace acquisition {

ros::Publisher acquisition_pub;
//vector<ros::Publisher> camera_image_pubs;
vector<image_transport::Publisher> camera_image_pubs;
vector<ros::Publisher> camera_info_pubs;
vector<image_transport::CameraPublisher> camera_image_pubs;
//vector<ros::Publisher> camera_info_pubs;


vector<sensor_msgs::ImagePtr> img_msgs;
vector<sensor_msgs::CameraInfo> cam_info_msgs;
vector<sensor_msgs::CameraInfoPtr> cam_info_msgs;
spinnaker_sdk_camera_driver::SpinnakerImageNames mesg;
boost::mutex queue_mutex_;
};
Expand Down
8 changes: 4 additions & 4 deletions launch/acquisition.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@
<!-- configure console output verbosity mode:debug_console.conf or std_console.conf -->
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>

<!-- acquisition.lauynch -->
<!-- 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="exp" default="0" doc="Exposure setting for cameras"/>
Expand All @@ -21,11 +22,10 @@
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>

<!-- load the acquisition node -->
<node pkg="spinnaker_sdk_camera_driver" type="acquisition_node" name="acquisition_node" output="$(arg output)"
args="">
<node pkg="spinnaker_sdk_camera_driver" type="acquisition_node" name="acquisition_node" output="$(arg output)" args="" respawn="false" >

<!-- load the acquisition node parameters file. Note any parameters provided in this file will
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
<rosparam command="load" file="$(arg config_file)" />

<!-- Load parameters onto server using argument or default values above -->
Expand Down
2 changes: 1 addition & 1 deletion launch/acquisition_nodelet.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
<arg name="save_path" default="~" doc="location to save the image data"/>
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
<arg name="soft_framerate" default="50" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
<arg name="time" default="false" doc="Show time/FPS on output"/>
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
Expand Down
28 changes: 28 additions & 0 deletions params/cam_17197558.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
cam_ids:
- 17197558
cam_aliases:
- cam0
master_cam: 17197558
skip: 5
delay: 0

#Camera info message details
distortion_model: plumb_bob
distortion_coeffs:
- [-0.22001, 0.16693, 0.00261, -0.00099, 0.00000]
#- [-0.17465, 0.03501, 0.00064, -0.00036]
#specified as [fx 0 cx 0 fy cy 0 0 1]
intrinsic_coeffs:
- [1278.71483, 0.0, 623.08283, 0.0, 1284.06247, 515.71835, 0.0, 0.0, 1.0]
#- [638.71023, 0.0, 315.25919, 0.0, 641.21041, 248.26077, 0.0, 0.0, 1.0]

# Assign all the follwing via launch file to prevent confusion and conflict

#save_path: ~/projects/data
#save_type: .bmp #binary or .tiff or .bmp
#binning: 1 # going from 2 to 1 requires cameras to be unplugged and replugged
color: false
#frames: 50
#soft_framerate: 4 # this frame rate reflects to the software frame rate set using ros::rate
#exp: 997
#to_ros: true #When to_ros is not selected, but live is selected, pressing 'space' exports single image to ROS
1 change: 0 additions & 1 deletion params/test_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -40,4 +40,3 @@ rectification_coeffs:
projection_coeffs:
- [913.700317, 0.000000, 953.448302, 0.000000, 0.000000, 1063.296631, 777.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
- [703.910323, 0.000000, 815.113302, 0.000000, 0.000000, 958.319231, 636.871993, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]

13 changes: 4 additions & 9 deletions src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@ void acquisition::Camera::deinit() {
ImagePtr acquisition::Camera::grab_frame() {

ImagePtr pResultImage = pCam_->GetNextImage(GET_NEXT_IMAGE_TIMEOUT_);

// Check if the Image is complete

if (pResultImage->IsIncomplete()) {

ROS_WARN_STREAM("Image incomplete with image status " << pResultImage->GetImageStatus() << "!");
Expand All @@ -60,11 +60,9 @@ ImagePtr acquisition::Camera::grab_frame() {
}

}

ROS_DEBUG_STREAM("Grabbed frame from camera " << get_id() << " with timestamp " << timestamp_*1000);

return pResultImage;

return pResultImage;
}

// Returns last timestamp
Expand Down Expand Up @@ -96,19 +94,16 @@ Mat acquisition::Camera::convert_to_mat(ImagePtr pImage) {
convertedImage = pImage->Convert(PixelFormat_BGR8); //, NEAREST_NEIGHBOR);
else
convertedImage = pImage->Convert(PixelFormat_Mono8); //, NEAREST_NEIGHBOR);

unsigned int XPadding = convertedImage->GetXPadding();
unsigned int YPadding = convertedImage->GetYPadding();
unsigned int rowsize = convertedImage->GetWidth();
unsigned int colsize = convertedImage->GetHeight();

//image data contains padding. When allocating Mat container size, you need to account for the X,Y image data padding.
Mat img;
if (COLOR_)
img = Mat(colsize + YPadding, rowsize + XPadding, CV_8UC3, convertedImage->GetData(), convertedImage->GetStride());
else
img = Mat(colsize + YPadding, rowsize + XPadding, CV_8UC1, convertedImage->GetData(), convertedImage->GetStride());

return img.clone();
// return img;

Expand Down Expand Up @@ -323,4 +318,4 @@ void acquisition::Camera::exposureTest() {
float expTime=ptrExpTest->GetValue();
ROS_DEBUG_STREAM("Exposure Time: "<<expTime<<endl);

}
}
Loading