(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Webcam calibration

Description: Simple example for industrial extrinsic calibration using a webcam

Tutorial Level:

Requirements

Warning: Only works with webcams that either have a manual mechanical focus or allow to control focus via UVC.

Tutorial

All files mentioned below can be found at https://github.com/andreasBihlmaier/industrial_calibration_helpers/tree/master/webcam_tutorial.

  • Install https://github.com/ktossell/camera_umd

  • Create a launch file for your webcam (here webcam.launch):

    • <launch>
        <arg name="device" default="/dev/video0" />
        
        <group ns="logitech_c910">
          <node pkg="nodelet" type="nodelet" name="camera_process" args="manager" output="screen"/>
        
          <node name="logitech_c910_uvc" pkg="nodelet" type="nodelet" args="load uvc_camera/CameraNodelet /logitech_c910/camera_process" output="screen">
            <param name="camera_info_url" value="file://$(env HOME)/.ros/camera_info/logitech_c910.yaml" />
            <param name="device" value="$(arg device)" />
            <param name="width" value="800" />
            <param name="height" value="448" />
            <param name="format" value="yuyv" />
            <param name="fps" value="24" />
            <param name="power_line_frequency" value="50"/>
            <param name="auto_exposure" value="1" />
      
            <!-- Use this for webcams with UVC controllable focus (e.g. Logitech C910) -->
            <param name="auto_focus" value="0" />
            <param name="focus_absolute" type="int" value="0" />
      
            <!--
            <param name="exposure_absolute" value="75" />
            <param name="exposure_auto_priority" value="0" />
            <param name="auto_white_balance" value="0" />
            <param name="white_balance_temperature" value="2800" />
            <param name="brightness" value="-45" />
            <param name="contrast" value="16" />
            <param name="saturation" value="128" />
            <param name="hue" value="0" />
            <param name="gamma" value="100" />
            <param name="sharpness" value="3" />
            <param name="backlight_compensation" value="2" />
            <param name="gain" value="30" />
            <param name="auto_gain" value="0" />
            <param name="horizontal_flip" value="0" />
            <param name="vertical_flip" value="0" />
            -->
          </node>
        
          <include file="$(find image_proc)/launch/image_proc.launch">
            <arg name="manager" value="/logitech_c910/camera_process" />
          </include>
        </group>
      </launch>
  • Create yaml configuration files for industrial calibration:
    • Overview of coordinate systems
      • industrial_extrinsic_cal.png

    • target.yaml
      • We use a circle grid as target with 25mm sized circles in a 35mm grid.
        static_targets:
        - angle_axis_ax: 0.0
          angle_axis_ay: 0.0
          angle_axis_az: 0.0
          circle_dia: 0.025
          num_points: 35
          points:
          - pnt:
            - 0.0
            - 0.21000000000000002
            - 0.0
          - pnt:
            - 0.035
            - 0.21000000000000002
            - 0.0
          - pnt:
            - 0.07
            - 0.21000000000000002
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.21000000000000002
            - 0.0
          - pnt:
            - 0.14
            - 0.21000000000000002
            - 0.0
          - pnt:
            - 0.0
            - 0.17500000000000002
            - 0.0
          - pnt:
            - 0.035
            - 0.17500000000000002
            - 0.0
          - pnt:
            - 0.07
            - 0.17500000000000002
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.17500000000000002
            - 0.0
          - pnt:
            - 0.14
            - 0.17500000000000002
            - 0.0
          - pnt:
            - 0.0
            - 0.14
            - 0.0
          - pnt:
            - 0.035
            - 0.14
            - 0.0
          - pnt:
            - 0.07
            - 0.14
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.14
            - 0.0
          - pnt:
            - 0.14
            - 0.14
            - 0.0
          - pnt:
            - 0.0
            - 0.10500000000000001
            - 0.0
          - pnt:
            - 0.035
            - 0.10500000000000001
            - 0.0
          - pnt:
            - 0.07
            - 0.10500000000000001
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.10500000000000001
            - 0.0
          - pnt:
            - 0.14
            - 0.10500000000000001
            - 0.0
          - pnt:
            - 0.0
            - 0.07
            - 0.0
          - pnt:
            - 0.035
            - 0.07
            - 0.0
          - pnt:
            - 0.07
            - 0.07
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.07
            - 0.0
          - pnt:
            - 0.14
            - 0.07
            - 0.0
          - pnt:
            - 0.0
            - 0.035
            - 0.0
          - pnt:
            - 0.035
            - 0.035
            - 0.0
          - pnt:
            - 0.07
            - 0.035
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.035
            - 0.0
          - pnt:
            - 0.14
            - 0.035
            - 0.0
          - pnt:
            - 0.0
            - 0.0
            - 0.0
          - pnt:
            - 0.035
            - 0.0
            - 0.0
          - pnt:
            - 0.07
            - 0.0
            - 0.0
          - pnt:
            - 0.10500000000000001
            - 0.0
            - 0.0
          - pnt:
            - 0.14
            - 0.0
            - 0.0
          position_x: 0.0
          position_y: 0.0
          position_z: 0.0
          target_cols: 5
          target_frame: target_frame
          target_name: circlegrid__7x5__0_025__0_035
          target_rows: 7
          target_type: 1
          transform_interface: ros_lti

        For target coordinate system see https://github.com/ros-industrial/industrial_calibration/blob/hydro-devel/industrial_extrinsic_cal/targets/CalibrationTarget.png. The X-axis points right, the Y-axis upward and the Z-axis towards the camera: industrial_extrinsic_cal-target_coords.png

        The example target (PDF for printing and YAML for industrial_extrinsic_cal) can be created with the helper tools generate_circlegrid.py and generate_circlegrid_target.py. For this particular target:

      • ./generate_circlegrid.py 7x5 0.025 0.035 /tmp/print_target_without_scaling.pdf

      • ./generate_circlegrid_target.py 7x5 0.025 0.035 circlegrid__7x5__0_025__0_035.yaml

    • camera.yaml
      • static_cameras:
         -
            camera_name: logitech_c910
            camera_optical_frame: logitech_c910_optical_frame
            trigger: NO_WAIT_TRIGGER
            image_topic: /logitech_c910/image_rect_color
            angle_axis_ax: 0.0
            angle_axis_ay: 0.0
            angle_axis_az: 0.0
            position_x: 0.1
            position_y: 0.0
            position_z: 0.0
            transform_interface: ros_camera_housing_bti
            camera_housing_frame: logitech_c910_link
            camera_mounting_frame: world_frame
            focal_length_x: 580
            focal_length_y: 590
            center_x: 385
            center_y: 211
            distortion_k1: 0.0
            distortion_k2: 0.0
            distortion_k3: 0.0
            distortion_p1: 0.0
            distortion_p2: 0.0

        The webcam was intrinsically calibrated using camera_calibration.

      • TODO document difference between camera_info params and those of image_rect_color.
      • transform_interface:
        • name

          description

          ros_camera_housing_bti

          Use position_* and angle_* as initial transform between camera_mouting_frame and camera_housing_frame. Transformation between camera_housing_frame and camera_optical_frame must be provided externally.

          ros_camera_housing_cti

          Uses mutable_joint_state_publisher between camera_mouting_frame and camera_housing_frame. Other transformations are provided by xacro/URDF.

          TODO

          TODO

    • caljob.yaml
      • reference_frame: world_frame
        scenes:
        -
             scene_id: 0
             trigger: NO_WAIT_TRIGGER
             observations:
             -
                  camera: logitech_c910
                  target: circlegrid__7x5__0_025__0_035
                  roi_x_min: 0
                  roi_x_max: 800
                  roi_y_min: 0
                  roi_y_max: 448
                  cost_type: FixedCircleTargetCameraReprjErrorPK
        
        optimization_parameters: xx
      • cost_type
        • name

          optimized parameters

          description

          FixedCircleTargetCameraReprjErrorPK

          extrinsics

          TODO

          LinkCameraCircleTargetReprjError

          extrinsics, target_pose_params, point positions

          TODO

          LinkCameraCircleTargetReprjErrorPK

          extrinsics, target_pose_params

          TODO

          TODO

          TODO

      • optimization_parameters
        • TODO
  • Create launch file for industrial calibration (here extrinsic_calibration.launch)

    • <launch>
      
        <!-- Launch service which is called to to indicate scene is ready   -->
        <node pkg="industrial_extrinsic_cal" type="trigger_service" name="rosSceneTrigger" output="screen" />
      
        <!-- Adjust this for your actual setup -->
        <node pkg="tf" type="static_transform_publisher"
                       name="target_frame"
                       args="1.2 0.0 0.0  -1.57079 0.0 1.57079 world_frame target_frame 100" />
      
        <!-- *_optical_frame with same origin as *_link, but using OpenCV convention (z = forward) instead of ROS convention (x = forward) -->
        <node pkg="tf" type="static_transform_publisher" name="logitech_c910_optical_frame" 
                       args="0.0 0.0 0.0  -1.57079 0.0 -1.57079 logitech_c910_link logitech_c910_optical_frame 100" /> 
      
        <node pkg="industrial_extrinsic_cal" type="service_node" name="calibration_service_node" output="screen" >
          <param name="yaml_file_path" value="$(find webcam_tutorial)/yaml/" />
          <rosparam>
            camera_file: "camera.yaml"
            target_file: "target.yaml"
            cal_job_file: "caljob.yaml"
            store_results_package_name: "webcam_tutorial"
            store_results_file_name: "world_to_logitech_c910_tf_broadcaster.launch"
          </rosparam>
        </node>
      
      </launch>
  • Test setup and initial positions:
    • Target is located 1.2 m along x axis of world coordinate system. Initial, that is not calibrated, camera position is set at [0.1, 0, 0] in world coordinates. Real camera position is approximately [0.31, 0, 0].

      webcam_calibration_setup.jpg

      webcam_calibration2_initial.jpg

  • Start calibration job: rosservice call /calibration_service "{}"

    • Observe how the transformation between camera_mounting_frame (here: world_frame) and camera_housing_frame (here: logitech_c910_link) is updated.

      webcam_calibration2_final.jpg

  • Alternative using xacro, mutable_joint_state_publisher and transform_interface: ros_camera_housing_cti

    • TODO
  • TODO

Wiki: industrial_extrinsic_cal/Tutorials/Webcam_calibration (last edited 2018-08-24 14:36:02 by ManuelUfheil)