├── nodelet_plugins.xml
├── .gitignore
├── package.xml
├── .github
└── workflows
│ └── build_industrial.yml
├── .travis.yml
├── README.md
├── src
├── check_ueye_api.cpp
└── ueye_cam_nodelet.cpp
├── LICENSE
├── cmake_modules
├── DownloadUEyeDrivers.cmake
├── DownloadUEyeDriversUnofficial.cmake
└── TargetArch.cmake
├── launch
├── debug.launch
├── xs_bayer_rggb.launch
├── rgb8.launch
├── bayer_rggb_image_proc.launch
├── master_slaves_pwm_rgb8.launch
└── master_slaves_rgb8.launch
├── resources
└── xs.ini
├── CMakeLists.txt
├── include
└── ueye_cam
│ ├── logging_macros.hpp
│ ├── ueye_cam_nodelet.hpp
│ └── ueye_cam_driver.hpp
├── CHANGELOG.rst
└── cfg
└── UEyeCam.cfg
/nodelet_plugins.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | Driver wrapper nodelet for UEye cameras by IDS Imaging Development Systems GMBH.
4 |
5 |
6 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | .project
2 | .cproject
3 | .pydevproject
4 | CMakeFiles
5 | msg_gen
6 | srv_gen
7 | CMakeCache.txt
8 | cmake_install.cmake
9 | build
10 | *.pyc
11 | bin/
12 | CPackConfig.cmake
13 | CPackSourceConfig.cmake
14 | doxygen.cfg
15 | *.bag
16 | moc_*
17 | ~*
18 | *.cfgc
19 | docs/
20 | lib/
21 | .settings
22 | doc/
23 | cfg/cpp/
24 | src/ueye_cam/
25 |
26 | ### vscode ###
27 | .vscode/*
28 | *.code-workspace
29 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 | ueye_cam
3 | 1.0.19
4 |
5 | A ROS nodelet and node that wraps the driver API for UEye cameras
6 | by IDS Imaging Development Systems GMBH.
7 |
8 | Anqi Xu
9 | BSD
10 |
11 | Anqi Xu
12 |
13 | catkin
14 |
15 | roscpp
16 | nodelet
17 | dynamic_reconfigure
18 | image_transport
19 | sensor_msgs
20 | camera_calibration_parsers
21 | camera_info_manager
22 |
23 |
24 |
25 |
26 |
27 |
28 |
--------------------------------------------------------------------------------
/.github/workflows/build_industrial.yml:
--------------------------------------------------------------------------------
1 | name: Build Test (not for release)
2 |
3 | # Controls when the action will run
4 | on:
5 | # Triggers the workflow on push or pull request events
6 | push:
7 | branches: [ master ]
8 | pull_request:
9 | branches: [ master ]
10 |
11 | # Jobs that should be run
12 | jobs:
13 | build:
14 | runs-on: ubuntu-20.04
15 | strategy:
16 | matrix:
17 | env:
18 | # Test against current release and testing repo
19 | - {ROS_DISTRO: noetic, ROS_REPO: main}
20 | - {ROS_DISTRO: noetic, ROS_REPO: testing}
21 | env:
22 | CCACHE_DIR: /github/home/.ccache # Directory for ccache (industrial_ci)
23 |
24 | # Steps representing the build job
25 | steps:
26 | - uses: actions/checkout@v2
27 |
28 | # This step will fetch/store the directory used by ccache before/after the ci run
29 | - uses: actions/cache@v2
30 | with:
31 | path: ${{ env.CCACHE_DIR }}
32 | key: ccache-${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
33 |
34 | # Run industrial_ci (building the package)
35 | - uses: 'ros-industrial/industrial_ci@master'
36 | env: ${{ matrix.env }}
37 |
38 |
--------------------------------------------------------------------------------
/.travis.yml:
--------------------------------------------------------------------------------
1 | # This config file for Travis CI utilizes ros-industrial/industrial_ci package.
2 | # For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst
3 | sudo: required
4 | dist: trusty
5 | services:
6 | - docker
7 | language: generic
8 | compiler:
9 | - gcc
10 | notifications:
11 | email:
12 | on_success: always
13 | on_failure: always
14 | recipients:
15 | - gm130s@gmail.com
16 | env:
17 | matrix:
18 | - ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true
19 | - ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu USE_DEB=true
20 | - ROS_DISTRO="indigo" PRERELEASE=true
21 | - ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true
22 | - ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu USE_DEB=true
23 | - ROS_DISTRO="jade" PRERELEASE=true
24 | matrix:
25 | allow_failures:
26 | - env: ROS_DISTRO="indigo" PRERELEASE=true # Run docker-based ROS prerelease test http://wiki.ros.org/bloom/Tutorials/PrereleaseTest Because we might not want to run prerelease test for all PRs, it's omitted from pass-fail criteria.
27 | - env: ROS_DISTRO="jade" PRERELEASE=true
28 | - env: ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu USE_DEB=true
29 | - env: ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu USE_DEB=true
30 | install:
31 | - git clone https://github.com/ros-industrial/industrial_ci.git .ci_config
32 | script:
33 | - source .ci_config/travis.sh
34 | # - source ./travis.sh # Enable this when you have a package-local script
35 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | /badge.svg?branch=master&event=push)
2 |
3 | **DISCLAMER:**
4 |
5 | This project was created within an academic research setting, and thus should
6 | be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
7 | code, so please adjust expectations accordingly. With that said, we are
8 | intrinsically motivated to ensure its correctness (and often its performance).
9 | Please use the corresponding web repository tool (e.g. github, bitbucket, etc)
10 | to file bugs, suggestions, pull requests; we will do our best to address them
11 | in a timely manner.
12 |
13 |
14 | **LAYOUT:**
15 | - ueye_cam/
16 | - cfg/: dynamic_reconfigure configuration files
17 | - include/: header files
18 | - launch/: roslaunch files
19 | - src/: source files
20 | - CMakeLists.txt: CMake project configuration file
21 | - LICENSES: license agreement
22 | - package.xml: ROS/Catkin package file
23 | - nodelet_plugins.xml: ROS nodelet specification file
24 | - README.md: this file
25 | - ~/.ros/camera_info/: camera calibration yaml files
26 | (see documentation for camera_calibration ROS package
27 | for more details)
28 | - ~/.ros/camera_conf/: UEye camera parameter configuration files
29 | (generatable using ueyedemo executable:
30 | File -> save parameter -> to file...)
31 |
32 |
33 | **REQUIREMENTS:**
34 | [IDS uEye Software Suite](https://en.ids-imaging.com/downloads.html) >= 4.94
35 |
36 |
37 | **DOCUMENTATION:**
38 |
39 | www.ros.org/wiki/ueye_cam
40 |
41 |
42 |
43 | Copyright (c) 2013-2021, Anqi Xu and contributors
44 |
45 | All rights reserved.
46 |
47 | BSD3 license: see LICENSE file
48 |
--------------------------------------------------------------------------------
/src/check_ueye_api.cpp:
--------------------------------------------------------------------------------
1 | /*******************************************************************************
2 | * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
3 | *
4 | * Copyright (c) 2016, Kei Okada
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the School of Computer Science, McGill University,
18 | * nor the names of its contributors may be used to endorse or promote
19 | * products derived from this software without specific prior written
20 | * permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
25 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
26 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 | *******************************************************************************/
33 |
34 | #include
35 | #include
36 |
37 | int main(int argc, char **argv) {
38 | void *handle;
39 | handle = dlopen("libueye_api.so", RTLD_LAZY);
40 | if ( ! handle ) {
41 | ROS_ERROR("The official IDS uEye driver (libueye_api.so) were not detected on your machine.");
42 | ROS_ERROR("You (or a system administrator) MUST still download and install the official IDS uEye drivers (http://en.ids-imaging.com/download-ueye.html).");
43 | exit(1);
44 | }
45 | ros::init(argc, argv, "check_ueye_api");
46 | ros::spin();
47 | exit(0);
48 | }
49 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | /*******************************************************************************
2 | * DO NOT MODIFY - AUTO-GENERATED
3 | *
4 | *
5 | * DISCLAMER:
6 | *
7 | * This project was created within an academic research setting, and thus should
8 | * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 | * code, so please adjust expectations accordingly. With that said, we are
10 | * intrinsically motivated to ensure its correctness (and often its performance).
11 | * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 | * to file bugs, suggestions, pull requests; we will do our best to address them
13 | * in a timely manner.
14 | *
15 | *
16 | * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 | *
18 | * Copyright (c) 2013, Anqi Xu
19 | * All rights reserved.
20 | *
21 | * Redistribution and use in source and binary forms, with or without
22 | * modification, are permitted provided that the following conditions
23 | * are met:
24 | *
25 | * * Redistributions of source code must retain the above copyright
26 | * notice, this list of conditions and the following disclaimer.
27 | * * Redistributions in binary form must reproduce the above
28 | * copyright notice, this list of conditions and the following
29 | * disclaimer in the documentation and/or other materials provided
30 | * with the distribution.
31 | * * Neither the name of the School of Computer Science, McGill University,
32 | * nor the names of its contributors may be used to endorse or promote
33 | * products derived from this software without specific prior written
34 | * permission.
35 | *
36 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 | *******************************************************************************/
47 |
--------------------------------------------------------------------------------
/cmake_modules/DownloadUEyeDrivers.cmake:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 |
3 | # Script derived from:
4 | # https://github.com/ros-drivers/pointgrey_camera_driver/blob/master/pointgrey_camera_driver/cmake/DownloadFlyCap.cmake
5 |
6 | function(download_ueye_drivers UEYE_LIBRARY_VAR UEYE_INCLUDE_DIR_VAR)
7 | if(NOT UNIX)
8 | message(FATAL_ERROR "Downloading IDS uEye drivers for non-Linux systems not supported")
9 | endif()
10 | include(cmake_modules/TargetArch.cmake)
11 |
12 | # This is technically compliant with IDS Imaging's legal requirements,
13 | # in terms of installing the official uEye USB drivers. The link was
14 | # supposed to be behind a password-protected webpage, although the
15 | # link is publically available.
16 | set(UEYE_URL_BASE "http://en.ids-imaging.com/download-ueye.html?file=tl_files/downloads/uEye_SDK/driver/")
17 | set(UEYE_ARCHIVE_x86_64 "uEye_Linux_4.40_64_Bit.zip")
18 | set(UEYE_ARCHIVE_i386 "uEye_Linux_4.40_32_Bit.zip")
19 | set(UEYE_INSTALLER_x86_64 "ueyesdk-setup-4.40-usb-amd64.gz.run")
20 | set(UEYE_INSTALLER_i386 "ueyesdk-setup-4.40-usb-amd64.gz.run")
21 |
22 | target_architecture(UEYE_ARCH)
23 | if(NOT DEFINED UEYE_ARCHIVE_${UEYE_ARCH})
24 | message(FATAL_ERROR "The system's architecture, ${UEYE_ARCH}, is not supported currently by IDS / this ROS package.")
25 | endif()
26 | set(UEYE_ARCHIVE ${UEYE_ARCHIVE_${UEYE_ARCH}})
27 | set(UEYE_INSTALLER ${UEYE_INSTALLER_${UEYE_ARCH}})
28 | if(EXISTS "${CMAKE_CURRENT_BINARY_DIR}/${UEYE_ARCHIVE}")
29 | message(STATUS "Using locally downloaded copy of ${UEYE_ARCHIVE}")
30 | else()
31 | message(STATUS "Downloading ${UEYE_ARCHIVE} (~70MB)")
32 | file(DOWNLOAD "${UEYE_URL_BASE}${UEYE_ARCHIVE}"
33 | "${CMAKE_CURRENT_BINARY_DIR}/${UEYE_ARCHIVE}")
34 | endif()
35 |
36 | set(UEYE_LIBRARY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_LIB_DESTINATION}/libueye_api.so")
37 | execute_process(
38 | COMMAND ${CMAKE_COMMAND} -E tar zxvf ${UEYE_ARCHIVE}
39 | WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
40 | execute_process(
41 | COMMAND chmod +x ${UEYE_INSTALLER}
42 | WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
43 | message(STATUS "Installing IDS uEye drivers require superuser privileges.")
44 | message(STATUS "If the current user account have superuser privileges, enter password below.")
45 | message(STATUS "Otherwise, ask a superuser to execute the following commands in a terminal: ('sudo' may not be needed)")
46 | message(STATUS "1. sudo ${CMAKE_CURRENT_BINARY_DIR}/${UEYE_INSTALLER}")
47 | message(STATUS "2. sudo /etc/init.d/ueyeusbdrc start")
48 | execute_process(
49 | COMMAND sudo ./${UEYE_INSTALLER}
50 | WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
51 | execute_process(
52 | COMMAND sudo /etc/init.d/ueyeusbdrc start
53 | WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
54 | set(${UEYE_LIBRARY_VAR} ${UEYE_LIBRARY} PARENT_SCOPE)
55 | set(${UEYE_INCLUDE_DIR_VAR} "${CMAKE_CURRENT_BINARY_DIR}/usr/include" PARENT_SCOPE)
56 | endfunction()
57 |
--------------------------------------------------------------------------------
/cmake_modules/DownloadUEyeDriversUnofficial.cmake:
--------------------------------------------------------------------------------
1 | # Script based on:
2 | # https://bitbucket.org/kmhallen/ueye/src/4d8e78311e9d1ba4db3327b89862c3fa3ae602d1/CMakeLists.txt?at=default
3 |
4 | function(download_ueye_drivers UEYE_LIBRARY_VAR UEYE_INCLUDE_DIR_VAR UEYE_DRIVER_DIR)
5 | message(WARNING "The official IDS uEye drivers were not detected on your machine. A temporary version of the header/library will be downloaded locally to your ROS buildspace, to ensure that this package compiles. Nevertheless, you (or a system administrator) MUST still download and install the official IDS uEye drivers (http://en.ids-imaging.com/download-ueye.html). Also make sure that the IDS daemon (/etc/init.d/ueyeusbdrc) is running.")
6 |
7 | include(CheckIncludeFileCXX)
8 | check_include_file_cxx("ueye.h" FOUND_UEYE_H)
9 | if (FOUND_UEYE_H)
10 | # Assumed that uEye drivers were installed unofficially previously, and that both include and link dirs are in typical expected locations
11 | set(${UEYE_LIBRARY_VAR} ueye_api PARENT_SCOPE)
12 | set(${UEYE_INCLUDE_DIR_VAR} '' PARENT_SCOPE)
13 |
14 | else (FOUND_UEYE_H)
15 | # Determine system architecture
16 | if(NOT UNIX)
17 | message(FATAL_ERROR "Downloading IDS uEye drivers for non-Linux systems not supported")
18 | endif()
19 | include(cmake_modules/TargetArch.cmake)
20 | target_architecture(UEYE_ARCH)
21 | if (UEYE_ARCH STREQUAL "x86_64")
22 | set (UEYE_ARCH "amd64")
23 | elseif ((UEYE_ARCH STREQUAL "armv5") OR (UEYE_ARCH STREQUAL "armv6") OR (UEYE_ARCH STREQUAL "armv7"))
24 | set (UEYE_ARCH "arm")
25 | elseif (UEYE_ARCH STREQUAL "aarch64")
26 | set (UEYE_ARCH "arm64")
27 | endif ()
28 |
29 | # Set download path (credits due to ueye ROS package developers)
30 | set (UEYE_ARCHIVE uEye_SDK_${UEYE_ARCH}.tar.gz)
31 | if (UEYE_ARCH STREQUAL "amd64")
32 | set (UEYE_DRIVER_URL https://github.com/anqixu/unofficial_ueye_sdk_drivers/raw/main/uEye_SDK_4_94_amd64.tar.gz)
33 | set (UEYE_DRIVER_MD5 f6d011cf739ccdd2274c5a7a0d6c158a)
34 | elseif (UEYE_ARCH STREQUAL "arm")
35 | set (UEYE_DRIVER_URL https://github.com/anqixu/unofficial_ueye_sdk_drivers/raw/main/uEye_SDK_4_94_armhf.tar.gz)
36 | set (UEYE_DRIVER_MD5 3fea88ddd3807eb63cea9b84e0f9d66c)
37 | elseif (UEYE_ARCH STREQUAL "arm64")
38 | set (UEYE_DRIVER_URL https://github.com/anqixu/unofficial_ueye_sdk_drivers/raw/main/uEye_SDK_4_94_arm64.tar.gz)
39 | set (UEYE_DRIVER_MD5 9aa3d071b6436a927fbc162c3175d010)
40 | else ()
41 | message(FATAL_ERROR "The system's architecture, ${UEYE_ARCH}, is not supported currently by IDS / this ROS package.")
42 | message(FATAL_ERROR "Internal debugging: CMAKE_SYSTEM_PROCESSOR=${CMAKE_SYSTEM_PROCESSOR}, CMAKE_SYSTEM_NAME=${CMAKE_SYSTEM_NAME}")
43 | endif()
44 |
45 | # Download and unpack drivers locally
46 | if(EXISTS "${UEYE_DRIVER_DIR}/${UEYE_ARCHIVE}")
47 | message(STATUS "Using locally downloaded drivers: ${UEYE_DRIVER_DIR}/${UEYE_ARCHIVE}")
48 | else()
49 | message(STATUS "Downloading drivers to: ${UEYE_DRIVER_DIR}/${UEYE_ARCHIVE}")
50 | file(DOWNLOAD
51 | ${UEYE_DRIVER_URL}
52 | ${UEYE_DRIVER_DIR}/${UEYE_ARCHIVE}
53 | SHOW_PROGRESS
54 | INACTIVITY_TIMEOUT 60
55 | EXPECTED_MD5 ${UEYE_DRIVER_MD5}
56 | TLS_VERIFY on)
57 | endif()
58 | execute_process(
59 | COMMAND ${CMAKE_COMMAND} -E tar xzf ${UEYE_DRIVER_DIR}/${UEYE_ARCHIVE}
60 | WORKING_DIRECTORY ${UEYE_DRIVER_DIR}
61 | )
62 |
63 | if(UEYE_ARCH STREQUAL "arm")
64 | set (UEYE_ARCH_DIR "armhf")
65 | else()
66 | set (UEYE_ARCH_DIR "${UEYE_ARCH}")
67 | endif()
68 |
69 | configure_file(
70 | ${UEYE_DRIVER_DIR}/${UEYE_ARCH_DIR}/ueye.h
71 | ${UEYE_DRIVER_DIR}/${UEYE_ARCH_DIR}/uEye.h
72 | COPYONLY
73 | )
74 |
75 | # Re-direct include and linker paths
76 | set(${UEYE_LIBRARY_VAR} ${UEYE_DRIVER_DIR}/${UEYE_ARCH_DIR}/libueye_api.so PARENT_SCOPE)
77 | set(${UEYE_INCLUDE_DIR_VAR} ${UEYE_DRIVER_DIR}/${UEYE_ARCH_DIR} PARENT_SCOPE)
78 | endif (FOUND_UEYE_H)
79 | endfunction()
80 |
--------------------------------------------------------------------------------
/launch/debug.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
--------------------------------------------------------------------------------
/launch/xs_bayer_rggb.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
--------------------------------------------------------------------------------
/launch/rgb8.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
--------------------------------------------------------------------------------
/launch/bayer_rggb_image_proc.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
66 |
67 |
68 |
69 |
70 |
71 |
--------------------------------------------------------------------------------
/resources/xs.ini:
--------------------------------------------------------------------------------
1 | [Versions]
2 | libueye_api.so=4.50.0017
3 | ueyed-usb=4.50.0017
4 | ueye_boot.sys=4.50.0017
5 |
6 |
7 | [Sensor]
8 | Sensor=XS
9 | Sensor bit depth=0
10 | Sensor source gain=0
11 | FPN correction mode=0
12 | Black reference mode=0
13 |
14 |
15 | [Image size]
16 | Start X=0
17 | Start Y=0
18 | Start X absolute=0
19 | Start Y absolute=0
20 | Width=1280
21 | Height=720
22 | Binning=0
23 | Subsampling=0
24 |
25 |
26 | [Scaler]
27 | Mode=0
28 | Factor=0.000000
29 |
30 |
31 | [Multi AOI]
32 | Enabled=0
33 | Mode=0
34 | x1=0
35 | x2=0
36 | x3=0
37 | x4=0
38 | y1=0
39 | y2=0
40 | y3=0
41 | y4=0
42 |
43 |
44 | [Shutter]
45 | Mode=0
46 | Linescan number=0
47 |
48 |
49 | [Log Mode]
50 | Mode=3
51 | Manual value=0
52 | Manual gain=0
53 |
54 |
55 | [Timing]
56 | Pixelclock=30
57 | Extended pixelclock range=0
58 | Framerate=11.630747
59 | Exposure=85.682667
60 | Long exposure=0
61 | Dual exposure ratio=0
62 |
63 |
64 | [Selected Converter]
65 | IS_SET_CM_RGB32=1
66 | IS_SET_CM_RGB24=256
67 | IS_SET_CM_RGB16=8
68 | IS_SET_CM_RGB15=8
69 | IS_SET_CM_Y8=8
70 | IS_SET_CM_RGB8=0
71 | IS_SET_CM_BAYER=8
72 | IS_SET_CM_UYVY=256
73 | IS_SET_CM_UYVY_MONO=0
74 | IS_SET_CM_UYVY_BAYER=0
75 | IS_CM_CBYCRY_PACKED=256
76 | IS_SET_CM_RGBY=0
77 | IS_SET_CM_RGB30=0
78 | IS_SET_CM_Y12=0
79 | IS_SET_CM_BAYER12=0
80 | IS_SET_CM_Y16=0
81 | IS_SET_CM_BAYER16=0
82 | IS_CM_BGR12_UNPACKED=0
83 | IS_CM_BGRA12_UNPACKED=0
84 | IS_CM_JPEG=256
85 | IS_CM_SENSOR_RAW10=8
86 | IS_CM_MONO10=0
87 | IS_CM_BGR10_UNPACKED=0
88 | IS_CM_RGBA8_PACKED=0
89 | IS_CM_RGB8_PACKED=0
90 | IS_CM_RGBY8_PACKED=0
91 | IS_CM_RGB10V2_PACKED=0
92 | IS_CM_RGB12_UNPACKED=0
93 | IS_CM_RGBA12_UNPACKED=0
94 | IS_CM_RGB10_UNPACKED=0
95 | IS_CM_RGB8_PLANAR=0
96 |
97 |
98 | [Parameters]
99 | Colormode=6
100 | Gamma=1.000000
101 | Hardware Gamma=1
102 | Blacklevel Mode=0
103 | Blacklevel Offset=0
104 | Hotpixel Mode=0
105 | Hotpixel Threshold=0
106 | Sensor Hotpixel=1
107 | GlobalShutter=0
108 | AllowRawWithLut=0
109 |
110 |
111 | [Gain]
112 | Master=52
113 | Red=0
114 | Green=0
115 | Blue=0
116 | GainBoost=7
117 |
118 |
119 | [Processing]
120 | EdgeEnhancementFactor=0
121 | RopEffect=0
122 | Whitebalance=0
123 | Whitebalance Red=1.000000
124 | Whitebalance Green=1.000000
125 | Whitebalance Blue=1.000000
126 | Whitebalance Sensor Mode=1
127 | Color correction=0
128 | Color_correction_factor=1.000000
129 | Color_correction_satU=100
130 | Color_correction_satV=100
131 | Bayer Conversion=1
132 | JpegCompression=2
133 | NoiseMode=1
134 | ImageEffect=0
135 | LscModel=3
136 | WideDynamicRange=0
137 | Saturation=0
138 | Sharpness=0
139 |
140 |
141 | [Auto features]
142 | Auto Framerate control=0
143 | Brightness exposure control=0
144 | Brightness gain control=0
145 | Auto Framerate Sensor control=0
146 | Brightness exposure Sensor control=1
147 | Brightness gain Sensor control=1
148 | Brightness exposure Sensor control photometry=0
149 | Brightness gain Sensor control photometry=0
150 | Brightness control once=0
151 | Brightness reference=128
152 | Brightness speed=50
153 | Brightness max gain=100
154 | Brightness max exposure=66.684500
155 | Brightness Aoi Left=0
156 | Brightness Aoi Top=0
157 | Brightness Aoi Width=1280
158 | Brightness Aoi Height=720
159 | Brightness Hysteresis=2
160 | Brightness Sensor Backlight Compensation=0
161 | Auto WB control=0
162 | Auto WB type=2
163 | Auto WB RGB color model=1
164 | Auto WB RGB color temperature=0
165 | Auto WB offsetR=0
166 | Auto WB offsetB=0
167 | Auto WB Sensor offsetR=71
168 | Auto WB Sensor offsetB=70
169 | Auto WB gainMin=0
170 | Auto WB gainMax=100
171 | Auto WB speed=50
172 | Auto WB Aoi Left=0
173 | Auto WB Aoi Top=0
174 | Auto WB Aoi Width=1280
175 | Auto WB Aoi Height=720
176 | Auto WB Once=0
177 | Auto WB Hysteresis=2
178 | Brightness Skip Frames Trigger Mode=4
179 | Brightness Skip Frames Freerun Mode=4
180 | Auto WB Skip Frames Trigger Mode=4
181 | Auto WB Skip Frames Freerun Mode=4
182 |
183 |
184 | [Trigger and Flash]
185 | Trigger mode=0
186 | Trigger timeout=0
187 | Trigger delay=0
188 | Trigger debounce mode=0
189 | Trigger debounce delay time=0
190 | Trigger burst size=1
191 | Trigger prescaler frame=1
192 | Trigger prescaler line=1
193 | Trigger input=1
194 | Flash strobe=0
195 | Flash delay=0
196 | Flash duration=0
197 | Flash auto freerun=0
198 | PWM mode=0
199 | PWM frequency=62500000
200 | PWM dutycycle=62500000
201 | GPIO state=0
202 | GPIO direction=0
203 |
204 |
205 | [Lens Focus]
206 | Focus manual value=240
207 | Focus AF enable=1
208 | Focus AF use FDT AOI=0
209 | Focus AF zone preset=0
210 |
211 |
212 | [Zoom]
213 | Digital zoom factor=1.000000
214 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 |
3 | project(ueye_cam)
4 |
5 | # C++11 Needed
6 | include(CheckCXXCompilerFlag)
7 |
8 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
9 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
10 |
11 | if(COMPILER_SUPPORTS_CXX11)
12 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
13 | elseif(COMPILER_SUPPORTS_CXX0X)
14 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
15 | else()
16 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
17 | endif()
18 |
19 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -g")
20 |
21 | find_package(catkin REQUIRED COMPONENTS
22 | roscpp
23 | nodelet
24 | dynamic_reconfigure
25 | image_transport
26 | sensor_msgs
27 | camera_calibration_parsers
28 | camera_info_manager
29 | )
30 | catkin_destinations() # define ${CATKIN_PACKAGE_SHARE_DESTINATION}
31 |
32 | #set(UEYE_LIBRARY_PATH /usr/lib)
33 | find_library(UEYE_LIBRARY ueye_api)
34 | set(USE_UNOFFICIAL_UEYE_DRIVERS FALSE)
35 | if(NOT UEYE_LIBRARY)
36 | message(STATUS "libueye_api was not found in system's library path")
37 | #include(cmake_modules/DownloadUEyeDrivers.cmake)
38 | include(cmake_modules/DownloadUEyeDriversUnofficial.cmake)
39 | set(UEYE_DRIVER_DIR ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION})
40 | if(UEYE_DRIVER_DIR)
41 | message(STATUS "Setting UEYE_DRIVER_DIR to: ${UEYE_DRIVER_DIR}")
42 | else()
43 | set(UEYE_DRIVER_DIR ${CMAKE_CURRENT_BINARY_DIR})
44 | message(STATUS "Failed to set UEYE_DRIVER_DIR to: CATKIN_DEVEL_PREFIX/CATKIN_PACKAGE_SHARE_DESTINATION, defaulting to CMAKE_CURRENT_BINARY_DIR: ${UEYE_DRIVER_DIR}")
45 | endif()
46 | download_ueye_drivers(UEYE_LIBRARY UEYE_INCLUDE_DIR ${UEYE_DRIVER_DIR})
47 | message(STATUS "libueye_api library: ${UEYE_LIBRARY}")
48 | message(STATUS "libueye_api include: ${UEYE_INCLUDE_DIR}")
49 | set(USE_UNOFFICIAL_UEYE_DRIVERS TRUE)
50 | endif()
51 |
52 | set(UEYECAM_NODELET_NAME ueye_cam_nodelet)
53 | set(UEYECAM_LIB_NAME ueye_wrapper)
54 |
55 | set(UEYECAM_LIB_SOURCES
56 | src/ueye_cam_driver.cpp
57 | )
58 |
59 | set(UEYECAM_LIB_HEADERS
60 | include/ueye_cam/logging_macros.hpp
61 | include/ueye_cam/ueye_cam_driver.hpp
62 | )
63 |
64 | set(UEYECAM_NODELET_SOURCES
65 | src/ueye_cam_nodelet.cpp
66 | )
67 |
68 | set(UEYECAM_NODELET_HEADERS
69 | include/ueye_cam/ueye_cam_nodelet.hpp
70 | )
71 |
72 | generate_dynamic_reconfigure_options(
73 | cfg/UEyeCam.cfg
74 | )
75 |
76 | catkin_package(
77 | INCLUDE_DIRS include
78 | LIBRARIES ${UEYECAM_LIB_NAME} ${UEYECAM_NODELET_NAME}
79 | CATKIN_DEPENDS roscpp nodelet dynamic_reconfigure image_transport sensor_msgs camera_calibration_parsers camera_info_manager
80 | )
81 |
82 | include_directories(
83 | include
84 | ${catkin_INCLUDE_DIRS}
85 | ${UEYE_INCLUDE_DIR}
86 | )
87 |
88 |
89 | add_library(${UEYECAM_LIB_NAME} ${UEYECAM_LIB_SOURCES} ${UEYECAM_LIB_HEADERS})
90 | target_link_libraries(${UEYECAM_LIB_NAME} ${catkin_LIBRARIES} ${UEYE_LIBRARY})
91 |
92 | add_library(${UEYECAM_NODELET_NAME} ${UEYECAM_NODELET_SOURCES} ${UEYECAM_NODELET_HEADERS})
93 | target_link_libraries(${UEYECAM_NODELET_NAME} ${catkin_LIBRARIES} ${UEYECAM_LIB_NAME})
94 | add_dependencies(${UEYECAM_NODELET_NAME} ${PROJECT_NAME}_gencfg)
95 |
96 | add_executable(check_ueye_api src/check_ueye_api.cpp)
97 | target_link_libraries(check_ueye_api ${catkin_LIBRARIES})
98 |
99 | # Do not package the barebones IDS drivers, since they will mask over the official drivers (when present)
100 | #if(USE_UNOFFICIAL_UEYE_DRIVERS)
101 | # get_filename_component(UNOFFICIAL_UEYE_DRIVERS_LIB_REALPATH ${UEYE_LIBRARY} REALPATH)
102 | # install(FILES ${UEYE_LIBRARY} ${UNOFFICIAL_UEYE_DRIVERS_LIB_REALPATH}
103 | # DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
104 | #endif()
105 |
106 | # Mark cpp header files for installation
107 | install(DIRECTORY include/${PROJECT_NAME}/
108 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
109 | FILES_MATCHING PATTERN "*.h"
110 | PATTERN ".svn" EXCLUDE
111 | )
112 |
113 | install(TARGETS ${UEYECAM_LIB_NAME} ${UEYECAM_NODELET_NAME} check_ueye_api
114 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
115 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
116 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
117 | )
118 |
119 | install(FILES nodelet_plugins.xml
120 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
121 | )
122 |
123 | install(DIRECTORY launch/
124 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
125 | )
126 |
--------------------------------------------------------------------------------
/include/ueye_cam/logging_macros.hpp:
--------------------------------------------------------------------------------
1 | /*******************************************************************************
2 | * DO NOT MODIFY - AUTO-GENERATED
3 | *
4 | *
5 | * DISCLAMER:
6 | *
7 | * This project was created within an academic research setting, and thus should
8 | * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 | * code, so please adjust expectations accordingly. With that said, we are
10 | * intrinsically motivated to ensure its correctness (and often its performance).
11 | * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 | * to file bugs, suggestions, pull requests; we will do our best to address them
13 | * in a timely manner.
14 | *
15 | *
16 | * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 | *
18 | * Copyright (c) 2013-2016, Anqi Xu and contributors
19 | * All rights reserved.
20 | *
21 | * Redistribution and use in source and binary forms, with or without
22 | * modification, are permitted provided that the following conditions
23 | * are met:
24 | *
25 | * * Redistributions of source code must retain the above copyright
26 | * notice, this list of conditions and the following disclaimer.
27 | * * Redistributions in binary form must reproduce the above
28 | * copyright notice, this list of conditions and the following
29 | * disclaimer in the documentation and/or other materials provided
30 | * with the distribution.
31 | * * Neither the name of the School of Computer Science, McGill University,
32 | * nor the names of its contributors may be used to endorse or promote
33 | * products derived from this software without specific prior written
34 | * permission.
35 | *
36 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 | *******************************************************************************/
47 |
48 | #ifndef LOGGING_MACROS_HPP_
49 | #define LOGGING_MACROS_HPP_
50 |
51 | /**
52 | * This header allows potentially ROS-agnostic code to either use ROS logging
53 | * mechanisms, ROS nodelet logging mechanisms, or standard output mechanisms.
54 | */
55 |
56 | #define STD_LOGGING_MACROS 0
57 | #define ROS_LOGGING_MACROS 1
58 | #define NODELET_LOGGING_MACROS 2
59 | #define LOGGING_MACROS_TYPE NODELET_LOGGING_MACROS
60 |
61 |
62 | #if LOGGING_MACROS_TYPE == ROS_LOGGING_MACROS
63 |
64 | #include
65 |
66 | #define DEBUG(...) ROS_DEBUG(__VA_ARGS__)
67 | #define INFO(...) ROS_INFO(__VA_ARGS__)
68 | #define WARN(...) ROS_WARN(__VA_ARGS__)
69 | #define ERROR(...) ROS_ERROR(__VA_ARGS__)
70 | #define FATAL(...) ROS_FATAL(__VA_ARGS__)
71 | #define DEBUG_STREAM(...) ROS_DEBUG_STREAM(__VA_ARGS__)
72 | #define INFO_STREAM(...) ROS_INFO_STREAM(__VA_ARGS__)
73 | #define WARN_STREAM(...) ROS_WARN_STREAM(__VA_ARGS__)
74 | #define ERROR_STREAM(...) ROS_ERROR_STREAM(__VA_ARGS__)
75 | #define FATAL_STREAM(...) ROS_FATAL_STREAM(__VA_ARGS__)
76 |
77 | #elif LOGGING_MACROS_TYPE == NODELET_LOGGING_MACROS
78 |
79 | #include
80 | #include
81 |
82 | using namespace ros::this_node;
83 |
84 | #define DEBUG(...) NODELET_DEBUG(__VA_ARGS__)
85 | #define INFO(...) NODELET_INFO(__VA_ARGS__)
86 | #define WARN(...) NODELET_WARN(__VA_ARGS__)
87 | #define ERROR(...) NODELET_ERROR(__VA_ARGS__)
88 | #define FATAL(...) NODELET_FATAL(__VA_ARGS__)
89 | #define DEBUG_STREAM(...) NODELET_DEBUG_STREAM(__VA_ARGS__)
90 | #define INFO_STREAM(...) NODELET_INFO_STREAM(__VA_ARGS__)
91 | #define WARN_STREAM(...) NODELET_WARN_STREAM(__VA_ARGS__)
92 | #define ERROR_STREAM(...) NODELET_ERROR_STREAM(__VA_ARGS__)
93 | #define FATAL_STREAM(...) NODELET_FATAL_STREAM(__VA_ARGS__)
94 |
95 | #else
96 | #include
97 | #include
98 |
99 | #define DEBUG(...) fprintf(stdout, "DEBUG> "); fprintf(stdout, __VA_ARGS__); fprintf(stdout, "\n")
100 | #define INFO(...) fprintf(stdout, "INFO > "); fprintf(stdout, __VA_ARGS__); fprintf(stdout, "\n")
101 | #define WARN(...) fprintf(stderr, "WARN > "); fprintf(stderr, __VA_ARGS__); fprintf(stderr, "\n")
102 | #define ERROR(...) fprintf(stderr, "ERROR> "); fprintf(stderr, __VA_ARGS__); fprintf(stderr, "\n")
103 | #define FATAL(...) fprintf(stderr, "FATAL> "); fprintf(stderr, __VA_ARGS__); fprintf(stderr, "\n")
104 | #define DEBUG_STREAM(...) std::cout << "DEBUG> " << __VA_ARGS__ << std::endl
105 | #define INFO_STREAM(...) std::cout << "INFO > " << __VA_ARGS__ << std::endl
106 | #define WARN_STREAM(...) std::cerr << "WARN > " << __VA_ARGS__ << std::endl
107 | #define ERROR_STREAM(...) std::cerr << "ERROR> " << __VA_ARGS__ << std::endl
108 | #define FATAL_STREAM(...) std::cerr << "FATAL> " << __VA_ARGS__ << std::endl
109 |
110 | #endif
111 |
112 | #endif /* LOGGING_MACROS_HPP_ */
113 |
--------------------------------------------------------------------------------
/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package ueye_cam
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 1.0.19 (2021-01-13)
6 | -------------------
7 | * updated MD5 hash for re-packaged unofficiall IDS drivers archives
8 | * Contributors: Anqi Xu
9 |
10 | 1.0.18 (2021-01-09)
11 | -------------------
12 | * updated driver URLs for 4.94 version
13 | * [uEye 4.94] Update Deprecated Event Handling Functions (`#97 `)
14 | * Updated event functions to 4.94 API + Added init of event before enabling it
15 | * Added uEye 4.94 req
16 | * Changed timeout to UINT to fit 4_94 API
17 | * Adding call of exit routine for the frame event
18 | * Adding auto exposure reference value
19 | * Added support for setting the software-gamma
20 | * Package format update and code cleanup
21 | * Contributors: Anqi Xu, Brett Newman, Nullket, jmackay2, nullket
22 |
23 | 1.0.17 (2020-08-26)
24 | -------------------
25 | * Merge pull request `#83 ` from anqixu/use_ros_time
26 | Do not get timestamp from camera, and use ros::Time::now() instead
27 | * Merge pull request `#61 ` from jackokaiser/master
28 | Adapted roslaunch for passing camera name as argument
29 | * Changes from https://github.com/anqixu/ueye_cam/issues/82
30 | * Do not link the ueye api to the check api node to avoid conflicts
31 | * Default dynamic_reconfigure parameters now don't overwrite ini file params.
32 | Fixes `#74 `
33 | * image dimensions now account for cam_subsampling_rate
34 | * Merge pull request `#65 ` from flynneva/dev
35 | * removed / from frame_ID so that data can be used with new ros tf2 standard
36 | * Removed trailing whitespaces
37 | * Readded camera_conf for backward compatibility
38 | * changed setFlashParams failure into warning
39 | * Adapted roslaunch for passing camera name as argument
40 | * nodelet no longer dies upon setFlashParams fail (since some cameras don't support it)
41 | * Merge pull request `#54 ` from 534o/master
42 | * forget to add check_ueye_api to install list
43 | * Contributors: Anqi Xu, Anup Parikh, Evan Flynn, Jacques KAISER, Tokyo Opensource Robotics Developer 534, loooph
44 |
45 | 1.0.16 (2017-01-02)
46 | -------------------
47 | * fixed crash on camera reconnect
48 | * Contributors: Anqi Xu, Christopher Wecht
49 |
50 | 1.0.15 (2016-08-25)
51 | -------------------
52 | * recover + update from failure in setColorMode
53 | * extended color modes (10, 12, 16 bit per channel)
54 | * added timeout topic for better debugging of frame timeouts
55 | * Contributors: Anqi Xu, Dominik Klein
56 |
57 | 1.0.14 (2016-05-26)
58 | -------------------
59 | * now attempting to link against 32-bit ARMHF IDS libs on ARM64 arch
60 | * added capability to detect ARM64 processor (aarch64)
61 | * added separate rates for polling frames vs publishing images
62 | * fixed buffersize for subsampling and increased maximum image size availible via rqt
63 | * added Travis CI config
64 | * Contributors: Anqi Xu, Eddy, Isaac I.Y. Saito, francois
65 |
66 | 1.0.13 (2016-05-13)
67 | -------------------
68 | * Change timestamp source based on issue https://github.com/anqixu/ueye_cam/issues/37
69 | * changed 'failure to set active-low flash' from error to warning
70 | * Fixed typo in Gain for dynamic reconfigure parameters
71 | * Updated pixel_clock cap in dyncfg settings
72 | * Added check_ueye_api to confirm availability of IDS SDK at runtime
73 | * Contributors: Anqi Xu, Anup, Aris Synodinos, Kei Okada
74 |
75 | 1.0.12 (2015-09-28)
76 | -------------------
77 | * fixed binning IS_INVALID_BUFFER_SIZE bug
78 | * Modified nodelet to use camera timestamp instead of wall clock time
79 | * Fix for new upstream dir name on ARM
80 | * Contributors: Alejandro Merello, Anqi Xu, Scott K Logan
81 |
82 | 1.0.11 (2015-08-17)
83 | -------------------
84 | * updated barebones IDS drivers to 4.61
85 | * removed barebones IDS drivers from debian packaging
86 | * Added proper checking for C++11 features on compilers
87 | * Performed minor code cleanup, updated old PLUGINLIB_DECLARE_CLASS to
88 | newer PLUGINLIB_EXPORT_CLASS
89 | * Contributors: Anqi Xu, Aris Synodinos
90 |
91 | 1.0.10 (2015-08-06)
92 | -------------------
93 | * fixed setting synchronization bugs during camera initialization
94 | * added support for (packed) BGR8 color mode
95 | * failing to set non-essential parameters will no longer prematurily terminate nodelet
96 | * updated printouts to be more verbose and consistent
97 | * fix for reported ARM arch on Fedora
98 | * Contributors: Anqi Xu, Scott K Logan
99 |
100 | 1.0.9 (2015-02-03)
101 | ------------------
102 | * fixed lagged changes to flip_upd and flip_lr via rqt_reconfigure
103 | * Support discrete-only pixelclocks cameras
104 | * Ask if gainboost is supported first
105 | * Switched to jbohren's version of the file(GENERATE...) fix
106 | * Contributors: Anqi Xu, Fran Real, Jonathan Bohren
107 |
108 | 1.0.8 (2015-01-08)
109 | ------------------
110 | * switched from cmake's file(GENERATE ...) to execute_command(cp ...), to accommodate cmake 2.8.x on Saucy
111 | * Contributors: Anqi Xu
112 |
113 | 1.0.7 (2014-12-22)
114 | ------------------
115 | * continuing to address issues on ROS bin buildfarm
116 | * Contributors: Anqi Xu
117 |
118 | 1.0.6 (2014-12-18)
119 | ------------------
120 | * continuing to trying to fix errors on ROS buildfarm
121 | * Contributors: Anqi Xu
122 |
123 | 1.0.5 (2014-12-11)
124 | ------------------
125 | * fixed/improved unofficial driver install; added warning messages during compile- & run-time to note that unofficially-installed drivers will allow ueye_cam to be compiled, but will not detect any cameras during runtime (since IDS camera daemon is not packaged in unofficial driver download)
126 | * Contributors: Anqi Xu
127 |
128 | 1.0.4 (2014-12-01)
129 | ------------------
130 | * Switching to DownloadUEyeDriversUnofficial.cmake (based on ueye ROS package) until IDS grants official permission
131 | * Contributors: Anqi Xu
132 |
133 | 1.0.3 (2014-11-05)
134 | ------------------
135 | * Dependency switch from 'vision_opencv' meta-package to 'cv_bridge' package
136 | * trim '/' prefix of topic and service to change to relative name-space
137 | * Contributors: Anqi Xu, Yutaka Kondo
138 |
139 | 1.0.2 (2014-10-16)
140 | ------------------
141 | * switched from rosdep 'opencv2' to 'vision_opencv'
142 | * Contributors: Anqi Xu
143 |
144 | 1.0.1 (2014-10-16)
145 | ------------------
146 | * Package now attempts to auto-install IDS uEye drivers; prints more useful info for IS_TIMED_OUT errors
147 | * First attempt at debian-packaging
148 | * Contributors: Anqi Xu, Dirk Thomas, Juan Camilo Gamboa Higuera, Kei Okada, Yutaka Kondo
149 |
--------------------------------------------------------------------------------
/cfg/UEyeCam.cfg:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | PACKAGE = "ueye_cam"
3 |
4 | from dynamic_reconfigure.parameter_generator_catkin import *
5 |
6 | RECONFIGURE_RUNNING = 0
7 | RECONFIGURE_STOP = 1
8 | RECONFIGURE_CLOSE = 3
9 |
10 | gen = ParameterGenerator()
11 |
12 | gen.add("image_width", int_t, RECONFIGURE_STOP,
13 | "Width of camera's area of interest (prior to subsampling, binning, or sensor scaling)", 640, 16, 4912)
14 | gen.add("image_height", int_t, RECONFIGURE_STOP,
15 | "Height of camera's area of interest (prior to subsampling, binning, or sensor scaling)", 480, 4, 3684)
16 | gen.add("image_left", int_t, RECONFIGURE_STOP,
17 | "Left index for camera's area of interest (-1: center)", -1, -1, 2560-16)
18 | gen.add("image_top", int_t, RECONFIGURE_STOP,
19 | "Top index for camera's area of interest (-1: center)", -1, -1, 1920-4)
20 |
21 | color_mode_enum = gen.enum([
22 | gen.const("MONO8", str_t, "mono8", "8-bit Monochrome"),
23 | gen.const("MONO10", str_t, "mono10", "10-bit Monochrome"),
24 | gen.const("MONO12", str_t, "mono12", "12-bit Monochrome"),
25 | gen.const("MONO16", str_t, "mono16", "16-bit Monochrome"),
26 | gen.const("RGB8", str_t, "rgb8", "24-bit Red/Green/Blue"),
27 | gen.const("RGB10", str_t, "rgb10", "32-bit packed Red/Green/Blue"),
28 | gen.const("RGB10u", str_t, "rgb10u", "48-bit unpacked Red/Green/Blue"),
29 | gen.const("RGB12u", str_t, "rgb12u", "48-bit unpacked Red/Green/Blue"),
30 | gen.const("BGR8", str_t, "bgr8", "24-bit Blue/Green/Red"),
31 | gen.const("BGR10", str_t, "bgr10", "32-bit packed Blue/Green/Red"),
32 | gen.const("BGR10u", str_t, "bgr10u", "48-bit unpacked Blue/Green/Red"),
33 | gen.const("BGR12u", str_t, "bgr12u", "48-bit unpacked Blue/Green/Red"),
34 | gen.const("BAYER_RGGB8", str_t, "bayer_rggb8", "8-bit Raw Bayer (RGGB)")],
35 | "Color mode values")
36 | gen.add("color_mode", str_t, RECONFIGURE_STOP,
37 | "Output image color mode", "mono8", edit_method=color_mode_enum)
38 |
39 | subsampling_enum = gen.enum([
40 | gen.const("SUB_1X", int_t, 1, "1X Subsampling"),
41 | gen.const("SUB_2X", int_t, 2, "2X Subsampling"),
42 | gen.const("SUB_4X", int_t, 4, "4X Subsampling"),
43 | gen.const("SUB_8X", int_t, 8, "8X Subsampling"),
44 | gen.const("SUB_16X", int_t, 16, "16X Subsampling")],
45 | "Subsampling Values")
46 | gen.add("subsampling", int_t, RECONFIGURE_STOP,
47 | "Output image subsampling ratio", 1, edit_method=subsampling_enum)
48 |
49 | binning_enum = gen.enum([
50 | gen.const("BIN_1X", int_t, 1, "1X Binning"),
51 | gen.const("BIN_2X", int_t, 2, "2X Binning"),
52 | gen.const("BIN_4X", int_t, 4, "4X Binning"),
53 | gen.const("BIN_8X", int_t, 8, "8X Binning"),
54 | gen.const("BIN_16X", int_t, 16, "16X Binning")],
55 | "Binning Values")
56 | gen.add("binning", int_t, RECONFIGURE_STOP,
57 | "Output image binning ratio", 1, edit_method=binning_enum)
58 |
59 | sensor_scaling_enum = gen.enum([
60 | gen.const("SS_1X", double_t, 1.0, "1X Internal Image Scaling"),
61 | gen.const("SS_2X", double_t, 2.0, "2X Internal Image Scaling"),
62 | gen.const("SS_4X", double_t, 4.0, "4X Internal Image Scaling"),
63 | gen.const("SS_8X", double_t, 8.0, "8X Internal Image Scaling"),
64 | gen.const("SS_16X", double_t, 16.0, "16X Internal Image Scaling")],
65 | "Internal Image Scaling Values")
66 | gen.add("sensor_scaling", double_t, RECONFIGURE_STOP,
67 | "Output image scaling ratio (Internal Image Scaling)", 1, edit_method=sensor_scaling_enum)
68 |
69 | gen.add("auto_gain", bool_t, RECONFIGURE_RUNNING,
70 | "Auto gain (overruled by auto framerate)", False)
71 | gen.add("master_gain", int_t, RECONFIGURE_RUNNING,
72 | "Master gain percentage", 0, 0, 100)
73 | gen.add("red_gain", int_t, RECONFIGURE_RUNNING,
74 | "Gain percentage for red channel", 0, 0, 100)
75 | gen.add("green_gain", int_t, RECONFIGURE_RUNNING,
76 | "Gain percentage for green channel", 0, 0, 100)
77 | gen.add("blue_gain", int_t, RECONFIGURE_RUNNING,
78 | "Gain percentage for blue channel", 0, 0, 100)
79 | gen.add("gain_boost", bool_t, RECONFIGURE_RUNNING,
80 | "Analog gain boost", False)
81 | gen.add("software_gamma", int_t, RECONFIGURE_RUNNING,
82 | "Software gamma in percent", 100, 1, 1000)
83 |
84 |
85 | gen.add("auto_exposure", bool_t, RECONFIGURE_RUNNING,
86 | "Auto exposure (a.k.a. auto shutter)", False)
87 | gen.add("auto_exposure_reference", double_t, RECONFIGURE_RUNNING,
88 | "Target for the exposure/gain brightness controller", 128, 0.0, 255.0)
89 | gen.add("exposure", double_t, RECONFIGURE_RUNNING,
90 | "Exposure value (ms)", 33.0, 0.0, 300.0)
91 |
92 | gen.add("auto_white_balance", bool_t, RECONFIGURE_RUNNING,
93 | "Auto white balance", False)
94 | gen.add("white_balance_red_offset", int_t, RECONFIGURE_RUNNING,
95 | "Red level offset for white balance", 0, -50, 50)
96 | gen.add("white_balance_blue_offset", int_t, RECONFIGURE_RUNNING,
97 | "Blue level offset for white balance", 0, -50, 50)
98 |
99 | gen.add("flash_delay", int_t, RECONFIGURE_RUNNING,
100 | "Flash output delay (us) [not applicable in external trigger mode]", 0, -1000000, 1000000)
101 | gen.add("flash_duration", int_t, RECONFIGURE_RUNNING,
102 | "Flash output duration (us) (0: set to exposure duration) [not applicable in external trigger mode]", 1000, 0, 1000000)
103 |
104 | gen.add("ext_trigger_mode", bool_t, RECONFIGURE_STOP,
105 | "Toggle between external trigger mode and free-run mode", False)
106 |
107 | gpio_enum = gen.enum([
108 | gen.const("Input", int_t, 0, "Input"),
109 | gen.const("Output_Low", int_t, 1, "Output Low"),
110 | gen.const("Output_High", int_t, 2, "Output High"),
111 | gen.const("Flash", int_t, 3, "Flash"),
112 | gen.const("PWM_Output", int_t, 4, "PWM Output"),
113 | gen.const("Trigger", int_t, 5, "Trigger")],
114 | "Mode of a GPIO pin")
115 | gen.add("gpio1", int_t, RECONFIGURE_STOP,
116 | "Mode for GPIO1 (pin 5)", 0, edit_method=gpio_enum)
117 | gen.add("gpio2", int_t, RECONFIGURE_STOP,
118 | "Mode for GPIO2 (pin 6)", 0, edit_method=gpio_enum)
119 | gen.add("pwm_freq", double_t, RECONFIGURE_RUNNING,
120 | "PWM output frequency", 1, 1, 10000)
121 | gen.add("pwm_duty_cycle", double_t, RECONFIGURE_RUNNING,
122 | "PWM output duty cycle", 0.5, 0, 1)
123 |
124 | gen.add("auto_frame_rate", bool_t, RECONFIGURE_RUNNING,
125 | "Auto frame rate (requires auto exposure, supercedes auto gain) [not applicable in external trigger mode]", False)
126 | gen.add("frame_rate", double_t, RECONFIGURE_RUNNING,
127 | "Frame process rate (Hz) [not applicable in external trigger mode]", 10.0, 0.01, 200.0)
128 | gen.add("output_rate", double_t, RECONFIGURE_RUNNING,
129 | "Frame publish rate (Hz) (0: publish all processed frames) [not applicable in external trigger mode]", 0, 0, 200.0)
130 | gen.add("pixel_clock", int_t, RECONFIGURE_RUNNING,
131 | "Pixel clock (MHz)", 25, 1, 500)
132 |
133 |
134 | gen.add("flip_upd", bool_t, RECONFIGURE_RUNNING,
135 | "Mirror Upside Down", False)
136 | gen.add("flip_lr", bool_t, RECONFIGURE_RUNNING,
137 | "Mirror Left Right", False)
138 |
139 | exit(gen.generate(PACKAGE, "ueye_cam", "UEyeCam"))
140 |
--------------------------------------------------------------------------------
/cmake_modules/TargetArch.cmake:
--------------------------------------------------------------------------------
1 | # Source: https://raw.github.com/petroules/solar-cmake/master/TargetArch.cmake
2 |
3 | # Copyright (c) 2012 Petroules Corporation. All rights reserved.
4 | #
5 | # Redistribution and use in source and binary forms, with or without modification, are permitted provided
6 | # that the following conditions are met:
7 | #
8 | # Redistributions of source code must retain the above copyright notice, this list of conditions and the
9 | # following disclaimer. Redistributions in binary form must reproduce the above copyright notice, this list
10 | # of conditions and the following disclaimer in the documentation and/or other materials provided with the
11 | # distribution. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS
12 | # OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
13 | # FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
14 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
15 | # NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
16 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR
17 | # TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
18 | # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
19 |
20 | # Based on the Qt 5 processor detection code, so should be very accurate
21 | # https://qt.gitorious.org/qt/qtbase/blobs/master/src/corelib/global/qprocessordetection.h
22 | # Currently handles arm (v5, v6, v7), x86 (32/64), ia64, and ppc (32/64)
23 |
24 | # Regarding POWER/PowerPC, just as is noted in the Qt source,
25 | # "There are many more known variants/revisions that we do not handle/detect."
26 |
27 | set(archdetect_c_code "
28 | #if defined(__arm__) || defined(__TARGET_ARCH_ARM)
29 | #if defined(__ARM_ARCH_7__) \\
30 | || defined(__ARM_ARCH_7A__) \\
31 | || defined(__ARM_ARCH_7R__) \\
32 | || defined(__ARM_ARCH_7M__) \\
33 | || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 7)
34 | #error cmake_ARCH armv7
35 | #elif defined(__ARM_ARCH_6__) \\
36 | || defined(__ARM_ARCH_6J__) \\
37 | || defined(__ARM_ARCH_6T2__) \\
38 | || defined(__ARM_ARCH_6Z__) \\
39 | || defined(__ARM_ARCH_6K__) \\
40 | || defined(__ARM_ARCH_6ZK__) \\
41 | || defined(__ARM_ARCH_6M__) \\
42 | || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 6)
43 | #error cmake_ARCH armv6
44 | #elif defined(__ARM_ARCH_5TEJ__) \\
45 | || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 5)
46 | #error cmake_ARCH armv5
47 | #else
48 | #error cmake_ARCH arm
49 | #endif
50 | #elif defined(__aarch64__)
51 | #error cmake_ARCH aarch64
52 | #elif defined(__i386) || defined(__i386__) || defined(_M_IX86)
53 | #error cmake_ARCH i386
54 | #elif defined(__x86_64) || defined(__x86_64__) || defined(__amd64) || defined(_M_X64)
55 | #error cmake_ARCH x86_64
56 | #elif defined(__ia64) || defined(__ia64__) || defined(_M_IA64)
57 | #error cmake_ARCH ia64
58 | #elif defined(__ppc__) || defined(__ppc) || defined(__powerpc__) \\
59 | || defined(_ARCH_COM) || defined(_ARCH_PWR) || defined(_ARCH_PPC) \\
60 | || defined(_M_MPPC) || defined(_M_PPC)
61 | #if defined(__ppc64__) || defined(__powerpc64__) || defined(__64BIT__)
62 | #error cmake_ARCH ppc64
63 | #else
64 | #error cmake_ARCH ppc
65 | #endif
66 | #endif
67 |
68 | #error cmake_ARCH unknown
69 | ")
70 |
71 | # Set ppc_support to TRUE before including this file or ppc and ppc64
72 | # will be treated as invalid architectures since they are no longer supported by Apple
73 |
74 | function(target_architecture output_var)
75 | if(APPLE AND CMAKE_OSX_ARCHITECTURES)
76 | # On OS X we use CMAKE_OSX_ARCHITECTURES *if* it was set
77 | # First let's normalize the order of the values
78 |
79 | # Note that it's not possible to compile PowerPC applications if you are using
80 | # the OS X SDK version 10.6 or later - you'll need 10.4/10.5 for that, so we
81 | # disable it by default
82 | # See this page for more information:
83 | # http://stackoverflow.com/questions/5333490/how-can-we-restore-ppc-ppc64-as-well-as-full-10-4-10-5-sdk-support-to-xcode-4
84 |
85 | # Architecture defaults to i386 or ppc on OS X 10.5 and earlier, depending on the CPU type detected at runtime.
86 | # On OS X 10.6+ the default is x86_64 if the CPU supports it, i386 otherwise.
87 |
88 | foreach(osx_arch ${CMAKE_OSX_ARCHITECTURES})
89 | if("${osx_arch}" STREQUAL "ppc" AND ppc_support)
90 | set(osx_arch_ppc TRUE)
91 | elseif("${osx_arch}" STREQUAL "i386")
92 | set(osx_arch_i386 TRUE)
93 | elseif("${osx_arch}" STREQUAL "x86_64")
94 | set(osx_arch_x86_64 TRUE)
95 | elseif("${osx_arch}" STREQUAL "ppc64" AND ppc_support)
96 | set(osx_arch_ppc64 TRUE)
97 | else()
98 | message(FATAL_ERROR "Invalid OS X arch name: ${osx_arch}")
99 | endif()
100 | endforeach()
101 |
102 | # Now add all the architectures in our normalized order
103 | if(osx_arch_ppc)
104 | list(APPEND ARCH ppc)
105 | endif()
106 |
107 | if(osx_arch_i386)
108 | list(APPEND ARCH i386)
109 | endif()
110 |
111 | if(osx_arch_x86_64)
112 | list(APPEND ARCH x86_64)
113 | endif()
114 |
115 | if(osx_arch_ppc64)
116 | list(APPEND ARCH ppc64)
117 | endif()
118 | else()
119 | file(WRITE "${CMAKE_BINARY_DIR}/arch.c" "${archdetect_c_code}")
120 |
121 | enable_language(C)
122 |
123 | # Detect the architecture in a rather creative way...
124 | # This compiles a small C program which is a series of ifdefs that selects a
125 | # particular #error preprocessor directive whose message string contains the
126 | # target architecture. The program will always fail to compile (both because
127 | # file is not a valid C program, and obviously because of the presence of the
128 | # #error preprocessor directives... but by exploiting the preprocessor in this
129 | # way, we can detect the correct target architecture even when cross-compiling,
130 | # since the program itself never needs to be run (only the compiler/preprocessor)
131 | try_run(
132 | run_result_unused
133 | compile_result_unused
134 | "${CMAKE_BINARY_DIR}"
135 | "${CMAKE_BINARY_DIR}/arch.c"
136 | COMPILE_OUTPUT_VARIABLE ARCH
137 | CMAKE_FLAGS CMAKE_OSX_ARCHITECTURES=${CMAKE_OSX_ARCHITECTURES}
138 | )
139 |
140 | # Parse the architecture name from the compiler output
141 | string(REGEX MATCH "cmake_ARCH ([a-zA-Z0-9_]+)" ARCH "${ARCH}")
142 |
143 | # Get rid of the value marker leaving just the architecture name
144 | string(REPLACE "cmake_ARCH " "" ARCH "${ARCH}")
145 |
146 | # If we are compiling with an unknown architecture this variable should
147 | # already be set to "unknown" but in the case that it's empty (i.e. due
148 | # to a typo in the code), then set it to unknown
149 | if (NOT ARCH)
150 | set(ARCH unknown)
151 | endif()
152 | endif()
153 |
154 | set(${output_var} "${ARCH}" PARENT_SCOPE)
155 | endfunction()
156 |
--------------------------------------------------------------------------------
/launch/master_slaves_pwm_rgb8.launch:
--------------------------------------------------------------------------------
1 |
2 |
10 |
11 |
12 |
13 |
14 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
--------------------------------------------------------------------------------
/include/ueye_cam/ueye_cam_nodelet.hpp:
--------------------------------------------------------------------------------
1 | /*******************************************************************************
2 | * DO NOT MODIFY - AUTO-GENERATED
3 | *
4 | *
5 | * DISCLAMER:
6 | *
7 | * This project was created within an academic research setting, and thus should
8 | * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 | * code, so please adjust expectations accordingly. With that said, we are
10 | * intrinsically motivated to ensure its correctness (and often its performance).
11 | * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 | * to file bugs, suggestions, pull requests; we will do our best to address them
13 | * in a timely manner.
14 | *
15 | *
16 | * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 | *
18 | * Copyright (c) 2013-2016, Anqi Xu and contributors
19 | * All rights reserved.
20 | *
21 | * Redistribution and use in source and binary forms, with or without
22 | * modification, are permitted provided that the following conditions
23 | * are met:
24 | *
25 | * * Redistributions of source code must retain the above copyright
26 | * notice, this list of conditions and the following disclaimer.
27 | * * Redistributions in binary form must reproduce the above
28 | * copyright notice, this list of conditions and the following
29 | * disclaimer in the documentation and/or other materials provided
30 | * with the distribution.
31 | * * Neither the name of the School of Computer Science, McGill University,
32 | * nor the names of its contributors may be used to endorse or promote
33 | * products derived from this software without specific prior written
34 | * permission.
35 | *
36 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 | *******************************************************************************/
47 |
48 | #ifndef UEYE_CAM_NODELET_HPP_
49 | #define UEYE_CAM_NODELET_HPP_
50 |
51 |
52 | #include
53 | #include
54 | #include
55 | #include
56 | #include
57 | #include
58 | #include
59 | #include
60 | #include
61 |
62 |
63 | namespace ueye_cam {
64 |
65 |
66 | typedef dynamic_reconfigure::Server ReconfigureServer;
67 |
68 |
69 | /**
70 | * ROS interface nodelet for UEye camera API from IDS Imaging Development Systems GMBH.
71 | */
72 | class UEyeCamNodelet : public nodelet::Nodelet, public UEyeCamDriver {
73 | public:
74 | constexpr static unsigned int RECONFIGURE_RUNNING = 0;
75 | constexpr static unsigned int RECONFIGURE_STOP = 1;
76 | constexpr static unsigned int RECONFIGURE_CLOSE = 3;
77 | constexpr static int DEFAULT_IMAGE_WIDTH = 640; // NOTE: these default values do not matter, as they
78 | constexpr static int DEFAULT_IMAGE_HEIGHT = 480; // are overwritten by queryCamParams() during connectCam()
79 | constexpr static double DEFAULT_EXPOSURE = 33.0;
80 | constexpr static double DEFAULT_FRAME_RATE = 10.0;
81 | constexpr static int DEFAULT_PIXEL_CLOCK = 25;
82 | constexpr static int DEFAULT_FLASH_DURATION = 1000;
83 |
84 | const static std::string DEFAULT_FRAME_NAME;
85 | const static std::string DEFAULT_CAMERA_NAME;
86 | const static std::string DEFAULT_CAMERA_TOPIC;
87 | const static std::string DEFAULT_TIMEOUT_TOPIC;
88 | const static std::string DEFAULT_COLOR_MODE;
89 |
90 |
91 | UEyeCamNodelet();
92 |
93 | virtual ~UEyeCamNodelet();
94 |
95 | /**
96 | * Initializes ROS environment, loads static ROS parameters, initializes UEye camera,
97 | * and starts live capturing / frame grabbing thread.
98 | */
99 | virtual void onInit();
100 |
101 | /**
102 | * Handles callbacks from dynamic_reconfigure.
103 | */
104 | void configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level);
105 |
106 |
107 | protected:
108 | /**
109 | * Calls UEyeCamDriver::syncCamConfig(), then updates ROS camera info
110 | * and ROS image settings.
111 | */
112 | virtual INT syncCamConfig(std::string dft_mode_str = "mono8");
113 |
114 | /**
115 | * Reads parameter values from currently selected camera.
116 | */
117 | INT queryCamParams();
118 |
119 | /**
120 | * Loads, validates, and updates static ROS parameters.
121 | */
122 | INT parseROSParams(ros::NodeHandle& local_nh);
123 |
124 | /**
125 | * Initializes the camera handle, loads UEye INI configuration, refreshes
126 | * parameters from camera, loads and sets static ROS parameters, and starts
127 | * the frame grabber thread.
128 | */
129 | virtual INT connectCam();
130 |
131 | /**
132 | * Stops the frame grabber thread, closes the camera handle,
133 | * and releases all local variables.
134 | */
135 | virtual INT disconnectCam();
136 |
137 | /**
138 | * (ROS Service) Updates the camera's intrinsic parameters over the ROS topic,
139 | * and saves the parameters to a flatfile.
140 | */
141 | bool setCamInfo(sensor_msgs::SetCameraInfo::Request& req,
142 | sensor_msgs::SetCameraInfo::Response& rsp);
143 |
144 | /**
145 | * Loads the camera's intrinsic parameters from camIntrFilename.
146 | */
147 | void loadIntrinsicsFile();
148 |
149 |
150 | /**
151 | * Saves the camera's intrinsic parameters to camIntrFilename.
152 | */
153 | bool saveIntrinsicsFile();
154 |
155 | /**
156 | * Main ROS interface "spin" loop.
157 | */
158 | void frameGrabLoop();
159 | void startFrameGrabber();
160 | void stopFrameGrabber();
161 |
162 | const static std::map ENCODING_DICTIONARY;
163 | /**
164 | * Transfers the current frame content into given sensor_msgs::Image,
165 | * therefore writes the fields width, height, encoding, step and
166 | * data of img.
167 | */
168 | bool fillMsgData(sensor_msgs::Image& img) const;
169 |
170 | /**
171 | * Returns image's timestamp or current wall time if driver call fails.
172 | */
173 | ros::Time getImageTimestamp();
174 |
175 | /**
176 | * Returns image's timestamp based on device's internal clock or current wall time if driver call fails.
177 | */
178 | ros::Time getImageTickTimestamp();
179 |
180 | virtual void handleTimeout();
181 |
182 | std::thread frame_grab_thread_;
183 | bool frame_grab_alive_;
184 |
185 | ReconfigureServer* ros_cfg_;
186 | boost::recursive_mutex ros_cfg_mutex_;
187 | bool cfg_sync_requested_;
188 |
189 | image_transport::CameraPublisher ros_cam_pub_;
190 | sensor_msgs::Image ros_image_;
191 | sensor_msgs::CameraInfo ros_cam_info_;
192 | unsigned int ros_frame_count_;
193 | ros::Publisher timeout_pub_;
194 | unsigned long long int timeout_count_;
195 |
196 | ros::ServiceServer set_cam_info_srv_;
197 |
198 | std::string frame_name_;
199 | std::string cam_topic_;
200 | std::string timeout_topic_;
201 | std::string cam_intr_filename_;
202 | std::string cam_params_filename_; // should be valid UEye INI file
203 | ueye_cam::UEyeCamConfig cam_params_;
204 |
205 | ros::Time init_ros_time_; // for processing frames
206 | uint64_t init_clock_tick_;
207 |
208 | ros::Time init_publish_time_; // for throttling frames from being published (see cfg.output_rate)
209 | uint64_t prev_output_frame_idx_; // see init_publish_time_
210 | boost::mutex output_rate_mutex_;
211 | };
212 |
213 |
214 | } // namespace ueye_cam
215 |
216 |
217 | #endif /* UEYE_CAM_NODELET_HPP_ */
218 |
--------------------------------------------------------------------------------
/launch/master_slaves_rgb8.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
157 |
158 |
159 |
160 |
161 |
162 |
--------------------------------------------------------------------------------
/include/ueye_cam/ueye_cam_driver.hpp:
--------------------------------------------------------------------------------
1 | /*******************************************************************************
2 | * DO NOT MODIFY - AUTO-GENERATED
3 | *
4 | *
5 | * DISCLAMER:
6 | *
7 | * This project was created within an academic research setting, and thus should
8 | * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 | * code, so please adjust expectations accordingly. With that said, we are
10 | * intrinsically motivated to ensure its correctness (and often its performance).
11 | * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 | * to file bugs, suggestions, pull requests; we will do our best to address them
13 | * in a timely manner.
14 | *
15 | *
16 | * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 | *
18 | * Copyright (c) 2013-2016, Anqi Xu and contributors
19 | * All rights reserved.
20 | *
21 | * Redistribution and use in source and binary forms, with or without
22 | * modification, are permitted provided that the following conditions
23 | * are met:
24 | *
25 | * * Redistributions of source code must retain the above copyright
26 | * notice, this list of conditions and the following disclaimer.
27 | * * Redistributions in binary form must reproduce the above
28 | * copyright notice, this list of conditions and the following
29 | * disclaimer in the documentation and/or other materials provided
30 | * with the distribution.
31 | * * Neither the name of the School of Computer Science, McGill University,
32 | * nor the names of its contributors may be used to endorse or promote
33 | * products derived from this software without specific prior written
34 | * permission.
35 | *
36 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 | *******************************************************************************/
47 |
48 | #ifndef UEYE_CAM_DRIVER_HPP_
49 | #define UEYE_CAM_DRIVER_HPP_
50 |
51 |
52 | #include
53 | #include
54 | #include
55 | #include
56 | #include "logging_macros.hpp"
57 |
58 |
59 | namespace ueye_cam {
60 |
61 |
62 | #define CAP(val, min, max) \
63 | if (val < min) { \
64 | val = min; \
65 | } else if (val > max) { \
66 | val = max; \
67 | }
68 |
69 | #define IS_SUBSAMPLING_2X (IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL)
70 | #define IS_SUBSAMPLING_4X (IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL)
71 | #define IS_SUBSAMPLING_8X (IS_SUBSAMPLING_8X_VERTICAL | IS_SUBSAMPLING_8X_HORIZONTAL)
72 | #define IS_SUBSAMPLING_16X (IS_SUBSAMPLING_16X_VERTICAL | IS_SUBSAMPLING_16X_HORIZONTAL)
73 |
74 | #define IS_BINNING_2X (IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL)
75 | #define IS_BINNING_4X (IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL)
76 | #define IS_BINNING_8X (IS_BINNING_8X_VERTICAL | IS_BINNING_8X_HORIZONTAL)
77 | #define IS_BINNING_16X (IS_BINNING_16X_VERTICAL | IS_BINNING_16X_HORIZONTAL)
78 |
79 |
80 | /**
81 | * Thin wrapper for UEye camera API from IDS Imaging Development Systems GMBH.
82 | */
83 | class UEyeCamDriver {
84 | public:
85 | constexpr static int ANY_CAMERA = 0;
86 |
87 |
88 | /**
89 | * Initializes member variables.
90 | */
91 | UEyeCamDriver(int cam_ID = ANY_CAMERA, std::string cam_name = "camera");
92 |
93 | /**
94 | * Terminates UEye camera interface.
95 | */
96 | virtual ~UEyeCamDriver();
97 |
98 | /**
99 | * Initializes and loads the UEye camera handle.
100 | *
101 | * \param new_cam_ID If set to -1, then uses existing camera ID.
102 | *
103 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
104 | */
105 | virtual INT connectCam(int new_cam_ID = -1);
106 |
107 | /**
108 | * Terminates and releases the UEye camera handle.
109 | *
110 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
111 | */
112 | virtual INT disconnectCam();
113 |
114 | /**
115 | * Loads UEye camera parameter configuration INI file into current camera's settings.
116 | *
117 | * \param filename Relative or absolute path to UEye camera configuration file.
118 | * \param ignore_load_failure Return IS_SUCCESS even if failed to load INI file.
119 | *
120 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
121 | */
122 | INT loadCamConfig(std::string filename, bool ignore_load_failure = true);
123 |
124 | /**
125 | * Updates current camera handle's color mode and re-initializes
126 | * internal frame buffer. This function will stop live capture
127 | * automatically if necessary.
128 | *
129 | * \param mode Color mode string. Valid values: see UEyeCamDriver::COLOR_DICTIONARY
130 | * Certain values may not be available for a given camera model.
131 | * \param reallocate_buffer Whether to auto-reallocate buffer or not after
132 | * changing parameter. If set to false, remember to reallocate_buffer
133 | * via another function or via reallocateCamBuffer() manually!
134 | *
135 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
136 | */
137 | INT setColorMode(std::string& mode, bool reallocate_buffer = true);
138 |
139 | /**
140 | * Updates current camera handle's sensor resolution and area of interest.
141 | * This function will stop live capture automatically if necessary.
142 | *
143 | * \param image_width Desired width for area of interest / image. Will be
144 | * automatically bounded by valid range for current camera.
145 | * \param image_height Desired height for area of interest / image. Will be
146 | * automatically bounded by valid range for current camera.
147 | * \param image_left Desired left pixel offset for area of interest / image.
148 | * Set to -1 to auto-center.
149 | * \param image_top Desired top pixel offset for area of interest / image.
150 | * Set to -1 to auto-center.
151 | * \param reallocate_buffer Whether to auto-reallocate buffer or not after
152 | * changing parameter. If set to false, remember to reallocate_buffer
153 | * via another function or via reallocateCamBuffer() manually!
154 | *
155 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
156 | */
157 | INT setResolution(INT& image_width, INT& image_height, INT& image_left,
158 | INT& image_top, bool reallocate_buffer = true);
159 |
160 | /**
161 | * Updates current camera handle's subsampling rate.
162 | *
163 | * \param rate Desired subsampling rate.
164 | * \param reallocate_buffer Whether to auto-reallocate buffer or not after
165 | * changing parameter. If set to false, remember to reallocate_buffer
166 | * via another function or via reallocateCamBuffer() manually!
167 | *
168 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
169 | */
170 | INT setSubsampling(int& rate, bool reallocate_buffer = true);
171 |
172 | /**
173 | * Updates current camera handle's binning rate.
174 | *
175 | * \param rate Desired binning rate.
176 | * \param reallocate_buffer Whether to auto-reallocate buffer or not after
177 | * changing parameter. If set to false, remember to reallocate_buffer
178 | * via another function or via reallocateCamBuffer() manually!
179 | *
180 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
181 | */
182 | INT setBinning(int& rate, bool reallocate_buffer = true);
183 |
184 | /**
185 | * Updates current camera handle's internal image scaling rate.
186 | *
187 | * \param rate Desired internal image scaling rate.
188 | * \param reallocate_buffer Whether to auto-reallocate buffer or not after
189 | * changing parameter. If set to false, remember to reallocate_buffer
190 | * via another function or via reallocateCamBuffer() manually!
191 | *
192 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
193 | */
194 | INT setSensorScaling(double& rate, bool reallocate_buffer = true);
195 |
196 | /**
197 | * Updates current camera handle's gain either to auto mode, or
198 | * to specified manual parameters.
199 | *
200 | * Auto gain mode is disabled if auto frame rate mode is enabled.
201 | *
202 | * \param auto_gain Updates camera's hardware auto gain / auto gain mode.
203 | * Will be deactivated if camera does not support mode.
204 | * \param master_gain_prc Manual master gain percentage.
205 | * \param red_gain_prc Manual red channel gain percentage.
206 | * \param green_gain_prc Manual green channel gain percentage.
207 | * \param blue_gain_prc Manual blue channel gain percentage.
208 | * \param gain_boost Sets the gain boost. This parameter is independent of
209 | * auto/manual gain mode.
210 | *
211 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
212 | */
213 | INT setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
214 | INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost);
215 |
216 | /**
217 | * Updates current camera handle's software gamma to specified parameter.
218 | *
219 | * According to ids this is only possible when the color mode is debayered by the ids driver
220 | *
221 | * \param software_gamma gamma value in percentage
222 | *
223 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
224 | */
225 | INT setSoftwareGamma(INT& software_gamma);
226 |
227 | /**
228 | * Updates current camera handle's exposure / shutter either to auto mode, or
229 | * to specified manual parameters.
230 | *
231 | * \param auto_exposure Updates camera's hardware auto shutter / auto shutter mode.
232 | * Will be deactivated if camera does not support mode.
233 | * \param auto_exposure_reference sets the reference value for the auto_exposure controller.
234 | * \param exposure_ms Manual exposure setting, in ms. Valid value range depends on
235 | * current camera pixel clock rate.
236 | *
237 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
238 | */
239 | INT setExposure(bool& auto_exposure, double& auto_exposure_reference, double& exposure_ms);
240 |
241 | /**
242 | * Enables or disables the current camera handle's auto white balance mode, and
243 | * configures auto white balance channel offset parameters.
244 | *
245 | * \param auto_white_balance Updates camera's hardware auto white balance /
246 | * auto white balance mode. Will be deactivated if camera does not support mode.
247 | * \param red_offset Red channel offset in auto white balance mode. Range: [-50, 50]
248 | * \param blue_offset Blue channel offset in auto white balance mode. Range: [-50, 50]
249 | *
250 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
251 | */
252 | INT setWhiteBalance(bool& auto_white_balance, INT& red_offset, INT& blue_offset);
253 |
254 | /**
255 | * Updates current camera handle's frame rate either to auto mode, or
256 | * to specified manual parameters.
257 | *
258 | * Enabling auto frame rate mode requires that auto shutter mode be enabled.
259 | * Enabling auto frame rate mode will disable auto gain mode.
260 | *
261 | * \param auto_frame_rate Updates camera's hardware auto frame rate / auto frame
262 | * mode mode. Will be deactivated if camera does not support mode.
263 | * \param frame_rate_hz Desired frame rate, in Hz / frames per second. Valid value
264 | * range depends on current camera pixel clock rate.
265 | *
266 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
267 | */
268 | INT setFrameRate(bool& auto_frame_rate, double& frame_rate_hz);
269 |
270 | /**
271 | * Updates current camera handle's pixel clock rate.
272 | *
273 | * \param clock_rate_mhz Desired pixel clock rate, in MHz. Valid value range
274 | * depends on camera model.
275 | *
276 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
277 | */
278 | INT setPixelClockRate(INT& clock_rate_mhz);
279 |
280 | /**
281 | * Updates the flash signal's delay (from start of exposure) and duration.
282 | * The flash signal is routed to the digital output pin by default in
283 | * setFreeRunMode(), and can act as a triggering signal for driving other
284 | * cameras configured as setExtTriggerMode().
285 | *
286 | * Note that setting flash parameters by itself may not have an effect, if
287 | * the flash output is not enabled via is_IO().
288 | */
289 | INT setFlashParams(INT& delay_us, UINT& duration_us);
290 |
291 | /**
292 | * Sets the mode for the GPIO pins.
293 | * \param GPIO pin to be set {GPIO1: 1, GPIO2: 2}.
294 | * \param mode for GPIO pin {0: input, 1: output low, 2: output high, 3: flash, 4: pwm output, 5: trigger input}.
295 | * \param pwm_freq frequency if pwm output is selected as the mode
296 | * \param pwm_duty_cycle duty cycle if pwm output is selected as the mode
297 | *
298 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
299 | */
300 | INT setGpioMode(const INT& gpio, INT& mode, double& pwm_freq, double& pwm_duty_cycle);
301 |
302 | /**
303 | * Sets current camera to start capturing frames to internal buffer repeatedly.
304 | * This function also pre-configures the camera to operate in free-run,
305 | * non-triggered mode, and further attempts to enable the digital output pin
306 | * to raise to HI during exposure (a.k.a. flash signal, which is useful for
307 | * triggering other cameras).
308 | *
309 | * Note that this function only sets the mode. Frames are grabbed by
310 | * calling processNextFrame().
311 | *
312 | * IMPLEMENTATION DETAIL: the flash output signal is set to active-high, so
313 | * that multiple flash outputs from different cameras can be connected
314 | * to an OR combination gate to allow any camera to emit the flash trigger.
315 | * In contrast, in active-low mode, any de-activated camera will output LOW,
316 | * which would dominate over the triggering signals at the NAND combination
317 | * gate.
318 | *
319 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
320 | */
321 | INT setFreeRunMode();
322 |
323 | /**
324 | * Sets current camera to external trigger mode, where a HI to LO falling-edge
325 | * signal on the digital input pin of the camera will trigger the camera to
326 | * capture a frame. This function also resets the digital output pin to
327 | * always be LO.
328 | *
329 | * Note that this function only sets the mode. Frames are then grabbed by
330 | * calling processNextFrame().
331 | *
332 | * IMPLEMENTATION DETAIL: currently this function supports falling-edge
333 | * trigger only, since our camera (UI-1246LE) only supports this mode
334 | *
335 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
336 | */
337 | INT setExtTriggerMode();
338 |
339 | /**
340 | * Disables either free-run or external trigger mode, and sets the current
341 | * camera to standby mode.
342 | *
343 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
344 | */
345 | INT setStandbyMode();
346 |
347 | /**
348 | * Mirrors the camera image upside down
349 | * \param flip_horizontal Wheter to flip the image upside down or not.
350 | *
351 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
352 | */
353 | INT setMirrorUpsideDown(bool flip_horizontal);
354 |
355 | /**
356 | * Mirrors the camera image left to right
357 | * \param flip_vertical Wheter to flip the image left to right or not.
358 | *
359 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
360 | */
361 | INT setMirrorLeftRight(bool flip_vertical);
362 |
363 | /**
364 | * Waits for next frame to be available, then returns pointer to frame if successful.
365 | * This function should only be called when the camera is in live capture mode.
366 | * Since this function will block until the next frame is available, it can be used
367 | * in a loop, without additional delays, to repeatedly query frames from the camera
368 | * at the maximum rate possible given current camera settings.
369 | *
370 | * \param timeout_ms Timeout duration while waiting for next frame event.
371 | *
372 | * \return Pointer to raw image buffer if successful, NULL otherwise.
373 | * WARNING: image buffer contents may change during capture, or may become
374 | * invalid after calling other functions!
375 | */
376 | const char* processNextFrame(UINT timeout_ms);
377 |
378 | inline bool isConnected() { return (cam_handle_ != HIDS(0)); }
379 |
380 | inline bool freeRunModeActive() {
381 | return ((cam_handle_ != HIDS(0)) &&
382 | (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_OFF) &&
383 | (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
384 | }
385 |
386 | inline bool extTriggerModeActive() {
387 | return ((cam_handle_ != HIDS(0)) &&
388 | (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_HI_LO) &&
389 | (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
390 | }
391 |
392 | inline bool isCapturing() {
393 | return ((cam_handle_ != HIDS(0)) &&
394 | (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
395 | }
396 |
397 | /**
398 | * Stringifies UEye API error flag.
399 | */
400 | const static char* err2str(INT error);
401 |
402 | /**
403 | * Stringifies UEye color mode flag.
404 | */
405 | const static char* colormode2str(INT mode);
406 |
407 | /**
408 | * translates UEye color mode flag to target ROS image encoding.
409 | */
410 | const static std::string colormode2img_enc(INT mode);
411 |
412 | /**
413 | * bits per pixel attribute of UEye color mode flag
414 | */
415 | static INT colormode2bpp(INT mode);
416 |
417 | /**
418 | * check if this driver supports the chosen UEye color mode
419 | */
420 | static bool isSupportedColorMode(INT mode);
421 |
422 | /**
423 | * translates ROS name to UEye color mode flag or the other way round.
424 | */
425 | static INT name2colormode(const std::string& name);
426 | const static std::string colormode2name(INT mode);
427 |
428 | /**
429 | * returns the proper transfer function to translate and copy the camera format
430 | * pixel buffer either into an 8 or 16 bit unsigned int per channel format.
431 | */
432 | const static std::function getUnpackCopyFunc(INT color_mode);
433 | static void* unpackRGB10(void* dst, void* src, size_t num);
434 | static void* unpack10u(void* dst, void* src, size_t num);
435 | static void* unpack12u(void* dst, void* src, size_t num);
436 |
437 | /**
438 | * Sets a timestamp indicating the moment of the image capture
439 | */
440 | bool getTimestamp(UEYETIME *timestamp);
441 |
442 | /**
443 | * Sets a clock tick indicating the moment of the image capture
444 | */
445 | bool getClockTick(uint64_t *tick);
446 |
447 |
448 | protected:
449 | /**
450 | * Queries current camera handle's configuration (color mode,
451 | * (area of interest / resolution, sensor scaling rate, subsampling rate,
452 | * binning rate) to synchronize with this class's internal member values,
453 | * then force-updates to default settings if current ones are not supported
454 | * by this driver wrapper (ueye_cam), and finally force (re-)allocates
455 | * internal frame buffer.
456 | *
457 | * This function is intended to be called internally, after opening a camera handle
458 | * (in connectCam()) or after loading a UEye camera configuration file
459 | * (in loadCamConfig()), where the camera may be already operating with a
460 | * non-supported setting.
461 | *
462 | * \param dft_mode_str: default color mode to switch to, if current color mode
463 | * is not supported by this driver wrapper. Valid values: {"rgb8", "bgr8", "mono8", "bayer_rggb8"}
464 | *
465 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
466 | */
467 | virtual INT syncCamConfig(std::string dft_mode_str = "mono8");
468 |
469 |
470 | virtual void handleTimeout() {}
471 |
472 |
473 | /**
474 | * (Re-)allocates internal frame buffer after querying current
475 | * area of interest (resolution), and configures IDS driver to use this buffer.
476 | *
477 | * \return IS_SUCCESS if successful, error flag otherwise (see err2str).
478 | */
479 | INT reallocateCamBuffer();
480 |
481 | const static std::map COLOR_DICTIONARY;
482 |
483 | HIDS cam_handle_;
484 | SENSORINFO cam_sensor_info_;
485 | char* cam_buffer_;
486 | int cam_buffer_id_;
487 | INT cam_buffer_pitch_;
488 | unsigned int cam_buffer_size_;
489 | std::string cam_name_;
490 | int cam_id_;
491 | IS_RECT cam_aoi_;
492 | unsigned int cam_subsampling_rate_;
493 | unsigned int cam_binning_rate_;
494 | double cam_sensor_scaling_rate_;
495 | INT color_mode_;
496 | INT bits_per_pixel_;
497 | };
498 |
499 |
500 | } // namespace ueye_cam
501 |
502 |
503 | #endif /* UEYE_CAM_DRIVER_HPP_ */
504 |
--------------------------------------------------------------------------------
/src/ueye_cam_nodelet.cpp:
--------------------------------------------------------------------------------
1 | /*******************************************************************************
2 | * DO NOT MODIFY - AUTO-GENERATED
3 | *
4 | *
5 | * DISCLAMER:
6 | *
7 | * This project was created within an academic research setting, and thus should
8 | * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 | * code, so please adjust expectations accordingly. With that said, we are
10 | * intrinsically motivated to ensure its correctness (and often its performance).
11 | * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 | * to file bugs, suggestions, pull requests; we will do our best to address them
13 | * in a timely manner.
14 | *
15 | *
16 | * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 | *
18 | * Copyright (c) 2013-2016, Anqi Xu and contributors
19 | * All rights reserved.
20 | *
21 | * Redistribution and use in source and binary forms, with or without
22 | * modification, are permitted provided that the following conditions
23 | * are met:
24 | *
25 | * * Redistributions of source code must retain the above copyright
26 | * notice, this list of conditions and the following disclaimer.
27 | * * Redistributions in binary form must reproduce the above
28 | * copyright notice, this list of conditions and the following
29 | * disclaimer in the documentation and/or other materials provided
30 | * with the distribution.
31 | * * Neither the name of the School of Computer Science, McGill University,
32 | * nor the names of its contributors may be used to endorse or promote
33 | * products derived from this software without specific prior written
34 | * permission.
35 | *
36 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 | *******************************************************************************/
47 |
48 | #include "ueye_cam/ueye_cam_nodelet.hpp"
49 | #include // needed for getenv()
50 | #include
51 | #include
52 | #include
53 | #include
54 | #include
55 |
56 |
57 | //#define DEBUG_PRINTOUT_FRAME_GRAB_RATES
58 |
59 |
60 | using namespace std;
61 | using namespace sensor_msgs::image_encodings;
62 |
63 |
64 | namespace ueye_cam {
65 |
66 |
67 | const std::string UEyeCamNodelet::DEFAULT_FRAME_NAME = "camera";
68 | const std::string UEyeCamNodelet::DEFAULT_CAMERA_NAME = "camera";
69 | const std::string UEyeCamNodelet::DEFAULT_CAMERA_TOPIC = "image_raw";
70 | const std::string UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC = "timeout_count";
71 | const std::string UEyeCamNodelet::DEFAULT_COLOR_MODE = "";
72 | constexpr int UEyeCamDriver::ANY_CAMERA; // Needed since CMakeLists.txt creates 2 separate libraries: one for non-ROS parent class, and one for ROS child class
73 |
74 |
75 | // Note that these default settings will be overwritten by queryCamParams() during connectCam()
76 | UEyeCamNodelet::UEyeCamNodelet():
77 | nodelet::Nodelet(),
78 | UEyeCamDriver(ANY_CAMERA, DEFAULT_CAMERA_NAME),
79 | frame_grab_alive_(false),
80 | ros_cfg_(nullptr),
81 | cfg_sync_requested_(false),
82 | ros_frame_count_(0),
83 | timeout_count_(0),
84 | cam_topic_(DEFAULT_CAMERA_TOPIC),
85 | timeout_topic_(DEFAULT_TIMEOUT_TOPIC),
86 | cam_intr_filename_(""),
87 | cam_params_filename_(""),
88 | init_clock_tick_(0),
89 | init_publish_time_(0),
90 | prev_output_frame_idx_(0) {
91 | ros_image_.is_bigendian = (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__); // TODO: what about MS Windows?
92 | cam_params_.image_width = DEFAULT_IMAGE_WIDTH;
93 | cam_params_.image_height = DEFAULT_IMAGE_HEIGHT;
94 | cam_params_.image_left = -1;
95 | cam_params_.image_top = -1;
96 | cam_params_.color_mode = DEFAULT_COLOR_MODE;
97 | cam_params_.subsampling = static_cast(cam_subsampling_rate_);
98 | cam_params_.binning = static_cast(cam_binning_rate_);
99 | cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
100 | cam_params_.auto_gain = false;
101 | cam_params_.master_gain = 0;
102 | cam_params_.red_gain = 0;
103 | cam_params_.green_gain = 0;
104 | cam_params_.blue_gain = 0;
105 | cam_params_.gain_boost = 0;
106 | cam_params_.software_gamma=100;
107 | cam_params_.auto_exposure = false;
108 | cam_params_.auto_exposure_reference = 128;
109 | cam_params_.exposure = DEFAULT_EXPOSURE;
110 | cam_params_.auto_white_balance = false;
111 | cam_params_.white_balance_red_offset = 0;
112 | cam_params_.white_balance_blue_offset = 0;
113 | cam_params_.auto_frame_rate = false;
114 | cam_params_.frame_rate = DEFAULT_FRAME_RATE;
115 | cam_params_.output_rate = 0; // disable by default
116 | cam_params_.pixel_clock = DEFAULT_PIXEL_CLOCK;
117 | cam_params_.ext_trigger_mode = false;
118 | cam_params_.flash_delay = 0;
119 | cam_params_.flash_duration = DEFAULT_FLASH_DURATION;
120 | cam_params_.gpio1 = 0;
121 | cam_params_.gpio2 = 0;
122 | cam_params_.pwm_freq = 1;
123 | cam_params_.pwm_duty_cycle=0.5;
124 | cam_params_.flip_upd = false;
125 | cam_params_.flip_lr = false;
126 | }
127 |
128 |
129 | UEyeCamNodelet::~UEyeCamNodelet() {
130 | disconnectCam();
131 |
132 | // NOTE: sometimes deleting dynamic reconfigure object will lock up
133 | // (suspect the scoped lock is not releasing the recursive mutex)
134 | //
135 | //if (ros_cfg_ != NULL) {
136 | // delete ros_cfg_;
137 | // ros_cfg_ = NULL;
138 | //}
139 | }
140 |
141 |
142 | void UEyeCamNodelet::onInit() {
143 | ros::NodeHandle& nh = getNodeHandle();
144 | ros::NodeHandle& local_nh = getPrivateNodeHandle();
145 | image_transport::ImageTransport it(nh);
146 |
147 | // Load camera-agnostic ROS parameters
148 | local_nh.param("camera_name", cam_name_, DEFAULT_CAMERA_NAME);
149 | local_nh.param("frame_name", frame_name_, DEFAULT_FRAME_NAME);
150 | local_nh.param("camera_topic", cam_topic_, DEFAULT_CAMERA_TOPIC);
151 | local_nh.param("timeout_topic", timeout_topic_, DEFAULT_TIMEOUT_TOPIC);
152 | local_nh.param("camera_intrinsics_file", cam_intr_filename_, "");
153 | local_nh.param("camera_id", cam_id_, ANY_CAMERA);
154 | local_nh.param("camera_parameters_file", cam_params_filename_, "");
155 | if (cam_id_ < 0) {
156 | WARN_STREAM("Invalid camera ID specified: " << cam_id_ <<
157 | "; setting to ANY_CAMERA");
158 | cam_id_ = ANY_CAMERA;
159 | }
160 |
161 | loadIntrinsicsFile();
162 |
163 | // Setup publishers, subscribers, and services
164 | ros_cam_pub_ = it.advertiseCamera(cam_name_ + "/" + cam_topic_, 1);
165 | set_cam_info_srv_ = nh.advertiseService(cam_name_ + "/set_camera_info",
166 | &UEyeCamNodelet::setCamInfo, this);
167 | timeout_pub_ = nh.advertise(cam_name_ + "/" + timeout_topic_, 1, true);
168 | std_msgs::UInt64 timeout_msg; timeout_msg.data = 0; timeout_pub_.publish(timeout_msg);
169 |
170 | // Initiate camera and start capture
171 | if (connectCam() != IS_SUCCESS) {
172 | ERROR_STREAM("Failed to initialize [" << cam_name_ << "]");
173 | return;
174 | }
175 |
176 | // Setup dynamic reconfigure server
177 | ros_cfg_ = new ReconfigureServer(ros_cfg_mutex_, local_nh);
178 | ReconfigureServer::CallbackType f;
179 | f = bind(&UEyeCamNodelet::configCallback, this, _1, _2);
180 | ros_cfg_->setCallback(f); // this will call configCallback, which will configure the camera's parameters
181 | startFrameGrabber();
182 | INFO_STREAM(
183 | "UEye camera [" << cam_name_ << "] initialized on topic " << ros_cam_pub_.getTopic() << endl <<
184 | "Width:\t\t\t" << cam_params_.image_width << endl <<
185 | "Height:\t\t\t" << cam_params_.image_height << endl <<
186 | "Left Pos.:\t\t" << cam_params_.image_left << endl <<
187 | "Top Pos.:\t\t" << cam_params_.image_top << endl <<
188 | "Color Mode:\t\t" << cam_params_.color_mode << endl <<
189 | "Subsampling:\t\t" << cam_params_.subsampling << endl <<
190 | "Binning:\t\t" << cam_params_.binning << endl <<
191 | "Sensor Scaling:\t\t" << cam_params_.sensor_scaling << endl <<
192 | "Auto Gain:\t\t" << cam_params_.auto_gain << endl <<
193 | "Master Gain:\t\t" << cam_params_.master_gain << endl <<
194 | "Red Gain:\t\t" << cam_params_.red_gain << endl <<
195 | "Green Gain:\t\t" << cam_params_.green_gain << endl <<
196 | "Blue Gain:\t\t" << cam_params_.blue_gain << endl <<
197 | "Gain Boost:\t\t" << cam_params_.gain_boost << endl <<
198 | "Software Gamma:\t\t" << cam_params_.software_gamma << endl <<
199 | "Auto Exposure:\t\t" << cam_params_.auto_exposure << endl <<
200 | "Auto Exposure Reference:\t" << cam_params_.auto_exposure_reference << endl <<
201 | "Exposure (ms):\t\t" << cam_params_.exposure << endl <<
202 | "Auto White Balance:\t" << cam_params_.auto_white_balance << endl <<
203 | "WB Red Offset:\t\t" << cam_params_.white_balance_red_offset << endl <<
204 | "WB Blue Offset:\t\t" << cam_params_.white_balance_blue_offset << endl <<
205 | "Flash Delay (us):\t" << cam_params_.flash_delay << endl <<
206 | "Flash Duration (us):\t" << cam_params_.flash_duration << endl <<
207 | "Ext Trigger Mode:\t" << cam_params_.ext_trigger_mode << endl <<
208 | "Auto Frame Rate:\t" << cam_params_.auto_frame_rate << endl <<
209 | "Frame Rate (Hz):\t" << cam_params_.frame_rate << endl <<
210 | "Output Rate (Hz):\t" << cam_params_.output_rate << endl <<
211 | "Pixel Clock (MHz):\t" << cam_params_.pixel_clock << endl <<
212 | "GPIO1 Mode:\t" << cam_params_.gpio1 << endl <<
213 | "GPIO2 Mode:\t" << cam_params_.gpio2 << endl <<
214 | "Mirror Image Upside Down:\t" << cam_params_.flip_upd << endl <<
215 | "Mirror Image Left Right:\t" << cam_params_.flip_lr << endl
216 | );
217 | }
218 |
219 |
220 | INT UEyeCamNodelet::parseROSParams(ros::NodeHandle& local_nh) {
221 | bool hasNewParams = false;
222 | ueye_cam::UEyeCamConfig prevCamParams = cam_params_;
223 | INT is_err = IS_SUCCESS;
224 |
225 | if (local_nh.hasParam("image_width")) {
226 | local_nh.getParam("image_width", cam_params_.image_width);
227 | if (cam_params_.image_width != prevCamParams.image_width) {
228 | if (cam_params_.image_width <= 0) {
229 | WARN_STREAM("Invalid requested image width for [" << cam_name_ <<
230 | "]: " << cam_params_.image_width <<
231 | "; using current width: " << prevCamParams.image_width);
232 | cam_params_.image_width = prevCamParams.image_width;
233 | } else {
234 | hasNewParams = true;
235 | }
236 | }
237 | } else {
238 | local_nh.setParam("image_width", cam_params_.image_width);
239 | }
240 | if (local_nh.hasParam("image_height")) {
241 | local_nh.getParam("image_height", cam_params_.image_height);
242 | if (cam_params_.image_height != prevCamParams.image_height) {
243 | if (cam_params_.image_height <= 0) {
244 | WARN_STREAM("Invalid requested image height for [" << cam_name_ <<
245 | "]: " << cam_params_.image_height <<
246 | "; using current height: " << prevCamParams.image_height);
247 | cam_params_.image_height = prevCamParams.image_height;
248 | } else {
249 | hasNewParams = true;
250 | }
251 | }
252 | } else {
253 | local_nh.setParam("image_height", cam_params_.image_height);
254 | }
255 | if (local_nh.hasParam("image_top")) {
256 | local_nh.getParam("image_top", cam_params_.image_top);
257 | if (cam_params_.image_top != prevCamParams.image_top) {
258 | hasNewParams = true;
259 | }
260 | } else {
261 | local_nh.setParam("image_top", cam_params_.image_top);
262 | }
263 | if (local_nh.hasParam("image_left")) {
264 | local_nh.getParam("image_left", cam_params_.image_left);
265 | if (cam_params_.image_left != prevCamParams.image_left) {
266 | hasNewParams = true;
267 | }
268 | } else {
269 | local_nh.setParam("image_left", cam_params_.image_left);
270 | }
271 | if (local_nh.hasParam("color_mode")) {
272 | local_nh.getParam("color_mode", cam_params_.color_mode);
273 | if (cam_params_.color_mode != prevCamParams.color_mode) {
274 | if (cam_params_.color_mode.length() > 0) {
275 | transform(cam_params_.color_mode.begin(),
276 | cam_params_.color_mode.end(),
277 | cam_params_.color_mode.begin(),
278 | ::tolower);
279 | if (name2colormode(cam_params_.color_mode) != 0) {
280 | hasNewParams = true;
281 | } else {
282 | WARN_STREAM("Invalid requested color mode for [" << cam_name_
283 | << "]: " << cam_params_.color_mode
284 | << "; using current mode: " << prevCamParams.color_mode);
285 | cam_params_.color_mode = prevCamParams.color_mode;
286 | }
287 | } else { // Empty requested color mode string
288 | cam_params_.color_mode = prevCamParams.color_mode;
289 | }
290 | }
291 | } else {
292 | local_nh.setParam("color_mode", cam_params_.color_mode);
293 | }
294 | if (local_nh.hasParam("subsampling")) {
295 | local_nh.getParam("subsampling", cam_params_.subsampling);
296 | if (cam_params_.subsampling != prevCamParams.subsampling) {
297 | if (!(cam_params_.subsampling == 1 ||
298 | cam_params_.subsampling == 2 ||
299 | cam_params_.subsampling == 4 ||
300 | cam_params_.subsampling == 8 ||
301 | cam_params_.subsampling == 16)) {
302 | WARN_STREAM("Invalid or unsupported requested subsampling rate for [" <<
303 | cam_name_ << "]: " << cam_params_.subsampling <<
304 | "; using current rate: " << prevCamParams.subsampling);
305 | cam_params_.subsampling = prevCamParams.subsampling;
306 | } else {
307 | hasNewParams = true;
308 | }
309 | }
310 | } else {
311 | local_nh.setParam("subsampling", cam_params_.subsampling);
312 | }
313 | if (local_nh.hasParam("auto_gain")) {
314 | local_nh.getParam("auto_gain", cam_params_.auto_gain);
315 | if (cam_params_.auto_gain != prevCamParams.auto_gain) {
316 | hasNewParams = true;
317 | }
318 | } else {
319 | local_nh.setParam("auto_gain", cam_params_.auto_gain);
320 | }
321 | if (local_nh.hasParam("master_gain")) {
322 | local_nh.getParam("master_gain", cam_params_.master_gain);
323 | if (cam_params_.master_gain != prevCamParams.master_gain) {
324 | if (cam_params_.master_gain < 0 || cam_params_.master_gain > 100) {
325 | WARN_STREAM("Invalid master gain for [" << cam_name_ << "]: " <<
326 | cam_params_.master_gain << "; using current master gain: " << prevCamParams.master_gain);
327 | cam_params_.master_gain = prevCamParams.master_gain;
328 | } else {
329 | hasNewParams = true;
330 | }
331 | }
332 | } else {
333 | local_nh.setParam("master_gain", cam_params_.master_gain);
334 | }
335 | if (local_nh.hasParam("red_gain")) {
336 | local_nh.getParam("red_gain", cam_params_.red_gain);
337 | if (cam_params_.red_gain != prevCamParams.red_gain) {
338 | if (cam_params_.red_gain < 0 || cam_params_.red_gain > 100) {
339 | WARN_STREAM("Invalid red gain for [" << cam_name_ << "]: " <<
340 | cam_params_.red_gain << "; using current red gain: " << prevCamParams.red_gain);
341 | cam_params_.red_gain = prevCamParams.red_gain;
342 | } else {
343 | hasNewParams = true;
344 | }
345 | }
346 | } else {
347 | local_nh.setParam("red_gain", cam_params_.red_gain);
348 | }
349 | if (local_nh.hasParam("green_gain")) {
350 | local_nh.getParam("green_gain", cam_params_.green_gain);
351 | if (cam_params_.green_gain != prevCamParams.green_gain) {
352 | if (cam_params_.green_gain < 0 || cam_params_.green_gain > 100) {
353 | WARN_STREAM("Invalid green gain for [" << cam_name_ << "]: " <<
354 | cam_params_.green_gain << "; using current green gain: " << prevCamParams.green_gain);
355 | cam_params_.green_gain = prevCamParams.green_gain;
356 | } else {
357 | hasNewParams = true;
358 | }
359 | }
360 | } else {
361 | local_nh.setParam("green_gain", cam_params_.green_gain);
362 | }
363 | if (local_nh.hasParam("blue_gain")) {
364 | local_nh.getParam("blue_gain", cam_params_.blue_gain);
365 | if (cam_params_.blue_gain != prevCamParams.blue_gain) {
366 | if (cam_params_.blue_gain < 0 || cam_params_.blue_gain > 100) {
367 | WARN_STREAM("Invalid blue gain for [" << cam_name_ << "]: " <<
368 | cam_params_.blue_gain << "; using current blue gain: " << prevCamParams.blue_gain);
369 | cam_params_.blue_gain = prevCamParams.blue_gain;
370 | } else {
371 | hasNewParams = true;
372 | }
373 | }
374 | } else {
375 | local_nh.setParam("blue_gain", cam_params_.blue_gain);
376 | }
377 | if (local_nh.hasParam("gain_boost")) {
378 | local_nh.getParam("gain_boost", cam_params_.gain_boost);
379 | if (cam_params_.gain_boost != prevCamParams.gain_boost) {
380 | hasNewParams = true;
381 | }
382 | } else {
383 | local_nh.setParam("gain_boost", cam_params_.gain_boost);
384 | }
385 | if (local_nh.hasParam("software_gamma")) {
386 | local_nh.getParam("software_gamma", cam_params_.software_gamma);
387 | if (cam_params_.software_gamma != prevCamParams.software_gamma) {
388 | hasNewParams = true;
389 | }
390 | }
391 | if (local_nh.hasParam("auto_exposure")) {
392 | local_nh.getParam("auto_exposure", cam_params_.auto_exposure);
393 | if (cam_params_.auto_exposure != prevCamParams.auto_exposure) {
394 | hasNewParams = true;
395 | }
396 | } else {
397 | local_nh.setParam("auto_exposure", cam_params_.auto_exposure);
398 | }
399 | if (local_nh.hasParam("auto_exposure_reference")) {
400 | local_nh.getParam("auto_exposure_reference", cam_params_.auto_exposure_reference);
401 | if (cam_params_.auto_exposure_reference != prevCamParams.auto_exposure_reference) {
402 | hasNewParams = true;
403 | }
404 | } else {
405 | local_nh.setParam("auto_exposure_reference", cam_params_.auto_exposure_reference);
406 | }
407 | if (local_nh.hasParam("exposure")) {
408 | local_nh.getParam("exposure", cam_params_.exposure);
409 | if (cam_params_.exposure != prevCamParams.exposure) {
410 | if (cam_params_.exposure < 0.0) {
411 | WARN_STREAM("Invalid requested exposure: " << cam_params_.exposure <<
412 | "; using current exposure: " << prevCamParams.exposure);
413 | cam_params_.exposure = prevCamParams.exposure;
414 | } else {
415 | hasNewParams = true;
416 | }
417 | }
418 | } else {
419 | local_nh.setParam("exposure", cam_params_.exposure);
420 | }
421 | if (local_nh.hasParam("auto_white_balance")) {
422 | local_nh.getParam("auto_white_balance", cam_params_.auto_white_balance);
423 | if (cam_params_.auto_white_balance != prevCamParams.auto_white_balance) {
424 | hasNewParams = true;
425 | }
426 | } else {
427 | local_nh.setParam("auto_white_balance", cam_params_.auto_white_balance);
428 | }
429 | if (local_nh.hasParam("white_balance_red_offset")) {
430 | local_nh.getParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
431 | if (cam_params_.white_balance_red_offset != prevCamParams.white_balance_red_offset) {
432 | if (cam_params_.white_balance_red_offset < -50 || cam_params_.white_balance_red_offset > 50) {
433 | WARN_STREAM("Invalid white balance red offset for [" << cam_name_ << "]: " <<
434 | cam_params_.white_balance_red_offset <<
435 | "; using current white balance red offset: " << prevCamParams.white_balance_red_offset);
436 | cam_params_.white_balance_red_offset = prevCamParams.white_balance_red_offset;
437 | } else {
438 | hasNewParams = true;
439 | }
440 | }
441 | } else {
442 | local_nh.setParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
443 | }
444 | if (local_nh.hasParam("white_balance_blue_offset")) {
445 | local_nh.getParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
446 | if (cam_params_.white_balance_blue_offset != prevCamParams.white_balance_blue_offset) {
447 | if (cam_params_.white_balance_blue_offset < -50 || cam_params_.white_balance_blue_offset > 50) {
448 | WARN_STREAM("Invalid white balance blue offset for [" << cam_name_ << "]: " <<
449 | cam_params_.white_balance_blue_offset <<
450 | "; using current white balance blue offset: " << prevCamParams.white_balance_blue_offset);
451 | cam_params_.white_balance_blue_offset = prevCamParams.white_balance_blue_offset;
452 | } else {
453 | hasNewParams = true;
454 | }
455 | }
456 | } else {
457 | local_nh.setParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
458 | }
459 | if (local_nh.hasParam("ext_trigger_mode")) {
460 | local_nh.getParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
461 | // NOTE: no need to set any parameters, since external trigger / live-run
462 | // modes come into effect during frame grab loop, which is assumed
463 | // to not having been initialized yet
464 | } else {
465 | local_nh.setParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
466 | }
467 | if (local_nh.hasParam("flash_delay")) {
468 | local_nh.getParam("flash_delay", cam_params_.flash_delay);
469 | // NOTE: no need to set any parameters, since flash delay comes into
470 | // effect during frame grab loop, which is assumed to not having been
471 | // initialized yet
472 | } else {
473 | local_nh.setParam("flash_delay", cam_params_.flash_delay);
474 | }
475 | if (local_nh.hasParam("flash_duration")) {
476 | local_nh.getParam("flash_duration", cam_params_.flash_duration);
477 | if (cam_params_.flash_duration < 0) {
478 | WARN_STREAM("Invalid flash duration for [" << cam_name_ << "]: " <<
479 | cam_params_.flash_duration <<
480 | "; using current flash duration: " << prevCamParams.flash_duration);
481 | cam_params_.flash_duration = prevCamParams.flash_duration;
482 | }
483 | // NOTE: no need to set any parameters, since flash duration comes into
484 | // effect during frame grab loop, which is assumed to not having been
485 | // initialized yet
486 | } else {
487 | local_nh.setParam("flash_duration", cam_params_.flash_duration);
488 | }
489 | if (local_nh.hasParam("gpio1")) {
490 | local_nh.getParam("gpio1", cam_params_.gpio1);
491 | if (cam_params_.gpio1 != prevCamParams.gpio1) {hasNewParams = true;}
492 | } else {
493 | local_nh.setParam("gpio1", cam_params_.gpio1);
494 | }
495 | if (local_nh.hasParam("gpio2")) {
496 | local_nh.getParam("gpio2", cam_params_.gpio2);
497 | if (cam_params_.gpio2 != prevCamParams.gpio2) {hasNewParams = true;}
498 | } else {
499 | local_nh.setParam("gpio2", cam_params_.gpio2);
500 | }
501 | if (local_nh.hasParam("pwm_freq")) {
502 | local_nh.getParam("pwm_freq", cam_params_.pwm_freq);
503 | if (cam_params_.pwm_freq != prevCamParams.pwm_freq) {hasNewParams = true;}
504 | } else {
505 | local_nh.setParam("pwm_freq", cam_params_.pwm_freq);
506 | }
507 | if (local_nh.hasParam("pwm_duty_cycle")) {
508 | local_nh.getParam("pwm_duty_cycle", cam_params_.pwm_duty_cycle);
509 | if (cam_params_.pwm_duty_cycle != prevCamParams.pwm_duty_cycle) {hasNewParams = true;}
510 | } else {
511 | local_nh.setParam("pwm_duty_cycle", cam_params_.pwm_duty_cycle);
512 | }
513 |
514 | if (local_nh.hasParam("auto_frame_rate")) {
515 | local_nh.getParam("auto_frame_rate", cam_params_.auto_frame_rate);
516 | if (cam_params_.auto_frame_rate != prevCamParams.auto_frame_rate) {
517 | hasNewParams = true;
518 | }
519 | } else {
520 | local_nh.setParam("auto_frame_rate", cam_params_.auto_frame_rate);
521 | }
522 | if (local_nh.hasParam("frame_rate")) {
523 | local_nh.getParam("frame_rate", cam_params_.frame_rate);
524 | if (cam_params_.frame_rate != prevCamParams.frame_rate) {
525 | if (cam_params_.frame_rate <= 0.0) {
526 | WARN_STREAM("Invalid requested frame rate for [" << cam_name_ << "]: " <<
527 | cam_params_.frame_rate <<
528 | "; using current frame rate: " << prevCamParams.frame_rate);
529 | cam_params_.frame_rate = prevCamParams.frame_rate;
530 | } else {
531 | hasNewParams = true;
532 | }
533 | }
534 | } else {
535 | local_nh.setParam("frame_rate", cam_params_.frame_rate);
536 | }
537 | if (local_nh.hasParam("output_rate")) {
538 | local_nh.getParam("output_rate", cam_params_.output_rate);
539 | if (cam_params_.output_rate < 0.0) {
540 | WARN_STREAM("Invalid requested output rate for [" << cam_name_ << "]: " <<
541 | cam_params_.output_rate <<
542 | "; disable publisher throttling by default");
543 | cam_params_.output_rate = 0;
544 | } else {
545 | cam_params_.output_rate = std::min(cam_params_.frame_rate, cam_params_.output_rate);
546 | // hasNewParams = true; // No need to re-allocate buffer memory or reconfigure camera parameters
547 | }
548 | } else {
549 | local_nh.setParam("output_rate", cam_params_.output_rate);
550 | }
551 | if (local_nh.hasParam("pixel_clock")) {
552 | local_nh.getParam("pixel_clock", cam_params_.pixel_clock);
553 | if (cam_params_.pixel_clock != prevCamParams.pixel_clock) {
554 | if (cam_params_.pixel_clock < 0) {
555 | WARN_STREAM("Invalid requested pixel clock for [" << cam_name_ << "]: " <<
556 | cam_params_.pixel_clock <<
557 | "; using current pixel clock: " << prevCamParams.pixel_clock);
558 | cam_params_.pixel_clock = prevCamParams.pixel_clock;
559 | } else {
560 | hasNewParams = true;
561 | }
562 | }
563 | } else {
564 | local_nh.setParam("pixel_clock", cam_params_.pixel_clock);
565 | }
566 | if (local_nh.hasParam("flip_upd")) {
567 | local_nh.getParam("flip_upd", cam_params_.flip_upd);
568 | if (cam_params_.flip_upd != prevCamParams.flip_upd) {
569 | hasNewParams = true;
570 | }
571 | } else {
572 | local_nh.setParam("flip_upd", cam_params_.flip_upd);
573 | }
574 | if (local_nh.hasParam("flip_lr")) {
575 | local_nh.getParam("flip_lr", cam_params_.flip_lr);
576 | if (cam_params_.flip_lr != prevCamParams.flip_lr) {
577 | hasNewParams = true;
578 | }
579 | } else {
580 | local_nh.setParam("flip_lr", cam_params_.flip_lr);
581 | }
582 |
583 | if (hasNewParams) {
584 | // Configure color mode, resolution, and subsampling rate
585 | // NOTE: this batch of configurations are mandatory, to ensure proper allocation of local frame buffer
586 | if ((is_err = setColorMode(cam_params_.color_mode, false)) != IS_SUCCESS) return is_err;
587 | if ((is_err = setSubsampling(cam_params_.subsampling, false)) != IS_SUCCESS) return is_err;
588 | if ((is_err = setBinning(cam_params_.binning, false)) != IS_SUCCESS) return is_err;
589 | if ((is_err = setResolution(cam_params_.image_width, cam_params_.image_height,
590 | cam_params_.image_left, cam_params_.image_top, false)) != IS_SUCCESS) return is_err;
591 | if ((is_err = setSensorScaling(cam_params_.sensor_scaling, false)) != IS_SUCCESS) return is_err;
592 |
593 | // Force synchronize settings and re-allocate frame buffer for redundancy
594 | // NOTE: although this might not be needed, assume that parseROSParams()
595 | // is called only once per nodelet, thus ignore cost
596 | if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
597 |
598 | // Check for mutual exclusivity among requested sensor parameters
599 | if (!cam_params_.auto_exposure) { // Auto frame rate requires auto shutter
600 | cam_params_.auto_frame_rate = false;
601 | }
602 | if (cam_params_.auto_frame_rate) { // Auto frame rate has precedence over auto gain
603 | cam_params_.auto_gain = false;
604 | }
605 |
606 | // Configure camera sensor parameters
607 | // NOTE: failing to configure certain parameters may or may not cause camera to fail;
608 | // cuurently their failures are treated as non-critical
609 | //#define noop return is_err
610 | #define noop (void)0
611 | if ((is_err = setGain(cam_params_.auto_gain, cam_params_.master_gain,
612 | cam_params_.red_gain, cam_params_.green_gain,
613 | cam_params_.blue_gain, cam_params_.gain_boost)) != IS_SUCCESS) noop;
614 | if ((is_err = setSoftwareGamma(cam_params_.software_gamma)) != IS_SUCCESS) noop;
615 | if ((is_err = setPixelClockRate(cam_params_.pixel_clock)) != IS_SUCCESS) return is_err;
616 | if ((is_err = setFrameRate(cam_params_.auto_frame_rate, cam_params_.frame_rate)) != IS_SUCCESS) return is_err;
617 | if ((is_err = setExposure(cam_params_.auto_exposure, cam_params_.auto_exposure_reference, cam_params_.exposure)) != IS_SUCCESS) noop;
618 | if ((is_err = setWhiteBalance(cam_params_.auto_white_balance, cam_params_.white_balance_red_offset,
619 | cam_params_.white_balance_blue_offset)) != IS_SUCCESS) noop;
620 | if ((is_err = setGpioMode(1, cam_params_.gpio1, cam_params_.pwm_freq, cam_params_.pwm_duty_cycle)) != IS_SUCCESS) noop;
621 | if ((is_err = setGpioMode(2, cam_params_.gpio2, cam_params_.pwm_freq, cam_params_.pwm_duty_cycle)) != IS_SUCCESS) noop;
622 | if ((is_err = setMirrorUpsideDown(cam_params_.flip_upd)) != IS_SUCCESS) noop;
623 | if ((is_err = setMirrorLeftRight(cam_params_.flip_lr)) != IS_SUCCESS) noop;
624 | #undef noop
625 | }
626 |
627 | DEBUG_STREAM("Successfully applied settings from ROS params to [" << cam_name_ << "]");
628 |
629 | return is_err;
630 | }
631 |
632 |
633 | void UEyeCamNodelet::configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level) {
634 | if (!isConnected()) return;
635 |
636 | // See if frame grabber needs to be restarted
637 | bool restartFrameGrabber = false;
638 | bool needToReallocateBuffer = false;
639 | if (level == RECONFIGURE_STOP && frame_grab_alive_) {
640 | restartFrameGrabber = true;
641 | stopFrameGrabber();
642 | }
643 |
644 | // Configure color mode, resolution, and subsampling rate
645 | if (config.color_mode != cam_params_.color_mode) {
646 | needToReallocateBuffer = true;
647 | if (setColorMode(config.color_mode, false) != IS_SUCCESS) return;
648 | }
649 |
650 | if (config.image_width != cam_params_.image_width ||
651 | config.image_height != cam_params_.image_height ||
652 | config.image_left != cam_params_.image_left ||
653 | config.image_top != cam_params_.image_top) {
654 | needToReallocateBuffer = true;
655 | if (setResolution(config.image_width, config.image_height,
656 | config.image_left, config.image_top, false) != IS_SUCCESS) {
657 | // Attempt to restore previous (working) resolution
658 | config.image_width = cam_params_.image_width;
659 | config.image_height = cam_params_.image_height;
660 | config.image_left = cam_params_.image_left;
661 | config.image_top = cam_params_.image_top;
662 | if (setResolution(config.image_width, config.image_height,
663 | config.image_left, config.image_top, false) != IS_SUCCESS) return;
664 | }
665 | }
666 |
667 | if (config.subsampling != cam_params_.subsampling) {
668 | needToReallocateBuffer = true;
669 | if (setSubsampling(config.subsampling, false) != IS_SUCCESS) return;
670 | }
671 |
672 | if (config.binning != cam_params_.binning) {
673 | needToReallocateBuffer = true;
674 | if (setBinning(config.binning, false) != IS_SUCCESS) return;
675 | }
676 |
677 | if (config.sensor_scaling != cam_params_.sensor_scaling) {
678 | needToReallocateBuffer = true;
679 | if (setSensorScaling(config.sensor_scaling, false) != IS_SUCCESS) return;
680 | }
681 |
682 | // Reallocate internal camera buffer, and synchronize both non-ROS and ROS settings
683 | // for redundancy
684 | if (needToReallocateBuffer) {
685 | if (syncCamConfig() != IS_SUCCESS) return;
686 | needToReallocateBuffer = false;
687 | }
688 |
689 | // Check for mutual exclusivity among requested sensor parameters
690 | if (!config.auto_exposure) { // Auto frame rate requires auto shutter
691 | config.auto_frame_rate = false;
692 | }
693 | if (config.auto_frame_rate) { // Auto frame rate has precedence over auto gain
694 | config.auto_gain = false;
695 | }
696 |
697 | // Configure camera sensor parameters
698 | if (config.auto_gain != cam_params_.auto_gain ||
699 | config.master_gain != cam_params_.master_gain ||
700 | config.red_gain != cam_params_.red_gain ||
701 | config.green_gain != cam_params_.green_gain ||
702 | config.blue_gain != cam_params_.blue_gain ||
703 | config.gain_boost != cam_params_.gain_boost) {
704 | // If any of the manual gain params change, then automatically toggle off auto_gain
705 | if (config.master_gain != cam_params_.master_gain ||
706 | config.red_gain != cam_params_.red_gain ||
707 | config.green_gain != cam_params_.green_gain ||
708 | config.blue_gain != cam_params_.blue_gain ||
709 | config.gain_boost != cam_params_.gain_boost) {
710 | config.auto_gain = false;
711 | }
712 |
713 | if (setGain(config.auto_gain, config.master_gain,
714 | config.red_gain, config.green_gain,
715 | config.blue_gain, config.gain_boost) != IS_SUCCESS) return;
716 | }
717 | if (config.software_gamma != cam_params_.software_gamma) {
718 | if (setSoftwareGamma(config.software_gamma) != IS_SUCCESS) return;
719 | }
720 |
721 |
722 | if (config.pixel_clock != cam_params_.pixel_clock) {
723 | if (setPixelClockRate(config.pixel_clock) != IS_SUCCESS) return;
724 | }
725 |
726 | if (config.auto_frame_rate != cam_params_.auto_frame_rate ||
727 | config.frame_rate != cam_params_.frame_rate) {
728 | if (setFrameRate(config.auto_frame_rate, config.frame_rate) != IS_SUCCESS) return;
729 | }
730 |
731 | if (config.output_rate != cam_params_.output_rate) {
732 | if (!config.auto_frame_rate) {
733 | config.output_rate = std::min(config.output_rate, config.frame_rate);
734 | } // else, auto-fps is enabled, so don't bother checking validity of user-specified config.output_rate
735 |
736 | // Reset reference time for publisher throttle
737 | output_rate_mutex_.lock();
738 | init_publish_time_ = ros::Time(0);
739 | prev_output_frame_idx_ = 0;
740 | output_rate_mutex_.unlock();
741 | }
742 |
743 | if (config.auto_exposure != cam_params_.auto_exposure ||
744 | config.auto_exposure_reference != cam_params_.auto_exposure_reference ||
745 | config.exposure != cam_params_.exposure) {
746 | if (setExposure(config.auto_exposure, config.auto_exposure_reference, config.exposure) != IS_SUCCESS) return;
747 | }
748 |
749 | if (config.auto_white_balance != cam_params_.auto_white_balance ||
750 | config.white_balance_red_offset != cam_params_.white_balance_red_offset ||
751 | config.white_balance_blue_offset != cam_params_.white_balance_blue_offset) {
752 | if (setWhiteBalance(config.auto_white_balance, config.white_balance_red_offset,
753 | config.white_balance_blue_offset) != IS_SUCCESS) return;
754 | }
755 |
756 | if (config.flip_upd != cam_params_.flip_upd) {
757 | if (setMirrorUpsideDown(config.flip_upd) != IS_SUCCESS) return;
758 | }
759 | if (config.flip_lr != cam_params_.flip_lr) {
760 | if (setMirrorLeftRight(config.flip_lr) != IS_SUCCESS) return;
761 | }
762 |
763 | // NOTE: nothing needs to be done for config.ext_trigger_mode, since frame grabber loop will re-initialize to the right setting
764 |
765 | if (config.flash_delay != cam_params_.flash_delay ||
766 | config.flash_duration != cam_params_.flash_duration) {
767 | // NOTE: need to copy flash parameters to local copies since
768 | // cam_params_.flash_duration is type int, and also sizeof(int)
769 | // may not equal to sizeof(INT) / sizeof(UINT)
770 | INT flash_delay = config.flash_delay;
771 | UINT flash_duration = static_cast(config.flash_duration);
772 | setFlashParams(flash_delay, flash_duration);
773 | // Copy back actual flash parameter values that were set
774 | config.flash_delay = flash_delay;
775 | config.flash_duration = static_cast(flash_duration);
776 | }
777 |
778 | // Change gpio if mode has changed OR if mode is pwm and pwm settings have been changed
779 | if ((config.gpio1 != cam_params_.gpio1) ||
780 | (config.gpio1 == 4 && ((config.pwm_freq != cam_params_.pwm_freq) || (config.pwm_duty_cycle != cam_params_.pwm_duty_cycle)))) {
781 | if (setGpioMode(1, config.gpio1, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS) return;
782 | }
783 | if ((config.gpio2 != cam_params_.gpio2) ||
784 | (config.gpio2 == 4 && ((config.pwm_freq != cam_params_.pwm_freq) || (config.pwm_duty_cycle != cam_params_.pwm_duty_cycle)))) {
785 | if (setGpioMode(2, config.gpio2, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS) return;
786 | }
787 |
788 | // Update local copy of parameter set to newly updated set
789 | cam_params_ = config;
790 |
791 | // Restart frame grabber if needed
792 | cfg_sync_requested_ = true;
793 | if (restartFrameGrabber) {
794 | startFrameGrabber();
795 | }
796 |
797 | DEBUG_STREAM("Successfully applied settings from dyncfg to [" << cam_name_ << "]");
798 | }
799 |
800 |
801 | INT UEyeCamNodelet::syncCamConfig(string dft_mode_str) {
802 | INT is_err;
803 |
804 | if ((is_err = UEyeCamDriver::syncCamConfig(dft_mode_str)) != IS_SUCCESS) return is_err;
805 |
806 | // Update ROS color mode string
807 | cam_params_.color_mode = colormode2name(is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE));
808 | if (cam_params_.color_mode.empty()) {
809 | ERROR_STREAM("Force-updating to default color mode for [" << cam_name_ << "]: " <<
810 | dft_mode_str << "\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
811 | cam_params_.color_mode = dft_mode_str;
812 | setColorMode(cam_params_.color_mode);
813 | }
814 |
815 | // Copy internal settings to ROS dynamic configure settings
816 | cam_params_.image_width = cam_aoi_.s32Width; // Technically, these are width and height for the
817 | cam_params_.image_height = cam_aoi_.s32Height; // sensor's Area of Interest, and not of the image
818 | if (cam_params_.image_left >= 0) cam_params_.image_left = cam_aoi_.s32X; // TODO: 1 ideally want to ensure that aoi top-left does correspond to centering
819 | if (cam_params_.image_top >= 0) cam_params_.image_top = cam_aoi_.s32Y;
820 | cam_params_.subsampling = static_cast(cam_subsampling_rate_);
821 | cam_params_.binning = static_cast(cam_binning_rate_);
822 | cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
823 | //cfg_sync_requested_ = true; // WARNING: assume that dyncfg client may want to override current settings
824 |
825 | // (Re-)populate ROS image message
826 | ros_image_.header.frame_id = frame_name_;
827 | // NOTE: .height, .width, .encoding, .step and .data determined in fillImgMsg();
828 | // .is_bigendian determined in constructor
829 |
830 | return is_err;
831 | }
832 |
833 |
834 | INT UEyeCamNodelet::queryCamParams() {
835 | INT is_err = IS_SUCCESS;
836 | INT query;
837 | double pval1, pval2;
838 |
839 | // NOTE: assume that color mode, bits per pixel, area of interest info, resolution,
840 | // sensor scaling rate, subsampling rate, and binning rate have already
841 | // been synchronized by syncCamConfig()
842 |
843 | if ((is_err = is_SetAutoParameter(cam_handle_,
844 | IS_GET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS &&
845 | (is_err = is_SetAutoParameter(cam_handle_,
846 | IS_GET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
847 | ERROR_STREAM("Failed to query auto gain mode for UEye camera '" <<
848 | cam_name_ << "' (" << err2str(is_err) << ")");
849 | return is_err;
850 | }
851 | cam_params_.auto_gain = (pval1 != 0);
852 |
853 | cam_params_.master_gain = is_SetHardwareGain(cam_handle_, IS_GET_MASTER_GAIN,
854 | IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
855 | cam_params_.red_gain = is_SetHardwareGain(cam_handle_, IS_GET_RED_GAIN,
856 | IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
857 | cam_params_.green_gain = is_SetHardwareGain(cam_handle_, IS_GET_GREEN_GAIN,
858 | IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
859 | cam_params_.blue_gain = is_SetHardwareGain(cam_handle_, IS_GET_BLUE_GAIN,
860 | IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
861 |
862 | query = is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST);
863 | if(query == IS_SET_GAINBOOST_ON) {
864 | query = is_SetGainBoost(cam_handle_, IS_GET_GAINBOOST);
865 | if (query == IS_SET_GAINBOOST_ON) {
866 | cam_params_.gain_boost = true;
867 | } else if (query == IS_SET_GAINBOOST_OFF) {
868 | cam_params_.gain_boost = false;
869 | } else {
870 | ERROR_STREAM("Failed to query gain boost for [" << cam_name_ <<
871 | "] (" << err2str(query) << ")");
872 | return query;
873 | }
874 | } else {
875 | cam_params_.gain_boost = false;
876 | }
877 |
878 | if ((is_err = is_Gamma(cam_handle_, IS_GAMMA_CMD_GET, (void*) &cam_params_.software_gamma,
879 | sizeof(cam_params_.software_gamma))) != IS_SUCCESS) {
880 | ERROR_STREAM("Failed to query software gamma value for [" << cam_name_ <<
881 | "] (" << err2str(is_err) << ")");
882 | return is_err;
883 | }
884 |
885 | if ((is_err = is_SetAutoParameter(cam_handle_,
886 | IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS &&
887 | (is_err = is_SetAutoParameter(cam_handle_,
888 | IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
889 | ERROR_STREAM("Failed to query auto shutter mode for [" << cam_name_ <<
890 | "] (" << err2str(is_err) << ")");
891 | return is_err;
892 | }
893 | cam_params_.auto_exposure = (pval1 != 0);
894 |
895 | if ((is_err = is_SetAutoParameter (cam_handle_, IS_GET_AUTO_REFERENCE,
896 | &cam_params_.auto_exposure_reference, 0)) != IS_SUCCESS) {
897 | ERROR_STREAM("Failed to query exposure reference value for [" << cam_name_ <<
898 | "] (" << err2str(is_err) << ")");
899 | }
900 |
901 | if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE,
902 | &cam_params_.exposure, sizeof(cam_params_.exposure))) != IS_SUCCESS) {
903 | ERROR_STREAM("Failed to query exposure timing for [" << cam_name_ <<
904 | "] (" << err2str(is_err) << ")");
905 | return is_err;
906 | }
907 |
908 | if ((is_err = is_SetAutoParameter(cam_handle_,
909 | IS_GET_ENABLE_AUTO_SENSOR_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS &&
910 | (is_err = is_SetAutoParameter(cam_handle_,
911 | IS_GET_ENABLE_AUTO_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS) {
912 | ERROR_STREAM("Failed to query auto white balance mode for [" << cam_name_ <<
913 | "] (" << err2str(is_err) << ")");
914 | return is_err;
915 | }
916 | cam_params_.auto_white_balance = (pval1 != 0);
917 |
918 | if ((is_err = is_SetAutoParameter(cam_handle_,
919 | IS_GET_AUTO_WB_OFFSET, &pval1, &pval2)) != IS_SUCCESS) {
920 | ERROR_STREAM("Failed to query auto white balance red/blue channel offsets for [" <<
921 | cam_name_ << "] (" << err2str(is_err) << ")");
922 | return is_err;
923 | }
924 | cam_params_.white_balance_red_offset = static_cast(pval1);
925 | cam_params_.white_balance_blue_offset = static_cast(pval2);
926 |
927 | IO_FLASH_PARAMS currFlashParams;
928 | if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS,
929 | (void*) &currFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
930 | ERROR_STREAM("Could not retrieve current flash parameter info for [" <<
931 | cam_name_ << "] (" << err2str(is_err) << ")");
932 | return is_err;
933 | }
934 | cam_params_.flash_delay = currFlashParams.s32Delay;
935 | cam_params_.flash_duration = static_cast(currFlashParams.u32Duration);
936 |
937 | if ((is_err = is_SetAutoParameter(cam_handle_,
938 | IS_GET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS &&
939 | (is_err = is_SetAutoParameter(cam_handle_,
940 | IS_GET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
941 | ERROR_STREAM("Failed to query auto frame rate mode for [" << cam_name_ <<
942 | "] (" << err2str(is_err) << ")");
943 | return is_err;
944 | }
945 | cam_params_.auto_frame_rate = (pval1 != 0);
946 |
947 | if ((is_err = is_SetFrameRate(cam_handle_, IS_GET_FRAMERATE, &cam_params_.frame_rate)) != IS_SUCCESS) {
948 | ERROR_STREAM("Failed to query frame rate for [" << cam_name_ <<
949 | "] (" << err2str(is_err) << ")");
950 | return is_err;
951 | }
952 |
953 | UINT currPixelClock;
954 | if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET,
955 | (void*) &currPixelClock, sizeof(currPixelClock))) != IS_SUCCESS) {
956 | ERROR_STREAM("Failed to query pixel clock rate for [" << cam_name_ <<
957 | "] (" << err2str(is_err) << ")");
958 | return is_err;
959 | }
960 | cam_params_.pixel_clock = static_cast(currPixelClock);
961 |
962 | INT currROP = is_SetRopEffect(cam_handle_, IS_GET_ROP_EFFECT, 0, 0);
963 | cam_params_.flip_upd = ((currROP & IS_SET_ROP_MIRROR_UPDOWN) == IS_SET_ROP_MIRROR_UPDOWN);
964 | cam_params_.flip_lr = ((currROP & IS_SET_ROP_MIRROR_LEFTRIGHT) == IS_SET_ROP_MIRROR_LEFTRIGHT);
965 |
966 | // NOTE: do not need to (re-)populate ROS image message, since assume that
967 | // syncCamConfig() was previously called
968 |
969 | DEBUG_STREAM("Successfully queries parameters from [" << cam_name_ << "]");
970 |
971 | return is_err;
972 | }
973 |
974 |
975 | INT UEyeCamNodelet::connectCam() {
976 | INT is_err = IS_SUCCESS;
977 |
978 | if ((is_err = UEyeCamDriver::connectCam()) != IS_SUCCESS) return is_err;
979 |
980 | // (Attempt to) load UEye camera parameter configuration file
981 | if (cam_params_filename_.length() <= 0) { // Try to use default filename if not specified otherwise
982 | std::string cam_params_filename_fallback = string(getenv("HOME")) + "/.ros/camera_conf/" + cam_name_ + ".ini";
983 | if (access( cam_params_filename_fallback.c_str(), F_OK ) != -1 ) { cam_params_filename_=cam_params_filename_fallback;}
984 | }
985 | if (cam_params_filename_.length() > 0) {
986 | if ((is_err = loadCamConfig(cam_params_filename_)) != IS_SUCCESS) return is_err;
987 | }
988 |
989 | // Query existing configuration parameters from camera
990 | if ((is_err = queryCamParams()) != IS_SUCCESS) return is_err;
991 |
992 | // Parse and load ROS camera settings
993 | if ((is_err = parseROSParams(getPrivateNodeHandle())) != IS_SUCCESS) return is_err;
994 |
995 | return IS_SUCCESS;
996 | }
997 |
998 |
999 | INT UEyeCamNodelet::disconnectCam() {
1000 | INT is_err = IS_SUCCESS;
1001 |
1002 | if (isConnected()) {
1003 | stopFrameGrabber();
1004 | is_err = UEyeCamDriver::disconnectCam();
1005 | }
1006 |
1007 | return is_err;
1008 | }
1009 |
1010 |
1011 | bool UEyeCamNodelet::setCamInfo(sensor_msgs::SetCameraInfo::Request& req,
1012 | sensor_msgs::SetCameraInfo::Response& rsp) {
1013 | ros_cam_info_ = req.camera_info;
1014 | ros_cam_info_.header.frame_id = frame_name_;
1015 | rsp.success = saveIntrinsicsFile();
1016 | rsp.status_message = (rsp.success) ?
1017 | "successfully wrote camera info to file" :
1018 | "failed to write camera info to file";
1019 | return true;
1020 | }
1021 |
1022 |
1023 | void UEyeCamNodelet::frameGrabLoop() {
1024 | #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
1025 | ros::Time prevStartGrab = ros::Time::now();
1026 | ros::Time prevGrabbedFrame = ros::Time::now();
1027 | ros::Time currStartGrab;
1028 | ros::Time currGrabbedFrame;
1029 | double startGrabSum = 0;
1030 | double grabbedFrameSum = 0;
1031 | double startGrabSumSqrd = 0;
1032 | double grabbedFrameSumSqrd = 0;
1033 | unsigned int startGrabCount = 0;
1034 | unsigned int grabbedFrameCount = 0;
1035 | #endif
1036 |
1037 | DEBUG_STREAM("Starting threaded frame grabber loop for [" << cam_name_ << "]");
1038 |
1039 | ros::Rate idleDelay(200);
1040 |
1041 | int prevNumSubscribers = 0;
1042 | int currNumSubscribers = 0;
1043 | while (frame_grab_alive_ && ros::ok()) {
1044 | // Initialize live video mode if camera was previously asleep, and ROS image topic has subscribers;
1045 | // and stop live video mode if ROS image topic no longer has any subscribers
1046 | currNumSubscribers = static_cast(ros_cam_pub_.getNumSubscribers());
1047 | if (currNumSubscribers > 0 && prevNumSubscribers <= 0) {
1048 | // Reset reference time to prevent throttling first frame
1049 | output_rate_mutex_.lock();
1050 | init_publish_time_ = ros::Time(0);
1051 | prev_output_frame_idx_ = 0;
1052 | output_rate_mutex_.unlock();
1053 |
1054 | if (cam_params_.ext_trigger_mode) {
1055 | if (setExtTriggerMode() != IS_SUCCESS) {
1056 | ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
1057 | ros::shutdown();
1058 | return;
1059 | }
1060 | INFO_STREAM("[" << cam_name_ << "] set to external trigger mode");
1061 | } else {
1062 | if (setFreeRunMode() != IS_SUCCESS) {
1063 | ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
1064 | ros::shutdown();
1065 | return;
1066 | }
1067 |
1068 | // NOTE: need to copy flash parameters to local copies since
1069 | // cam_params_.flash_duration is type int, and also sizeof(int)
1070 | // may not equal to sizeof(INT) / sizeof(UINT)
1071 | INT flash_delay = cam_params_.flash_delay;
1072 | UINT flash_duration = static_cast(cam_params_.flash_duration);
1073 | setFlashParams(flash_delay, flash_duration);
1074 | // Copy back actual flash parameter values that were set
1075 | cam_params_.flash_delay = flash_delay;
1076 | cam_params_.flash_duration = static_cast(flash_duration);
1077 |
1078 | INFO_STREAM("[" << cam_name_ << "] set to free-run mode");
1079 | }
1080 | } else if (currNumSubscribers <= 0 && prevNumSubscribers > 0) {
1081 | if (setStandbyMode() != IS_SUCCESS) {
1082 | ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
1083 | ros::shutdown();
1084 | return;
1085 | }
1086 | INFO_STREAM("[" << cam_name_ << "] set to standby mode");
1087 | }
1088 | prevNumSubscribers = currNumSubscribers;
1089 |
1090 | // Send updated dyncfg parameters if previously changed
1091 | if (cfg_sync_requested_) {
1092 | if (ros_cfg_mutex_.try_lock()) { // Make sure that dynamic reconfigure server or config callback is not active
1093 | ros_cfg_mutex_.unlock();
1094 | ros_cfg_->updateConfig(cam_params_);
1095 | cfg_sync_requested_ = false;
1096 | }
1097 | }
1098 |
1099 |
1100 | #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
1101 | startGrabCount++;
1102 | currStartGrab = ros::Time::now();
1103 | if (startGrabCount > 1) {
1104 | startGrabSum += (currStartGrab - prevStartGrab).toSec() * 1000.0;
1105 | startGrabSumSqrd += ((currStartGrab - prevStartGrab).toSec() * 1000.0)*((currStartGrab - prevStartGrab).toSec() * 1000.0);
1106 | }
1107 | prevStartGrab = currStartGrab;
1108 | #endif
1109 |
1110 | if (isCapturing()) {
1111 | UINT eventTimeout = (cam_params_.auto_frame_rate || cam_params_.ext_trigger_mode) ?
1112 | static_cast(2000) : static_cast(1000.0 / cam_params_.frame_rate * 2);
1113 | if (processNextFrame(eventTimeout) != nullptr) {
1114 | // Initialize shared pointers from member messages for nodelet intraprocess publishing
1115 | sensor_msgs::ImagePtr img_msg_ptr(new sensor_msgs::Image(ros_image_));
1116 | sensor_msgs::CameraInfoPtr cam_info_msg_ptr(new sensor_msgs::CameraInfo(ros_cam_info_));
1117 |
1118 | // Initialize/compute frame timestamp based on clock tick value from camera
1119 | if (init_ros_time_.isZero()) {
1120 | if(getClockTick(&init_clock_tick_)) {
1121 | init_ros_time_ = getImageTimestamp();
1122 | }
1123 | }
1124 | img_msg_ptr->header.stamp = cam_info_msg_ptr->header.stamp = getImageTickTimestamp();
1125 |
1126 | // Process new frame
1127 | #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
1128 | grabbedFrameCount++;
1129 | currGrabbedFrame = ros::Time::now();
1130 | if (grabbedFrameCount > 1) {
1131 | grabbedFrameSum += (currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0;
1132 | grabbedFrameSumSqrd += ((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0)*((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0);
1133 | }
1134 | prevGrabbedFrame = currGrabbedFrame;
1135 |
1136 | if (grabbedFrameCount > 1) {
1137 | WARN_STREAM("\nPre-Grab: " << startGrabSum/startGrabCount << " +/- " <<
1138 | sqrt(startGrabSumSqrd/startGrabCount - (startGrabSum/startGrabCount)*(startGrabSum/startGrabCount)) << " ms (" <<
1139 | 1000.0*startGrabCount/startGrabSum << "Hz)\n" <<
1140 | "Post-Grab: " << grabbedFrameSum/grabbedFrameCount << " +/- " <<
1141 | sqrt(grabbedFrameSumSqrd/grabbedFrameCount - (grabbedFrameSum/grabbedFrameCount)*(grabbedFrameSum/grabbedFrameCount)) << " ms (" <<
1142 | 1000.0*grabbedFrameCount/grabbedFrameSum << "Hz)\n" <<
1143 | "Target: " << cam_params_.frame_rate << "Hz");
1144 | }
1145 | #endif
1146 |
1147 | if (!frame_grab_alive_ || !ros::ok()) break;
1148 |
1149 | // Throttle publish rate
1150 | bool throttle_curr_frame = false;
1151 | output_rate_mutex_.lock();
1152 | if (!cam_params_.ext_trigger_mode && cam_params_.output_rate > 0) {
1153 | if (init_publish_time_.is_zero()) { // Set reference time
1154 | init_publish_time_ = img_msg_ptr->header.stamp;
1155 | } else {
1156 | double time_elapsed = (img_msg_ptr->header.stamp - init_publish_time_).toSec();
1157 | uint64_t curr_output_frame_idx = static_cast(std::floor(time_elapsed * cam_params_.output_rate));
1158 | if (curr_output_frame_idx <= prev_output_frame_idx_) {
1159 | throttle_curr_frame = true;
1160 | } else {
1161 | prev_output_frame_idx_ = curr_output_frame_idx;
1162 | }
1163 | }
1164 | }
1165 | output_rate_mutex_.unlock();
1166 | if (throttle_curr_frame) continue;
1167 |
1168 | cam_info_msg_ptr->width = static_cast(cam_params_.image_width / cam_sensor_scaling_rate_ / cam_binning_rate_ / cam_subsampling_rate_);
1169 | cam_info_msg_ptr->height = static_cast(cam_params_.image_height / cam_sensor_scaling_rate_ / cam_binning_rate_ / cam_subsampling_rate_);
1170 |
1171 | // Copy pixel content from internal frame buffer to ROS image
1172 | if (!fillMsgData(*img_msg_ptr)) continue;
1173 |
1174 | img_msg_ptr->header.seq = cam_info_msg_ptr->header.seq = ros_frame_count_++;
1175 | img_msg_ptr->header.frame_id = cam_info_msg_ptr->header.frame_id;
1176 |
1177 | if (!frame_grab_alive_ || !ros::ok()) break;
1178 |
1179 | ros_cam_pub_.publish(img_msg_ptr, cam_info_msg_ptr);
1180 | }
1181 | } else {
1182 | init_ros_time_ = ros::Time(0);
1183 | init_clock_tick_ = 0;
1184 | }
1185 |
1186 | if (!frame_grab_alive_ || !ros::ok()) break;
1187 | idleDelay.sleep();
1188 | }
1189 |
1190 | setStandbyMode();
1191 | frame_grab_alive_ = false;
1192 |
1193 | DEBUG_STREAM("Frame grabber loop terminated for [" << cam_name_ << "]");
1194 | }
1195 |
1196 |
1197 | void UEyeCamNodelet::startFrameGrabber() {
1198 | frame_grab_alive_ = true;
1199 | frame_grab_thread_ = thread(bind(&UEyeCamNodelet::frameGrabLoop, this));
1200 | }
1201 |
1202 |
1203 | void UEyeCamNodelet::stopFrameGrabber() {
1204 | frame_grab_alive_ = false;
1205 | if (frame_grab_thread_.joinable()) {
1206 | frame_grab_thread_.join();
1207 | }
1208 | frame_grab_thread_ = thread();
1209 | }
1210 |
1211 | const std::map UEyeCamNodelet::ENCODING_DICTIONARY = {
1212 | { IS_CM_SENSOR_RAW8, sensor_msgs::image_encodings::BAYER_RGGB8 },
1213 | { IS_CM_SENSOR_RAW10, sensor_msgs::image_encodings::BAYER_RGGB16 },
1214 | { IS_CM_SENSOR_RAW12, sensor_msgs::image_encodings::BAYER_RGGB16 },
1215 | { IS_CM_SENSOR_RAW16, sensor_msgs::image_encodings::BAYER_RGGB16 },
1216 | { IS_CM_MONO8, sensor_msgs::image_encodings::MONO8 },
1217 | { IS_CM_MONO10, sensor_msgs::image_encodings::MONO16 },
1218 | { IS_CM_MONO12, sensor_msgs::image_encodings::MONO16 },
1219 | { IS_CM_MONO16, sensor_msgs::image_encodings::MONO16 },
1220 | { IS_CM_RGB8_PACKED, sensor_msgs::image_encodings::RGB8 },
1221 | { IS_CM_BGR8_PACKED, sensor_msgs::image_encodings::BGR8 },
1222 | { IS_CM_RGB10_PACKED, sensor_msgs::image_encodings::RGB16 },
1223 | { IS_CM_BGR10_PACKED, sensor_msgs::image_encodings::BGR16 },
1224 | { IS_CM_RGB10_UNPACKED, sensor_msgs::image_encodings::RGB16 },
1225 | { IS_CM_BGR10_UNPACKED, sensor_msgs::image_encodings::BGR16 },
1226 | { IS_CM_RGB12_UNPACKED, sensor_msgs::image_encodings::RGB16 },
1227 | { IS_CM_BGR12_UNPACKED, sensor_msgs::image_encodings::BGR16 }
1228 | };
1229 |
1230 | bool UEyeCamNodelet::fillMsgData(sensor_msgs::Image& img) const {
1231 | // Copy pixel content from internal frame buffer to img
1232 | // and unpack to proper pixel format
1233 | INT expected_row_stride = cam_aoi_.s32Width * bits_per_pixel_/8;
1234 | if (cam_buffer_pitch_ < expected_row_stride) {
1235 | ERROR_STREAM("Camera buffer pitch (" << cam_buffer_pitch_ <<
1236 | ") is smaller than expected for [" << cam_name_ << "]: " <<
1237 | "width (" << cam_aoi_.s32Width << ") * bytes per pixel (" <<
1238 | bits_per_pixel_/8 << ") = " << expected_row_stride);
1239 | return false;
1240 | }
1241 |
1242 | // allocate target memory
1243 | img.width = static_cast(cam_aoi_.s32Width);
1244 | img.height = static_cast(cam_aoi_.s32Height);
1245 | img.encoding = ENCODING_DICTIONARY.at(color_mode_);
1246 | img.step = img.width * static_cast(sensor_msgs::image_encodings::numChannels(img.encoding)) * static_cast(sensor_msgs::image_encodings::bitDepth(img.encoding))/8;
1247 | img.data.resize(img.height * img.step);
1248 |
1249 | DEBUG_STREAM("Allocated ROS image buffer for [" << cam_name_ << "]:" <<
1250 | "\n size: " << cam_buffer_size_ <<
1251 | "\n width: " << img.width <<
1252 | "\n height: " << img.height <<
1253 | "\n step: " << img.step <<
1254 | "\n encoding: " << img.encoding);
1255 |
1256 | const std::function unpackCopy = getUnpackCopyFunc(color_mode_);
1257 |
1258 | if (cam_buffer_pitch_ == expected_row_stride) {
1259 | // Content is contiguous, so copy out the entire buffer at once
1260 | unpackCopy(img.data.data(), cam_buffer_, img.height*static_cast(expected_row_stride));
1261 | } else { // cam_buffer_pitch_ > expected_row_stride
1262 | // Each row contains extra buffer according to cam_buffer_pitch_, so must copy out each row independently
1263 | uint8_t* dst_ptr = img.data.data();
1264 | char* cam_buffer_ptr = cam_buffer_;
1265 | for (INT row = 0; row < cam_aoi_.s32Height; row++) {
1266 | unpackCopy(dst_ptr, cam_buffer_ptr, static_cast(expected_row_stride));
1267 | cam_buffer_ptr += cam_buffer_pitch_;
1268 | dst_ptr += img.step;
1269 | }
1270 | }
1271 | return true;
1272 | }
1273 |
1274 |
1275 | void UEyeCamNodelet::loadIntrinsicsFile() {
1276 | if (cam_intr_filename_.length() <= 0) { // Use default filename
1277 | cam_intr_filename_ = string(getenv("HOME")) + "/.ros/camera_info/" + cam_name_ + ".yaml";
1278 | }
1279 |
1280 | if (camera_calibration_parsers::readCalibration(cam_intr_filename_, cam_name_, ros_cam_info_)) {
1281 | DEBUG_STREAM("Loaded intrinsics parameters for [" << cam_name_ << "]");
1282 | }
1283 | ros_cam_info_.header.frame_id = frame_name_;
1284 | }
1285 |
1286 |
1287 | bool UEyeCamNodelet::saveIntrinsicsFile() {
1288 | if (camera_calibration_parsers::writeCalibration(cam_intr_filename_, cam_name_, ros_cam_info_)) {
1289 | DEBUG_STREAM("Saved intrinsics parameters for [" << cam_name_ <<
1290 | "] to " << cam_intr_filename_);
1291 | return true;
1292 | }
1293 | return false;
1294 | }
1295 |
1296 | ros::Time UEyeCamNodelet::getImageTimestamp() {
1297 | // There have been several issues reported on time drifts, so we shall rely purely on ros::Time::now()
1298 | // e.g. https://github.com/anqixu/ueye_cam/issues/82
1299 | //
1300 | // UEYETIME utime;
1301 | // if(getTimestamp(&utime)) {
1302 | // struct tm tm;
1303 | // tm.tm_year = utime.wYear - 1900;
1304 | // tm.tm_mon = utime.wMonth - 1;
1305 | // tm.tm_mday = utime.wDay;
1306 | // tm.tm_hour = utime.wHour;
1307 | // tm.tm_min = utime.wMinute;
1308 | // tm.tm_sec = utime.wSecond;
1309 | // ros::Time t = ros::Time(mktime(&tm),utime.wMilliseconds*1e6);
1310 | //
1311 | // // Deal with instability due to daylight savings time
1312 | // if (abs((ros::Time::now() - t).toSec()) > abs((ros::Time::now() - (t+ros::Duration(3600,0))).toSec())) { t += ros::Duration(3600,0); }
1313 | // if (abs((ros::Time::now() - t).toSec()) > abs((ros::Time::now() - (t-ros::Duration(3600,0))).toSec())) { t -= ros::Duration(3600,0); }
1314 | //
1315 | // return t;
1316 | // }
1317 | return ros::Time::now();
1318 | }
1319 |
1320 | ros::Time UEyeCamNodelet::getImageTickTimestamp() {
1321 | uint64_t tick;
1322 | if(getClockTick(&tick)) {
1323 | return init_ros_time_ + ros::Duration(double(tick - init_clock_tick_)*1e-7);
1324 | }
1325 | return ros::Time::now();
1326 | }
1327 | // TODO: 0 bug where nodelet locks and requires SIGTERM when there are still subscribers (need to find where does code hang)
1328 |
1329 |
1330 | void UEyeCamNodelet::handleTimeout() {
1331 | std_msgs::UInt64 timeout_msg;
1332 | timeout_msg.data = ++timeout_count_;
1333 | timeout_pub_.publish(timeout_msg);
1334 | };
1335 |
1336 |
1337 | } // namespace ueye_cam
1338 |
1339 |
1340 | // TODO: 9 bug: when binning (and suspect when subsampling / sensor scaling), white balance / color gains seem to have different effects
1341 |
1342 |
1343 | #include
1344 | PLUGINLIB_EXPORT_CLASS(ueye_cam::UEyeCamNodelet, nodelet::Nodelet)
1345 |
--------------------------------------------------------------------------------