cameramodels.stereo_camera.StereoCameraModel

class cameramodels.stereo_camera.StereoCameraModel(left=None, right=None)[source]

A Stereo Camera Model

Parameters:

Methods

static from_camera_info(left_camera_info_msg, right_camera_info_msg)[source]

Return StereoCameraModel from camera info msgs.

Parameters:
  • left_camera_info_msg (sensor_msgs.msg.CameraInfo) – left message of camera info.

  • right_camera_info_msg (sensor_msgs.msg.CameraInfo) – right message of camera info.

Returns:

cameramodel – stereo camera model

Return type:

cameramodels.StereoCameraModel

static from_yaml_file(left_yaml, right_yaml)[source]

Create instance of StereoCameraModel from yaml file.

This function is supporting sensor_msgs/CameraInfo’s YAML format in ROS.

left_depth_to_right_depth(depth)[source]

Return right camera depth image from left camera depth image.

Parameters:

depth (numpy.ndarray) – depth image in meters.

Returns:

right_depth – right camera’s depth image in meters.

Return type:

numpy.ndarray

points_from_keypoints(left_uv, right_uv, return_pixel_error=False)[source]

Calculate points from left and right camera’s keypoints.

Parameters:
  • left_uv (numpy.ndarray or tuple) – (x, y) coordinates.

  • right_uv (numpy.ndarray or tuple) – (x, y) coordinates.

  • return_pixel_error (bool) – if True, teturns the distance between the reprojected point and the input point.

Returns:

points – (x, y, z) points.

Return type:

numpy.ndarray

update_q()[source]

Update variable fields of reprojection matrix

From Springer Handbook of Robotics, p. 524:

\[\begin{split}P = \left( \begin{array}{cccc} f_x & 0 & c_x & 0 \\ 0 & f_y & c_y & 0 \\ 0 & 0 & 1 & 0 \end{array} \right)\end{split}\]
\[\begin{split}P' = \left( \begin{array}{cccc} f_x & 0 & c'_x & f_x T_x \\ 0 & f_y & c_y & 0 \\ 0 & 0 & 1 & 0 \end{array} \right)\end{split}\]

where primed parameters are from the left projection matrix, unprimed from the right.

[u   v 1]^T = P  * [x y z 1]^T
[(u-d) v 1]^T = P' * [x y z 1]^T

Combining the two equations above results in the following equation

[u v u-d 1]^T = [ Fx   0    Cx   0    ] * [ x y z 1]^T
                [ 0    Fy   Cy   0    ]
                [ Fx   0    Cx'  FxTx ]
                [ 0    0    1    0    ]

Subtracting the 3rd from from the first and inverting the expression results in the following equation.

[x y z 1]^T = Q * [u v d 1]^T

Where Q is defined as

\[\begin{split}Q = \left( \begin{array}{cccc} f_y T_x & 0 & 0 & -f_y c_x T_x \\ 0 & f_x T_x & 0 & -f_x c_y T_x \\ 0 & 0 & 0 & f_x f_y T_x \\ 0 & 0 & - f_y & f_y (c_x - c'_x) \end{array} \right)\end{split}\]

Using the assumption f_x = f_y Q can be simplified to the following. But for compatibility with stereo cameras with different focal lengths we will use the full Q matrix.

\[\begin{split}Q = \left( \begin{array}{cccc} 1 & 0 & 0 & -c_x \\ 0 & 1 & 0 & -c_y \\ 0 & 0 & 0 & f_x \\ 0 & 0 & -1/T_x & (c_x - c'_{x})/T_x \end{array} \right)\end{split}\]
\[Disparity = x_{left} - x_{right}\]

For compatibility with stereo cameras with different focal lengths we will use the full Q matrix.

__eq__(value, /)

Return self==value.

__ne__(value, /)

Return self!=value.

__lt__(value, /)

Return self<value.

__le__(value, /)

Return self<=value.

__gt__(value, /)

Return self>value.

__ge__(value, /)

Return self>=value.

Attributes

Q

Return Q matrix.

\[\begin{split}Q = \left( \begin{array}{cccc} 1 & 0 & 0 & -c_x \\ 0 & 1 & 0 & -c_y \\ 0 & 0 & 0 & f_x \\ 0 & 0 & -1/T_x & (c_x - c'_{x})/T_x \end{array} \right)\end{split}\]
Returns:

self._Q – Q matrix.

Return type:

numpy.ndarray

baseline

Return left to right baseline.

Currently assuming horizontal baseline

Returns:

baseline – left to right translation.

Return type:

float

left_camera

Getter of left camera.

Returns:

self._left_camera – left camera model

Return type:

cameramodels.PinholeCameraModel

right_camera

Getter of right camera.

Returns:

self._right_camera – right camera model

Return type:

cameramodels.PinholeCameraModel