Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make camera settings configurable & more #38

Merged
merged 28 commits into from
Aug 7, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
57b0d83
build: Set CMAKE_CXX_STANDARD_REQUIRED
luator May 28, 2024
5f35b9c
Add CameraSettings struct and function to load from file
luator May 28, 2024
580c7de
Reimplement Settings
luator May 28, 2024
1c9b0b9
test: Add unit tests for Settings
luator May 28, 2024
a098807
Use Settings in PylonDriver
luator May 28, 2024
406fa95
Use Settings in TriCameraDriver
luator May 28, 2024
21513fc
doc: Add documentation for Settings
luator May 29, 2024
d89dcf7
Update CHANGELOG
luator May 29, 2024
72114de
fix: Open camera when no device_user_id is given & refactor
luator May 29, 2024
0f06620
Add executable pylon_dump_camera_settings
luator May 29, 2024
6f94f93
doc: Add documentation for pylon-related executables
luator May 29, 2024
5e15d49
(check_camera_sharpness) Do not assume camera rate
luator May 29, 2024
0a1f605
PyBulletTriCameraDriver: Use Settings to get frame rate
luator May 29, 2024
320d86a
Add Python bindings for Settings
luator Jun 5, 2024
83ea941
pylon_list_cameras: Keep stdout clean if there are no cameras
luator Jun 5, 2024
2bed6f4
docs: Update info on writing pylon device user id
luator Jun 5, 2024
392c8f7
More informative error if config file parsing fails
luator Jun 5, 2024
1f444e3
Use fmt in PylonDriver
luator Jun 5, 2024
77a977b
Nicer error output in demo_camera.py
luator Jun 5, 2024
40adfa2
Load device ID from camera if not specified.
luator Jun 5, 2024
9b3a6da
fix: Add cli_utils to package.xml
luator Jun 11, 2024
570001e
fix: Properly export fmt dependency
luator Jun 11, 2024
ceb2f23
build: Remove ament_export_libraries and _include_directories
luator Jun 11, 2024
9cc988b
fix linter warnings in demo_tricamera.py
luator Jun 24, 2024
e643965
Add script tricamera_monitor_rate.py
luator Aug 5, 2024
3927d86
doc: Update CHANGELOG
luator Aug 5, 2024
37e0dee
Reformat C++
luator Aug 5, 2024
74b4518
Reformat Python
luator Aug 5, 2024
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,23 @@
significantly out of focus.
- Executable `pylon_write_device_user_id_to_camera` to set the "DeviceUserID" of
Pylon cameras.
- Executable `pylon_dump_camera_settings` to save settings of a Pylon camera.
- Make some settings (e.g. frame rate) configurable through a TOML config file. For
more information see
[documentation](https://open-dynamic-robot-initiative.github.io/trifinger_cameras/doc/configuration.html)
- Executable `tricamera_monitor_rate` for checking the actual frame rate (most meant for
debugging and testing during development)

### Removed
- Obsolete script `verify_calibration.py`

### Fixed
- pybind11 build error on Ubuntu 22.04
- Connecting to camera without specifying DeviceUserID was not working. It now opens
the first camera in the list of connected cameras if no ID is specified.

### Changed
- `pylon_list_cameras`: Keep stdout clean if there are no cameras.


## [1.0.0] - 2022-06-28
Expand Down
69 changes: 50 additions & 19 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 3.5)
project(trifinger_cameras)

set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED on)

# libraries need to be position independent for building Python modules
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
Expand All @@ -24,9 +25,12 @@ find_package(robot_interfaces REQUIRED)
find_package(serialization_utils REQUIRED)
find_package(yaml_utils REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(cli_utils REQUIRED)

find_package(Eigen3 REQUIRED)
find_package(fmt REQUIRED)
find_package(OpenCV REQUIRED)
find_package(tomlplusplus REQUIRED)

find_package(Pylon)
if (${Pylon_FOUND})
Expand All @@ -38,13 +42,27 @@ endif()
ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR python/${PROJECT_NAME})


ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)


set(install_targets "")


# Libraries
add_library(settings
src/settings.cpp
)
target_include_directories(settings PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${OpenCV_INCLUDE_DIRS})
target_link_libraries(settings
tomlplusplus::tomlplusplus
fmt::fmt
)
ament_target_dependencies(settings
ament_index_cpp
)
list(APPEND install_targets settings)

add_library(camera_observations
src/camera_observation.cpp
src/tricamera_observation.cpp
Expand Down Expand Up @@ -85,11 +103,10 @@ if (${Pylon_FOUND})
target_link_libraries(pylon_driver
${OpenCV_LIBRARIES}
${Pylon_LIBRARIES}
fmt::fmt
robot_interfaces::robot_interfaces
camera_observations
)
ament_target_dependencies(pylon_driver
ament_index_cpp
settings
)
list(APPEND install_targets pylon_driver)

Expand All @@ -106,6 +123,7 @@ if (${Pylon_FOUND})
${Pylon_LIBRARIES}
robot_interfaces::robot_interfaces
pylon_driver
settings
)
list(APPEND install_targets tricamera_driver)

Expand All @@ -132,6 +150,20 @@ if (${Pylon_FOUND})
target_link_libraries(pylon_write_device_user_id_to_camera ${Pylon_LIBRARIES})
list(APPEND install_targets pylon_write_device_user_id_to_camera)

add_executable(pylon_dump_camera_settings
src/pylon_dump_camera_settings.cpp
)
target_include_directories(pylon_dump_camera_settings PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${Pylon_INCLUDE_DIRS}
)
target_link_libraries(pylon_dump_camera_settings
${Pylon_LIBRARIES}
pylon_driver
cli_utils::program_options
)
list(APPEND install_targets pylon_dump_camera_settings)

# Set library names to variables, so we can use the variable instead of the
# direct name below. In case, Pylon drivers are not built, the variables
Expand All @@ -148,6 +180,7 @@ target_include_directories(pybullet_tricamera_driver PUBLIC
)
target_link_libraries(pybullet_tricamera_driver
camera_observations
settings
serialization_utils::serialization_utils
robot_interfaces::robot_interfaces
pybind11_opencv::pybind11_opencv
Expand Down Expand Up @@ -187,6 +220,7 @@ list(APPEND install_targets load_camera_config_test)
add_pybind11_module(py_camera_types srcpy/py_camera_types.cpp
LINK_LIBRARIES
pybind11_opencv::pybind11_opencv
settings
camera_observations
opencv_driver
${pylon_driver}
Expand Down Expand Up @@ -231,6 +265,7 @@ install_scripts(
scripts/record_image_dataset.py
scripts/tricamera_log_converter.py
scripts/tricamera_log_viewer.py
scripts/tricamera_monitor_rate.py
scripts/tricamera_test_connection.py

DESTINATION lib/${PROJECT_NAME}
Expand All @@ -245,23 +280,27 @@ install(
)



# Tests
if (BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_cmake_nose REQUIRED)

# install files that are used by the tests
install(FILES tests/camera_calib.yml
DESTINATION share/${PROJECT_NAME}/tests)

ament_add_gtest(test_camera_observation tests/test_camera_observation.cpp)
ament_add_gmock(test_settings tests/test_settings.cpp)
target_link_libraries(test_settings
settings
)

ament_add_gmock(test_camera_observation tests/test_camera_observation.cpp)
target_link_libraries(test_camera_observation
${OpenCV_LIBRARIES}
camera_observations
)

ament_add_gtest(test_shared_memory_camera_data
ament_add_gmock(test_shared_memory_camera_data
tests/test_shared_memory_camera_data.cpp)
target_link_libraries(test_shared_memory_camera_data
${OpenCV_LIBRARIES}
Expand All @@ -276,14 +315,6 @@ endif()



ament_export_include_directories(include ${Pylon_INCLUDE_DIRS})
ament_export_libraries(
camera_observations
opencv_driver
${pylon_driver}
${tricamera_driver}
pybullet_tricamera_driver
camera_calibration_parser
)
ament_export_dependencies(yaml_utils sensor_msgs)
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(yaml_utils sensor_msgs tomlplusplus fmt)
ament_package(CONFIG_EXTRAS cmake/cfg_extras.cmake.in)
26 changes: 18 additions & 8 deletions demos/demo_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,15 @@
camera, and the available methods for that.
"""
import argparse
import sys

import cv2

import trifinger_cameras
from trifinger_cameras import utils


def main():
def main() -> int:
argparser = argparse.ArgumentParser(description=__doc__)
argparser.add_argument(
"--pylon",
Expand All @@ -39,13 +41,19 @@ def main():
camera_data = trifinger_cameras.camera.SingleProcessData()
# camera_data = trifinger_cameras.camera.MultiProcessData("cam", True, 10)

if args.pylon:
camera_driver = trifinger_cameras.camera.PylonDriver(args.camera_id)
else:
camera_id = int(args.camera_id) if args.camera_id else 0
camera_driver = trifinger_cameras.camera.OpenCVDriver(camera_id)
try:
if args.pylon:
camera_driver = trifinger_cameras.camera.PylonDriver(
args.camera_id
)
else:
camera_id = int(args.camera_id) if args.camera_id else 0
camera_driver = trifinger_cameras.camera.OpenCVDriver(camera_id)
except Exception as e:
print("Failed to initialise driver:", e)
return 1

camera_backend = trifinger_cameras.camera.Backend( # noqa
camera_backend = trifinger_cameras.camera.Backend( # noqa: F841
camera_driver, camera_data
)
camera_frontend = trifinger_cameras.camera.Frontend(camera_data)
Expand All @@ -68,6 +76,8 @@ def main():
print("Save recorded data to file {}".format(args.record))
logger.stop_and_save(args.record)

return 0


if __name__ == "__main__":
main()
sys.exit(main())
10 changes: 5 additions & 5 deletions demos/demo_tricamera.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
and if desired, store the timestamps from them to analyse how well the three
cameras are in sync with each other.
"""

import argparse
import cv2
import pickle
Expand All @@ -12,7 +13,7 @@
from trifinger_cameras import utils


def main():
def main() -> None: # noqa: D103
argparser = argparse.ArgumentParser(description=__doc__)
argparser.add_argument(
"--store-timestamps",
Expand Down Expand Up @@ -42,7 +43,7 @@ def main():
camera_driver = trifinger_cameras.tricamera.TriCameraDriver(
*camera_names
)
camera_backend = trifinger_cameras.tricamera.Backend( # noqa
camera_backend = trifinger_cameras.tricamera.Backend( # noqa: F841
camera_driver, camera_data
)

Expand All @@ -67,9 +68,8 @@ def main():
)

if args.store_timestamps:
pickle.dump(
observations_timestamps_list, open(args.store_timestamps, "wb")
)
with open(args.store_timestamps, "wb") as f:
pickle.dump(observations_timestamps_list, f)


if __name__ == "__main__":
Expand Down
81 changes: 81 additions & 0 deletions doc/configuration.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
.. _configuration:

*************
Configuration
*************

Some parameters of the Pylon driver classes can be configured via a TOML configuration
file.

Configuration Options
=====================

The configuration file has to be in TOML format. Below is an overview of the supported
sections/settings and their default values. All settings are optional. If not
specified the default values are used.

.. code-block:: toml

[pylon_driver]
pylon_settings_file = "path/to/default_pylon_camera_settings.txt"

[tricamera_driver]
frame_rate_fps = 10.0


pylon_driver
------------

Settings concerning all Pylon cameras.

.. list-table::

* - ``pylon_settings_file``
- Path to the file containing the settings for the Pylon SDK (see
:ref:`pylon_settings_file`). If not set, the default settings file shipped with
this package is used (see :ref:`default_pylon_camera_settings`).


tricamera_driver
----------------

Settings specific to :cpp:class:`~trifinger_cameras::TriCameraDriver`.

.. list-table::

* - ``frame_rate_fps``
- Frequency at which frames are fetched from the cameras. **Important:** This is
limited by the ``AcquisitionFrameRate`` setting in the
:ref:`pylon_settings_file`, i.e. make sure to set ``AcquisitionFrameRate >=
frame_rate_fps``.


How to use the custom configuration
===================================

To use the file, simply write the path to the environment variable
``TRIFINGER_CAMERA_CONFIG``.

Alternatively, if you instantiate the :cpp:class:`~trifinger_cameras::PylonDriver` or
:cpp:class:`~trifinger_cameras::TriCameraDriver` classes in your own code, you can create a
:cpp:class:`~trifinger_cameras::Settings` instance (specify the path to the TOML file in the constructor)
and pass this to the constructor of the driver class.


.. _pylon_settings_file:

Pylon Settings
==============

The driver for Pylon cameras uses the Pylon SDK, which allows configuration of camera
settings like frame rate, white balancing, etc.
These settings are stored in a file, which is loaded by the
:cpp:class:`~trifinger_cameras::PylonDriver` class during initialisation. The path to
this file can be configured through the ``pylon_settings_file`` setting (see above).

This package ships with a default settings file (see
:ref:`default_pylon_camera_settings`). For simple changes like adjusting the frame
rate, you may simply copy that file and change the corresponding values.
For more complex changes, it is recommended to use the graphical interface of the
Pylon Viewer application (part of the SDK) and then save the settings to a file using
:ref:`executable_pylon_dump_camera_settings`.
Loading
Loading