Camera setup

The following applies to image version 0.15 and up. See previous version of the article (Russian only) for older images.

Computer vision modules (like ArUco markers and Optical Flow) require adjusting the camrea focus and set up camera position and orientation relative to the drone body.

Focusing the camera lens

In order to focus the camera lens, do the following:

  1. Open the live camera stream in your browser using web_video_server.
  2. Rotate the lens to adjust the image. Make sure the objects that are 2-3 m from the camera are in focus.
Focused image Unfocused image

Setting the camera position

Position and orientation of the main camera is set in the ~/catkin_ws/src/clever/clever/launch/main_camera.launch file:

<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>

This line describes how the camera is positioned relative to the drone body. Technically, it creates a static transform between the base_link frame ( which corresponds to the flight controller housing) and the camera (main_camera_optical) in the following format:

shift_x shift_y shift_z yaw_angle pitch_angle roll_angle

Camera frame (that is, frame of reference) is aligned as follows:

  • x points to the right side of the image;
  • y points to the bottom of the image;
  • z points away from the camera matrix plane.

Shifts are set in meters, angles are in radians. You can check the transform for correctness using rviz.

Presets for Clever

The presets for usual camera orientations are available in the main_camera.launch file. The images should help you choose the one that is right for you: the first one is how your drone will be displayed in rviz, the second is how the camera is actually mounted on the drone.

1. Camera faces downward, cable goes backward

<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>

2. Camera faces downward, cable goes forward

<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 1.5707963 0 3.1415926 base_link main_camera_optical"/>

3. Camera faces upward, cable goes backward

<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 0.07 1.5707963 0 0 base_link main_camera_optical"/>

4. Camera faces upward, cable goes forward

<node pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 0.07 -1.5707963 0 0 base_link main_camera_optical"/>

The selfcheck.py utility will describe your current camera setup in a human-readable fashion. Be sure to check whether this description corresponds to your actual camera position.

results matching ""

    No results matching ""