• Stars
    star
    161
  • Rank 233,470 (Top 5 %)
  • Language
    C++
  • License
    MIT License
  • Created over 3 years ago
  • Updated over 1 year ago

Reviews

There are no reviews yet. Be the first to send feedback to the community and the maintainers!

Repository Details

image_projection is a ROS package to create various projections from multiple calibrated cameras.

image_projection

Overview

image_projection is a ROS package to create various projections from multiple calibrated cameras. Use cases involve:

  • Rectify a distorted image
  • Create a cylindrical projection (equirectangular, mercator ..) from 360° camera data from multiple cameras
  • Create a perspective (pinhole) projection from fisheye camera data
  • Convert non-linear fisheye data to an ideal fisheye lense ("tru-theta")
  • Define a virtual pan-tilt camera

Available projection targets are:

  • Pinhole / perspective projection
  • Mercator projection
  • Ideal fisheye projection

Projections can be created periodically or on-demand. All projection parameters including image dimensions and position/direction can be configured dynamically at runtime. All cameras have to be calibrated beforehand.

A demo launch configuration is available below.

Author/Maintainer: Martin Oehler
Affiliation: TU Darmstadt, SIM
License: MIT

Examples

Insta 360 Air Low cost 360° camera with two fisheye lenses pointing in opposite directions

Source Images Pinhole projection Mercator projection

Boston Dynamics Spot 5 pinhole cameras, 2 at the front, 2 at the sides and 1 at the rear

Source Images Pinhole projection Mercator projection

Citation

Please cite our paper if you use this software as part of your scientific publication:

@INPROCEEDINGS{oehler2021flexible,
  author={Oehler, Martin and von Stryk, Oskar},
  booktitle={2021 European Conference on Mobile Robots (ECMR)}, 
  title={A Flexible Framework for Virtual Omnidirectional Vision to Improve Operator Situation Awareness}, 
  year={2021}
}

Installation

If you haven't already installed it, install ROS. Please use Desktop-Full Install to run the demo. Noetic is officially supported, but Melodic and Kinetic should work as well.

Create a new catkin workspace. Skip this step if you use your existing workspace.

source /opt/ros/noetic/setup.bash
mkdir -p catkin_ws/src
cd catkin_ws/
catkin init

Go into the source directory of your workspace and check out image_projection

cd src/
git clone https://github.com/tu-darmstadt-ros-pkg/image_projection.git

Install dependencies via rosdep and wstool (.rosinstall)

cd image_projection
rosdep install --from-paths . --ignore-src -r -y
wstool init ../.. # not required if already initialized
wstool merge image_projection_https.rosinstall
wstool update

Build

catkin build image_projection_demo

and source the workspace

source ../../devel/setup.bash

Verify your installation by launching the demo (see below).

Getting started

Launching the demo

Make sure to open a new terminal after building the project for the first time.

Start by downloading the demo bag file with

roscd image_projection_demo/bags/
wget https://www.sim.informatik.tu-darmstadt.de/~oehler/insta360_air_robocup2018.bag

Launch the demo with

roslaunch image_projection_demo demo_insta360.launch

An rqt window with the source video and projection examples will open. The rqt_reconfigure GUI on the right side can be used to change projection parameters at runtime.

Setting up your own projection

To use image_projection for your robot, you will need to update camera topics, calibration and projection parameters. You can duplicate the launch and configuration files in the demo and adapt them to your robot.

The main launch file is image_projection_demo/launch/projections.launch. It loads the configuration, calibration and starts up the projection nodelets. Cameras are configured in image_projection_demo/config/camera360_cameras.yaml. This setup uses an extended camera calibration from kalibr. Projections are configured in image_projection_demo/config/projections.yaml.

Lastly, make sure that your cameras are properly calibrated. For calibration instructions, refer to the section "Camera calibration" below.

Camera calibration

The following calibration formats are supported:

  • sensor_msgs/CameraInfo is the ROS standard camera calibration for pinhole cameras. It can be created with camera_calibration. Normally, the calibration file is loaded by the camera driver and published on /[camera_name]/camera_info.

  • kalibr_image_geometry_msgs/ExtendedCameraInfo is an extended calibration format with additional support for fisheye cameras. The format is based on calibrations with kalibr. The extended calibration can be published with the node kalibr_extended_camera_info_publisher/camera_info_publisher_node on topic /[camera_name]/extended_camera_info. You can see an example in image_projection_demo/launch/calibration_publisher.launch. The node needs the calibration as a YAML file, you can see the format in image_projection_demos/config/insta360_3_omni_radtan_calibration/camera360_right.yaml. The information has to be filled in from the kalibr calibration file.

Insights

Method

image_projection projects multiple cameras onto 3D projection surfaces. The shapes of the projection surfaces are parameterized and depend on the chosen projection. A pinhole projection uses a planar projection surfaces, cylindrical projections, e.g. Mercator, use, as the name suggests, a cylindrical surface. The surfaces are generated inside the scene with a pixel grid of the chosen target resolution. Each surface pixel is projected into every camera to retrieve color information. If the projected pixel is valid (inside the image) in more than one camera, the best match is chosen based on a heuristic. Pixels close to the respective image center are preferred.

Initially, a projection map is computed as described above. This step is rather costly and has to be repeated each time parameters are changed. The projection itself is comparatively cheap and implemented as a remap for each camera onto the same target image.

Stitching Seams

Typically, projections with multiple camera sources show stitching seams. These seams are due to the fact, that camera centers to not coincide. With a wider baseline between the two cameras, more artifacts will be visible. Reversely, stitching quality improves if baselines are small. The effect can be mitigated by moving the projection surface to the typical distance of surrounding objects. Another common approach to eliminate stitching seams is blending, which might get integrated in the future. However, this can lead to ghosting artifacts.

Nodes (Nodelets)

All nodes also come in nodelet variants (name in brackets) and are implemented as lazy subscribers.

periodic_image_projection_node (image_projection/PeriodicImageProjectionNodelet)

This node/nodelet periodically publishes a projected image from the latest camera data. All projection parameters can be configured dynamically at runtime. No computation is performed, if the output topic is not subscribed.

Subscribed Topics

  • /[camera_ns]/image_raw (sensor_msgs/Image)

    The source camera images. camera_ns refers to the configured cameras (see ~cameras parameter).

  • /[camera_ns]/camera_info (sensor_msgs/CameraInfo)

    Camera calibration. Make sure that only camera_info or extended_camera_info are published, never both.

  • /[camera_topic]/extended_camera_info (kalibr_image_geometry_msgs/ExtendedCameraInfo)

    Extended calibration info for calibration with kalibr. Make sure that only camera_info or extended_camera_info are published, never both.

  • ~set_pose (geometry_msgs/Pose)

    Set the pose of the virtual sensor frame relative to ~base_frame. Can be used to implement a virtual pan-tilt sensor head by updating the sensor pose based on joystick feedback.

  • /tf and /tf_static (tf2_msgs/TFMessage)

    tf2 is used to retrieve the transformations between each camera's optical frame and the projection base_frame.

Published Topics

  • ~projection (sensor_msgs/Image)

    Projected image.

  • ~camera_info (sensor_msgs/CameraInfo)

    In case of the image_projection_plugins::PinholeProjection plugin, the camera info of the projection is published on this topic if the parameters virtual_sensor_frame and virtual_sensor_optical_frame are set.

Services

  • ~project_pixel_to_ray ([image_projection_msgs/ProjectPixelTo3DRay])

    Can be called with the x/y-coordinates of a pixel in the projection and will return the corresponding 3D ray into the scene in base_frame.

Parameters

  • ~update_rate (double, default: 1.0)

    Publishing frequency of the projected image

  • ~base_frame (string, mandatory)

    Name of the tf frame in which the pose of the projection surface is defined.

  • ~virtual_sensor_frame (string, default: "")

    If set, this frame will be broadcasted to tf at the pose of the virtual sensor frame.

  • ~virtual_sensor_optical_frame (string, default: "")

    If set, this frame will be broadcasted to tf at the pose of the virtual sensor optical frame.

  • ~pose (list[double, default: [0, 0, 0, 0, 0, 0])

    Pose of the virtual sensor frame (also see ~virtual_sensor_frame) relative to ~base_frame. List with 6 entries in the order x, y, z, roll, pitch, yaw.

  • ~projection_type (string, mandatory)

    Name of a projection plugin (see below "Projection plugins")

  • ~projection_parameters/image_width (int, mandatory)

    Image width of the output projection.

  • ~projection_parameters/image_height (int, mandatory)

    Image height of the output projection.

  • ~projection_parameters (dict)

    Place parameters of the projection plugin in this namespace. For info on available parameters, see "Projection plugins" below.

  • ~always_recompute_mapping (bool, default: false)

    Forces a map update in each cycle instead of only when changes occurred. This can be used to achieve a uniform latency of the projection.

  • ~cameras (list[string], mandatory)

    List of camera namespaces to be used for projections. The camera namespace is the base namespace of your image and camera info topic; e,g, if your camera publishes the topics /camera/image_raw and /camera/camera_info, the camera namespace is /camera.

  • [camera_ns]/image_topic (string, default: "image_raw")

    Configure the camera topic for each camera.

  • [camera_ns]/camera_info_topic (string, default: "camera_info")

    Configure the camera info for each camera.

  • [camera_ns]/extended_camera_info_topic (string, default: "extended_camera_info")

    Configure the extended camera info topic for each camera.

image_projection_server_node

Not yet implemented. This node creates projections on-demand as a service.

Projection plugins

Projections are implemented as plugins. The following plugins are available:

image_projection_plugins::PinholeProjection

Creates a virtual perspective (pinhole) camera by creating a 3D plane. The camera points towards the x-axis in the camera frame and towards the z-axis in the optical frame (ROS standard).

Parameters

  • ~projection_parameters/focal_length (double, 1.0)

    Focal length of the simulated pinhole camera in meters.

  • ~projection_parameters/horizontal_fov (double, 90.0)

    Horizontal field of view in degree. Vertical field of view is calculated based on aspect ratio to enforce square pixels.

Published Topics

image_projection_plugins::MercatorProjection

The Mercator projection creates a virtual 3D cylinder projection surface.

Parameters

  • ~projection_parameters/cylinder_radius (double, 1.0)

    Radius of the cylinder in meters.

  • ~projection_parameters/vertical_fov (double, 1.0)

    Vertical field of view of the projection. This determines the height of the cylinder.

image_projection_plugins::IdealFisheyeProjection

Generates an ideal ("tru-theta") fisheye image by creating a 3D sphere. An ideal fisheye image has a linear relationship between pixel distance from image center to corresponding light ray. Most real fisheye lenses do not achieve this.

Parameters

  • ~projection_parameters/sphere_radius (double, 1.0)

    Radius of the sphere in meters.

  • ~projection_parameters/fov (double, 1.0)

    Horizontal and vertical field of view of the fisheye in degree.

Planned features

  • GPU support (OpenGL/CUDA)
  • Image blending

More Repositories

1

hector_slam

hector_slam contains ROS packages related to performing SLAM in unstructed environments like those encountered in the Urban Search and Rescue (USAR) scenarios of the RoboCup Rescue competition.
C++
581
star
2

hector_quadrotor

hector_quadrotor contains packages related to modeling, control and simulation of quadrotor UAV systems.
C++
358
star
3

hector_gazebo

hector_gazebo provides packages related to the simulation of robots using gazebo (gazebo plugins, world files etc.).
C++
160
star
4

hector_navigation

hector_navigation provides packages related to navigation of unmanned vehicles in USAR environments.
C++
121
star
5

hector_localization

The hector_localization stack is a collection of packages, that provide the full 6DOF pose of a robot or platform.
C++
76
star
6

hector_models

hector_models contains (urdf) models of sensors and robot components.
CMake
57
star
7

hector_vision

Vision related packages developed within Team Hector/TU Darmstadt
C++
26
star
8

mapstitch

C++
24
star
9

hector_calibration

ROS packages related to calibration of robots and subsystems (cameras, LIDAR, kinematics)
C++
22
star
10

color_cloud_from_image

Color point cloud data from camera images
C++
19
star
11

sbpl_lattice_planner

Fork of sbpl_lattice_planner used by Team Hector
C++
17
star
12

ublox

Provides a ublox_gps node for uBlox GPS receivers and message and serialization packages for the binary UBX protocol.
C++
16
star
13

ps4_stereo_camera

PS4 stereo camera driver using the V4L2 API.
C++
15
star
14

legged_locomotion_library

Repository including all instructions and tutorials how to use the legged locomotion library (L3)
Shell
14
star
15

hector_tracked_vehicles_common

Contains packages related to modeling different tracked vehicles used by Team Hector
CMake
12
star
16

workspace_scripts

Generic package bringing convenient scripts to work with ROS workspaces
Shell
10
star
17

hector_nist_arenas_gazebo

hector_nist_arenas_gazebo provides means for the fast and convenient creation of test scenarios involving parts like those used for NIST standard test methods for response robots.
C++
10
star
18

vehicle_controller

Controller for wheeled and tracked vehicles
C++
9
star
19

cartographer_hector_tracker

Provides Taurob Tracker (Team Hector variant) integration for Cartographer.
Lua
9
star
20

hector_laserscan_to_pointcloud

Converts LIDAR data to pointcloud, optionally performing high fidelity projection and removing scan shadow/veiling points in the process
C++
9
star
21

3d_coverage_path_planning

Global path planning that generates an optimal path for an autonomous mobile ground robot to cover a prior 3D mesh model with a sensor payload. Code to the paper "3D Coverage Path Planning for Efficient Construction Progress Monitoring." in IEEE SSRR 2022.
C++
9
star
22

cpp_introspection

C++
7
star
23

hector_small_arm_common

ROS Packages used for the small lightweight Dynamixel RX motor based arm used by Team Hector
CMake
6
star
24

hector_camera_control

Packages related to controlling an pan/tilt camera head (output to ros_control based controllers)
C++
6
star
25

affw_control

Adaptive feed-forward controller for mobile platforms
C++
6
star
26

hector_rviz_overlay

C++
6
star
27

rosmatlab

A stack to enable interoperability between ROS and Matlab/Simulink
C++
6
star
28

hector_cloud_image_proc

Packages related to processing cloud data as (depth) images. Uses both PCL and OpenCV.
C++
5
star
29

taurob_tracker_common

Taurob tracker related common files (including URDF model) analogous to pr2_common
CMake
5
star
30

navigation_collision_checker

Provides a package that checks for environment collision with octomap data during navigation of mobile robots
C++
5
star
31

grid_map_2d_mapper

Simple 2D mapping with known poses using the grid_map library
C++
5
star
32

grid_map_navigation_planner

Grid map based navigation planner and tools
C++
5
star
33

hector_stairs_planner

Planner and associated packages for climbing stairs with (tracked) robots.
C++
5
star
34

topic_proxy

topic_proxy implements a ROS service server and client to pull single messages from one master and optionally republish them locally.
C++
5
star
35

hector_trac_ik

Fork of trac_ik mainly for use with manipulators with less than 6 DOF
C++
5
star
36

hector_vehicle_launch

Repository for high level launch files used by Team Hector
CMake
4
star
37

blob_tools

blob provides a new message type blob/Blob for binary data.
C++
4
star
38

sdf_contact_estimation

Accurate pose prediction based on Signed Distance Fields for mobile ground robots in rough terrain.
C++
4
star
39

hector_tracker_gazebo

Taurob tracker setup for Gazebo simulation as used by Team Hector. This might depend on some non-public repositories.
CMake
4
star
40

hector_ground_truth_gazebo_plugins

Obtain a ground truth from your gazebo world
C++
4
star
41

rotation_aware_traversability_path_planning

Rotation-aware Traversability Path Planning is based on the Legged Locomotion Library (L3). It extends L3 in the following ways: Plugins that consider traversability during path planning; Configs allowing the use of Boston Dynamics' Spot in L3; Conversion of resulting L3 step plans into Follow Path Actions.
C++
4
star
42

hector_radiation_mapping

2D and 3D radiation mapping for mobile robots.
C++
3
star
43

hector_teleop

Packages related to teleoperation of robots
C++
3
star
44

l3_footstep_planning

C++
3
star
45

grid_map_proc

Various grid map processing functionality
C++
3
star
46

move_base_lite

Experimental move_base substitute that aims at reducing complexity
C++
3
star
47

moveit_kinematics_plugin_benchmark

Tools for benchmarking moveit kinematics plugins
C++
3
star
48

hector_turtlebot

hector_turtlebot contains packages related to simulating Turtlebots as used by Team Hector (for example with additional LIDAR sensors)
C++
3
star
49

hector_multisensor_head_driver

Provides bringup system for the (real) hector_multisensor_head
CMake
3
star
50

pose_to_pose_with_covariance

Converts a geometry_msgs/PoseStamped to geometry_msgs/PoseWithCovarianceStamped with fixed covariance.
CMake
3
star
51

hector_quadrotor_apps

hector_quadrotor_apps contains demo packages that demonstrate the usage of the hector_quadrotor stack together with other useful stacks and packages.
3
star
52

hector_worldmodel

The hector_worldmodel stack helps to collect and fuse information about objects in the world.
C++
2
star
53

hector_tracker_robot

Hector Tracker specific components that are used in bringing up a robot (analogous to pr2_robot)
CMake
2
star
54

robot_self_filter

C++
2
star
55

hector_rough_terrain_planning

Tools for planning over rough terrain
C++
2
star
56

dynamixel_workbench_ros_control

ros_control wrapper for dynamixel_workbench
C++
2
star
57

scan_matching_benchmark

C++
2
star
58

hector_quadrotor_experimental

hector_quadrotor_experimental contains experimental packages that are related to the hector_quadrotor stack.
2
star
59

hector_mpu6050_imu_driver

C++
2
star
60

hector_rqt_multiplot_config

Configuration and launch files for rqt_multiplot
CMake
2
star
61

hector_model_conversions

Packages related to the conversion of 3d models to different representations.
C++
2
star
62

mapstitch_data

Contains data for experimenting with map stitching
2
star
63

hector_pseye_camera

Camera driver (node and nodelet) for efficiently retrieving monochrome images from PS Eye cameras
C++
1
star
64

hector_cloud_proc

Packages related to cloud processing
C++
1
star
65

hector_senseair_s8_driver

Python
1
star
66

uxvcos

The Unmanned Vehicle Control System.
C++
1
star
67

l3_core

C++
1
star
68

hector_generic_rqt_widgets

rqt-based widget using generic message for common use cases
Python
1
star
69

hector_flexbe_behavior

Contains FlexBE behavior packages for Hector USAR robots
Python
1
star
70

e_stop_manager

The E-Stop Manager merges multiple E-Stop sources.
C++
1
star
71

hector_tracker_launch

High level launch files for the hector tracker robot
1
star
72

motion_editor

Tool for creating keyframe-based motions for robots.
Python
1
star
73

simox

Fork of https://gitlab.com/Simox/simox
C++
1
star
74

hector_dynamixel_ros_control_wrapper

C++
1
star
75

camera_model_loader

Camera model loader for (at this point) kalibr-based camera calibration
C++
1
star
76

hector_perception

Perception related ROS packages
C++
1
star
77

hector_visualization

The hector_visualization stack is a collection of packages that provide some sort of visualization add-ons, e.g. rviz plugins for message types used in other hector packages.
C++
1
star
78

environment_models

Provides generic (URDF) models of environments and elements that can be spawned into them (mainly for use with Gazebo).
CMake
1
star
79

autonomous_stair_traversal_tutorial

Repo providing a ROS workspace setup that allows for the simulation of a tracked robot capable of autonomous stair climbing
Shell
1
star
80

hector_diagnostics

Some helpers to diagnose the runtime behavior of nodes
Python
1
star
81

pointcloud_accumulator

Nodelet to build an ikd-Tree from incoming PointCloud messages to build a downsampled cloud of the complete environment.
C++
1
star
82

l3_terrain_modeling

C++
1
star
83

moveit_joystick_control

Direct end-effector control using a joystick based on the moveit inverse kinematics interface.
C++
1
star
84

hector_filter_nodelets

Filter chain nodelets based on [filters](http://wiki.ros.org/filters)
C++
1
star
85

hector_openni2_camera

Modified version of openni2_camera, that allows streaming of depth and rgb data with different rates. Also checks for platform movement before publishing via tf
C++
1
star
86

gazebo_ros_control_select_joints

Hardware interface that allows for selecting the controlled joints (unlike the standard default_robot_hw_sim which grabs all transmissions available in the model)
C++
1
star
87

robot_mesh_localization

Robust 3D localization of mobile robots in a building mesh using Lidar and depth sensors.
1
star
88

l3_navigation

C++
1
star
89

centaur_robot_tutorial

Repo containing a full simulation setup for a centaur type (humanoid upper body, tracked base) robot.
Shell
1
star