3D相机9点标定使用范围

396 阅读3分钟

本文已参与「新人创作礼」活动,一起开启掘金创作之路。

9 点标定法


1 适用范围及情形

1.1      在机器人外固定安装的3D相机与机器人的手眼标定,相机等安装与固定支架上,不依赖与外部运动机构而自动获取3D图像的情形****

1.2      在机器人外部安装于运动机构上的3D相机与机器人的手眼标定,相机等安装于直线导轨单元上,由电机带着相机运动来获取3D图像;

1.3      相机安装于机器人第6轴上,相机由机器人轨迹驱动从而获取3D图像,但是机器人只需要带动相机在固定位置/轨迹获取图像,或者不需机器人频繁变换取图位置(只有有限几个取图路径),此时可以视作同情形1.2。

2 能做

2.1      允许如此安装的情形。

2.2      如果相机在机器人第6轴上安装并沿固定轨迹取图,精度要求不高的场合;具体视客户测试情况而定。

3 不能做

3.1      如果相机在机器人第6轴上安装并沿固定轨迹取图,精度要求过高;

4 示例作业

4.1     采用halcon与3D视觉进行九点标定;

image.png

image.png

image.png


dev_update_off ()
dev_set_color ('green')
* 打开新的窗口
dev_close_window ()
WindowWidth := 512
WindowHeight := 384
* 设置窗口
ImagesDir := '3d_machine_vision/hand_eye/robot_gripper_gray_'
dev_open_window (0, WindowWidth + 10, WindowWidth, WindowHeight, 'black', ImageWindowHandle)
dev_open_window (0, 0, WindowWidth, WindowHeight, 'black', WindowHandle)
set_display_font (WindowHandle, 14, 'mono', 'true', 'false')
set_display_font (ImageWindowHandle, 14, 'mono', 'true', 'false')
Instruction := ['Rotate: Left button','Zoom:   Shift + left button','Move:   Ctrl  + left button']
* 读取3D模型

read_object_model_3d ('hand_eye/robot_gripper_3d_model.om3', 1, [], [], OM3DModel, Status)
create_surface_model (OM3DModel, 0.03, [], [], SurfaceModelID)
Message := 'Surface model to be searched'
* 为了更好地显示,请减少模型的点密度。
sample_object_model_3d (OM3DModel, 'fast', 0.0009, [], [], SampledObjectModel3D)
visualize_object_model_3d (WindowHandle, SampledObjectModel3D, [], [], 'color_0', 'gray', Message, [], Instruction, PoseOut)
* 
NumCalibrationScenes := 15
*创建手眼校准的校准模型

*使用固定的3D传感器。由于未使用摄像机校准

*执行校准对象并直接设置姿势

*在模型中,摄像机数量和校准对象数量为0。
create_calib_data ('hand_eye_stationary_cam', 0, 0, HECCalibDataID)
*设置要使用的优化方法。
set_calib_data (HECCalibDataID, 'model', 'general', 'optimization_method', 'nonlinear')
* 
*确定观察模型对象的三维姿势

*在所有场景中使用基于曲面的匹配。
for I := 1 to NumCalibrationScenes by 1
    read_image (ImageRobotGripperGray, ImagesDir + I$'02d')
    read_pose ('tool_in_base_pose_' + I$'02d' + '.dat', ToolInBasePose)
    * 读取3D模型
    filename := 'hand_eye/robot_gripper_3d_scene_' + I$'02d'
    * 读取
    read_object_model_3d (filename, 1, [], [], OM3DScene, Status1)
    *在当前场景中查找曲面模型。
    find_surface_model (SurfaceModelID, OM3DScene, 0.05, 1, 0, 'false', [], [], ObjInCamPose, Score, SurfaceMatchingResultID)
    refine_surface_model_pose (SurfaceModelID, OM3DScene, ObjInCamPose, 0, 'false', [], [], ObjInCamPose, Score, SurfaceMatchingResultID1)
    if (|Score|)
     *仅当基于曲面的匹配结果为

*足够好了。
        set_calib_data (HECCalibDataID, 'tool', I, 'tool_in_base_pose', ToolInBasePose)
        set_calib_data_observ_pose (HECCalibDataID, 0, 0, I, ObjInCamPose)
    endif
 *要可视化在场景中发现模型的姿势,

*变换三维对象模型,以便可以将其覆盖到

*当前场景。
    pose_to_hom_mat3d (ObjInCamPose, HomMat3D)
    affine_trans_object_model_3d (SampledObjectModel3D, HomMat3D, OM3DModelTrans)
 *仅显示前三个场景的交互式三维可视化。
    if (I < 4)
        * Clear both windows.
        dev_clear_window ()
        dev_set_window (ImageWindowHandle)
        dev_display (ImageRobotGripperGray)
        disp_message (ImageWindowHandle, 'Image from pinhole camera', 'window', 12, 12, 'black', 'true')
        dev_set_window (WindowHandle)
        Message := 'Surface model is matched in the 3D scene.'
        Message[1] := 'Points of the current scene are gray.'
        Message[2] := 'Points of the matched model are green.'
        * For better visualization, reduce the point density of the model.
        sample_object_model_3d (OM3DScene, 'fast', 0.0009, [], [], SampledOM3DScene)
        disp_message (WindowHandle, Message, 'window', 12, 12, 'black', 'true')
        Message := 'Scene: '
        Message[1] := I + ' of ' + NumCalibrationScenes
        disp_message (WindowHandle, Message, 'window', 80, 12, 'white', 'false')
        * Visualize matching result with user interaction.
        visualize_object_model_3d (WindowHandle, [SampledOM3DScene,OM3DModelTrans], [], [], ['color_0','color_1','disp_background'], ['gray','green','true'], [], [], Instruction, PoseOut)
    else
        * Clear both windows.
        dev_clear_window ()
        dev_set_window (ImageWindowHandle)
        dev_clear_window ()
        dev_set_window (WindowHandle)
        if (I == 4)
            Message := 'In the following, the surface-based matching'
            Message[1] := 'result is shown using the 3D visualization '
            Message[2] := 'without user interaction.'
            disp_message (WindowHandle, Message, 'window', 12, 12, 'black', 'true')
            disp_continue_message (WindowHandle, 'black', 'true')
            stop ()
            dev_clear_window ()
        endif
        dev_set_window (ImageWindowHandle)
        dev_display (ImageRobotGripperGray)
        disp_message (ImageWindowHandle, 'Image from pinhole camera', 'window', 12, 12, 'black', 'true')
        dev_set_window (WindowHandle)
        * For better visualization, reduce the point density of the model.
        sample_object_model_3d (OM3DScene, 'fast', 0.0009, [], [], SampledOM3DScene)
        * Visualize matching result without user interaction.
        disp_object_model_3d_safe (WindowHandle, [SampledOM3DScene,OM3DModelTrans], [], [], ['color_0','color_1'], ['gray','green'])
        Message := 'Scene: ' + I + ' of ' + NumCalibrationScenes
        disp_message (WindowHandle, Message, 'window', 12, 12, 'white', 'false')
        disp_continue_message (WindowHandle, 'black', 'true')
        stop ()
    endif
endfor
* Check the input poses for consistency
check_hand_eye_calibration_input_poses (HECCalibDataID, 0.05, 0.005, Warnings)
if (|Warnings| != 0)
   *在输入姿势中检测到问题。检查警告和

*使用remove\u calib\u data和remove\u calib\u data\u observ删除错误姿势。
   dev_inspect_ctrl (Warnings)
    stop ()