projecting 3D points to image - acfr/snark GitHub Wiki

This tutorial shows how to project 3D points from camera frame to image pixels.

Sample data

To create sample data points representing a cube run following command:

cat <<eof > cube.csv
-1,-1,5,0
-1,1,5,1
1,-1,5,2
1,1,5,3
-1,-1,7,4
-1,1,7,5
1,-1,7,6
1,1,7,7
eof

view dataset:

view-points "cube.csv;fields=x,y,z,label;colour=white;weight=5"

Here is a sample config for camera:

cat <<EOF >config.json
{
    "sensor_size":
    {
        "x": "1.28",
        "y": "0.96"
    },
    "image_size":
    {
        "x": "1280",
        "y": "960"
    },
    "focal_length": "2",
    "principal_point":
    {
        "x": "645.4481811523438",
        "y": "469.3671875"
    },
    "distortion":
    {
        "radial":
        {
            "k1": "0",
            "k2": "0",
            "k3": "0"
        },
        "tangential":
        {
            "p1": "0",
            "p2": "0"
        },
        "map": ""
    }
}
EOF

Use following code to create axis.csv for viewing:

(echo "-100,0,0,100,0,0,0";echo "0,-100,0,0,100,0,1";echo "0,0,-100,0,0,100,2") >axis.csv

Project points in camera frame onto an image

Suppose we want to project the cube onto an image.

Project the points of the cube onto the image plane

Assume that the image is from a camera with focal distance 2 as specified in config.json. In camera frame, the focal point will have coordinates (0,0,0) and image plane could be defined by point (0,0,-2) and normal (0,0,1).

To project points onto image plane, run:

cat cube.csv | points-calc plane-intersection --fields=first --plane=0,0,-2,0,0,1 > projected.csv
view-points "cube.csv;colour=white;weight=5;fields=x,y,z,label"\
    <( echo 0,0,0,F )";colour=green;weight=10;fields=x,y,z,label"\
    "projected.csv;colour=yellow;weight=5;fields=,,,label,x,y,z" \
    "projected.csv;shape=line;colour=yellow;fields=first,id,second"

Convert the points on the image plane to pixel

To convert points from camera frame to image col,row and view use following command, with camera config sample above:

cat projected.csv | image-pinhole to-pixels --config=config.json --fields=,,,,x,y,z >pixels.csv
csv-to-svg header --width=1280 --height=960 --viewbox "0 0 1280 960" >pixels.svg
cat pixels.csv | csv-to-svg point --fields=,,,,,,,x,y --colour=blue >>pixels.svg
csv-to-svg footer >>pixels.svg

Project points in world frame onto an image

Using the cube.csv data created above, and assuming it to be in world frame, we want to first convert them to camera frame and then project them to image pixels

Convert points from world frame to camera frame

We use points-frame to map from world to camera in this example camera is at -10,-10,-10 in world frame with roll,pitch,yaw of 30,0,30 degrees. To convert the points and view:

cat cube.csv | points-frame --fields=x,y,z --from="$(echo "10,10,10,-30,0,-30" | csv-units --from degrees --to radians --fields=,,,roll,pitch,yaw)" > points.csv
echo "0,0,0,C" | view-points --fields=x,y,z,label --colour=yellow --weight=5 "points.csv;fields=x,y,z,label;colour=cyan;weight=5" "axis.csv;shape=line;fields=first,second,id"

Project the points onto the image plane

Assume that the image is from a camera with focal distance 0.4. In camera frame, the focal point will have coordinates (0,0,0) and image plane could be defined by point (0,0,-0.4) and normal (0,0,1).

To project points onto image plane, run:

cat "points.csv" | points-calc plane-intersection --fields=first --plane="0,0,-0.4,0,0,1" > projected.csv

to view projected points in world frame run these commands:

cat "projected.csv" | points-frame --fields="x,y,z" --to="$(echo "10,10,10,-30,0,-30" | csv-units --from degrees --to radians --fields=,,,roll,pitch,yaw)"  \
    | points-frame --fields=",,,,x,y,z" --to="$(echo "10,10,10,-30,0,-30" | csv-units --from degrees --to radians --fields=,,,roll,pitch,yaw)" >"projected-world.csv"

view-points "cube.csv;colour=white;weight=5;fields=x,y,z,label"\
    <( echo 0,0,0,F | points_to_world )";colour=green;weight=10;fields=x,y,z,label"\
    "projected-world.csv;colour=yellow;weight=5;fields=,,,label,x,y,z" \
    "projected-world.csv;shape=line;colour=yellow;fields=first,id,second"\
    "axis.csv;shape=line;fields=first,second,id"

To convert points from camera frame to image col,row and view use following command, with camera config sample above:

cat projected.csv | image-pinhole to-pixels --config=config.json --fields=,,,,x,y,z >pixels.csv
csv-to-svg header --width=1280 --height=960 --viewbox "0 0 1280 960" >pixels.svg
cat pixels.csv | csv-to-svg point --fields=,,,,,,,x,y --colour=blue >>pixels.svg
csv-to-svg footer >>pixels.svg

A real-life example

This example maps lidar 3D points to camera image and views them as overlay
The data files are available from:
http://perception.acfr.usyd.edu.au/data/samples/tutorial/points-project.zip
which contains velodyne.bin (lidar sample data), a png file from cameras, distortion map file for each of the the six cameras, and a config.json file describing the cameras.

config.json

This configuration file config.json is used for following examples.

Translate from lidar to camera framework

Camera position and relative rotation is available in config.json for each camera. First we translate from lidar to camera framework using points-frame

source $(which comma-application-util)
comma_path_value_to_var --prefix=config < <(cat config.json | name-value-convert --from=json --to=path-value) 
cat velodyne.bin | points-frame --binary="t,5d,2ui,t" --fields=",x,y,z" --from="$config_velodyne_offset" --to="$config_ladybug_offset" --discard >tmp.bin

Project points to pixel

Following function will project 3D points from world frame to pixels for a particular camera. There are six cameras to provide round view. The function parameter is camera number (between 0 and 5).
It first converts to this particular cameras frame work then (removing points behind the camera) projects them through camera using plane-intersection and the focal point. The plane is specified as perpendicular to z axis and at focal_length (in pixels) distance from focus point (0,0,0 in camera frame).
Then it converts from 3D to pixel row,col and using image-pinhole to-pixels which also distorts the image using distortion map file. Finally it offsets the pixels based on camera number for the final viewing as a mosaic.

function project_to_pixels()
{
    local i="$1"
    format="t,5d,2ui,t"
    fields=",x,y,z"
    offset="config_ladybug_camera_${i}_offset"
    focal_length="config_ladybug_camera_${i}_focal_length"
    echo "cam offset: ${!offset} focal length ${!focal_length}" >&2
    points-frame --binary="$format" --fields="$fields" --to="${!offset}" \
        | csv-select --binary="$format" --fields=,,,z "z;greater=0" \
        | points-calc plane-intersection --binary="$format" --fields=",first/y,first/x,first/z" --plane="0,0,${!focal_length},0,0,1" \
        | image-pinhole to-pixels --binary="$format,3d" --fields=",,,,,,,,,x,y,z" --config="config.json#ladybug/camera-${i}" --clip --verbose \
        | csv-shuffle --binary="$format,5d" --fields=t,,,z,,,,,,,,,y,x --output=t,x,y,z \
        | points-frame --binary="t,3d" --fields=,x,y --to="$(bc <<< "(${i}-1) * -1232"),0,0,0,$(math-deg2rad 180),0"
}

Putting it all together

This script calls point project for each camera and views them on top of the image. The points are overlaid on the image and each points colour indicates its distance from the camera.

rm projected
for i in {0..5}; do
    echo new $i
    cat tmp.bin | project_to_pixels $i >>projected
done

echo -6160,0,5,0,0,0  \
    | view-points "projected;binary=t,3d;fields=,x,y,scalar;point-size=3;colour=2:20,hot"\
    "-;fields=x,y,z,roll,pitch,yaw;shape=20130813T035249.990303.png,1"

⚠️ **GitHub.com Fallback** ⚠️