勇哥的实验:halcon眼在手上的九点标定(eye in hand)

这种是eye in hand,即眼在手上。

我们需要确定的是相机坐标系和机器人工具坐标系之间的关系。

image.png

(图1)



halcon手眼标定,是相机绑定在机器手的工具坐标系末端,同时对于机械手来说标定物是静态的。

这个时候要求两个位置的姿态:一个是CalObjInBasePose, 一个是ToolInCamPose

CalObjInBasePose是在机械基础坐标系下的标定物坐标系下的姿态

ToolInCamPose是在相机坐标系下的工具坐标系下的姿态

如图1所示,黄色框是指的相机的坐标系,蓝色框是指的机械手末端的工具坐标系,绿色框是机械手的基础坐标系,红色框的是标定物的坐标系。

以上每个坐标系如果想转换到另一个坐标系只需要做平移与旋转就可以做到。

一旦我们求得CalObjInBasePose和CalObjInBasePose,我们就可以求出标定物在机械手基础坐标系下的坐标,通过相机拍照后把像素转换为机械手坐标系下的坐标,因为相机和机械手坐标系的转换关系有了,通过相机可以求出世界坐标,这个世界坐标就是用标定板标出来的,它是用单相机标定方法求出来的。


标定的时候,标定板不动,机器手带着相机从不同的角度去拍标定板。

image.png

(图2)


image.png

(图3)


dev_update_off ()
* Directories with calibration images and data files
ImageNameStart := '3d_machine_vision/hand_eye/movingcam_calib3cm_'
DataNameStart := 'hand_eye/movingcam_'
NumImages := 14
read_image (Image, ImageNameStart + '00')
dev_close_window ()
get_image_size (Image, Width, Height)
dev_open_window (0, 0, Width, Height, 'black', WindowHandle)
dev_set_line_width (2)
dev_set_draw ('margin')
dev_display (Image)
set_display_font (WindowHandle, 14, 'mono', 'true', 'false')
ParamName := ['color_0','color_1','color_2','color_3','color_4','color_5','color_6','alpha_6']
ParamValue := ['red','green','blue','red','green','blue','white',0.7]
* Labels for the visualized 3D object models.
tuple_gen_const (7, '', Labels)
Labels[0] := 'Robot\'s Tool'
Labels[3] := 'Robot\'s Base'
Instructions[0] := 'Rotate: Left button'
Instructions[1] := 'Zoom:   Shift + left button'
Instructions[2] := 'Move:   Ctrl  + left button'
* Set size for 3D visualization in [m]
ArrowThickness := 0.005
ArrowLength := 0.05
gen_robot_tool_and_base_object_model_3d (ArrowThickness, ArrowLength, OM3DToolOrigin, OM3DBase)
* Load the calibration plate description file.
* Make sure that the file is in the current directory or
* in HALCONROOT/calib, or use an absolute path.
CalTabFile := 'caltab_30mm.descr'
*读相机初始内参,相当于读标定助手中那些像元大小的参数 
read_cam_par (DataNameStart + 'start_campar.dat', StartCamParam)
* 创建手眼标定的模型
*'hand_eye_moving_cam'就是眼在手上的模式
* 一个相机,一个标定板
create_calib_data ('hand_eye_moving_cam', 1, 1, CalibDataID)
* 这里设置面扫描,在halcon12里,这个的[]是参数‘area_scan_division’
set_calib_data_cam_param (CalibDataID, 0, [], StartCamParam)
* 把标定板的描述文件上设置到这个标定模形中去
set_calib_data_calib_object (CalibDataID, 0, CalTabFile)
* 设置优化方法
set_calib_data (CalibDataID, 'model', 'general', 'optimization_method', 'nonlinear')
disp_message (WindowHandle, 'The calibration data model was created', 'window', 12, 12, 'black', 'true')
disp_continue_message (WindowHandle, 'black', 'true')
stop ()

dev_open_window (0, Width + 10, Width, Height, 'black', WindowHandleR)
set_display_font (WindowHandleR, 14, 'mono', 'true', 'false')
for I := 0 to NumImages - 1 by 1
    *循环里面就是eye-in-hand模式下,标定板不动,机械手带着相机从各个角度拍标定板的过程
    *这里只是读取图片
    dev_set_window (WindowHandle)
    dev_clear_window ()
    read_image (Image, ImageNameStart + I$'02d')
    dev_display (Image)
    * Search for the calibration plate, extract the marks and the
    * pose of it, and store the results in the calibration data
    * The poses are stored in the calibration data model for use by
    * the hand eye calibration and do not have to be set explicitly
    find_calib_object (Image, CalibDataID, 0, 0, I, [], [])
    get_calib_data_observ_contours (Caltab, CalibDataID, 'caltab', 0, 0, I)
    get_calib_data_observ_points (CalibDataID, 0, 0, I, RCoord, CCoord, Index, PoseForCalibrationPlate)
    * Visualize the extracted calibration marks and the estimated pose (coordinate system)
    dev_set_color ('green')
    dev_display (Image)
    dev_display (Caltab)
    dev_set_color ('yellow')
    disp_cross (WindowHandle, RCoord, CCoord, 6, 0)
    dev_set_colored (3)
    disp_3d_coord_system (WindowHandle, StartCamParam, PoseForCalibrationPlate, 0.01)
    disp_message (WindowHandle, 'Extracting data from calibration image ' + (I + 1) + ' of ' + NumImages, 'window', 12, 12, 'black', 'true')
    * Read pose of tool in robot base coordinates (ToolInBasePose)
    *读取机械手基础坐标系下的工具坐标系下的姿态
    *所谓姿态就是平移旋转
    *即工具坐标坐标系相对于机械手基础坐标系之间的关系
    read_pose (DataNameStart + 'robot_pose_' + I$'02d' + '.dat', ToolInBasePose)
*     if (I == 0)
*         PoseIn := [-0.006,-0.296,12,178,2,270,0]
*     else
*         PoseIn := PoseOut
*     endif
    *rigid_trans_object_model_3d (OM3DToolOrigin, ToolInBasePose, OM3DTool)
    *visualize_object_model_3d (WindowHandleR, [OM3DTool,OM3DBase], [], PoseIn, ParamName, ParamValue, 'Position of robot tool coordinate system in robot base coordinate system', Labels, Instructions, PoseOut)
    * Set the pose tool in robot base coordinates in the calibration data model
    set_calib_data (CalibDataID, 'tool', I, 'tool_in_base_pose', ToolInBasePose)
endfor
dev_set_window (WindowHandleR)
dev_close_window ()
disp_message (WindowHandle, 'All relevant data has been set in the calibration data model', 'window', 12, 12, 'black', 'true')
disp_continue_message (WindowHandle, 'black', 'true')
stop ()
* Check the input poses for consistency
check_hand_eye_calibration_input_poses (CalibDataID, 0.05, 0.005, Warnings)
if (|Warnings| != 0)
    * There were problem detected in the input poses. Inspect Warnings and
    * remove erroneous poses with remove_calib_data and remove_calib_data_observ.
    dev_inspect_ctrl (Warnings)
    stop ()
endif
* 
* Perform the hand eye calibration and store the results to file
* The calibration of the cameras is done internally prior
* to the hand eye calibration
dev_display (Image)
disp_message (WindowHandle, 'Performing the hand-eye calibration', 'window', 12, 12, 'black', 'true')
*手眼标定算子,Errors是标定误差
calibrate_hand_eye (CalibDataID, Errors)
* Query the error of the camera calibration
*取标定误差
get_calib_data (CalibDataID, 'model', 'general', 'camera_calib_error', CamCalibError)
* Query the camera parameters and the poses
*取相机的内参
get_calib_data (CalibDataID, 'camera', 0, 'params', CamParam)
* Get poses computed by the hand eye calibration
get_calib_data (CalibDataID, 'camera', 0, 'tool_in_cam_pose', ToolInCamPose)
get_calib_data (CalibDataID, 'calib_obj', 0, 'obj_in_base_pose', CalObjInBasePose)
* Get the plane in base coordinate system pose by translating the
* CalObjInBasePose by the calibration object's thickness in the
* z-direction.
*set_origin_pose (CalObjInBasePose, 0, 0, 0.005, PlaneInBasePose)
try
    * Handle situation where user does not have the permission
    * to write in the current directory.
    * 
    * Store the camera parameters to file
    write_cam_par (CamParam, DataNameStart + 'final_campar.dat')
    * Save the hand eye calibration results to file
    write_pose (ToolInCamPose, DataNameStart + 'final_pose_cam_tool.dat')
    write_pose (CalObjInBasePose, DataNameStart + 'final_pose_base_calplate.dat')
    *write_pose (PlaneInBasePose, DataNameStart + 'final_pose_base_plane.dat')
catch (Exception)
    * do nothing
endtry
dev_display (Image)
* Display calibration errors
disp_results (WindowHandle, CamCalibError, Errors)
disp_continue_message (WindowHandle, 'black', 'true')
stop ()
* For the given camera, get the corresponding pose indices and calibration object indices
query_calib_data_observ_indices (CalibDataID, 'camera', 0, CalibObjIdx, PoseIds)
* 计算相机坐标系下标定板的姿态
* system via calibrated poses and the ToolInBasePose and visualize it.
* Set sizes for 3D visualization in [m]
CameraSize := 0.05
CameraConeLength := 0.3
get_calib_data (CalibDataID, 'calib_obj', 0, 'x', PX)
get_calib_data (CalibDataID, 'calib_obj', 0, 'y', PY)
get_calib_data (CalibDataID, 'calib_obj', 0, 'z', PZ)
gen_object_model_3d_from_points (PX, PY, PZ, OM3DObjectOrig)
rigid_trans_object_model_3d (OM3DObjectOrig, CalObjInBasePose, OM3DObject)
dev_open_window (0, Width + 10, Width, Height, 'black', WindowHandleR)
set_display_font (WindowHandleR, 14, 'mono', 'true', 'false')
ParamName := ['color_0','color_1','color_2','color_3','color_4','color_5','color_6','color_7','alpha_7','color_8','color_9','color_10','alpha_8','alpha_9','alpha_10','point_size']
ParamValue := ['red','red','green','blue','red','green','blue','white',0.7,'magenta','yellow','white',0.5,0.5,0.5,5]
* Labels for the visualized 3D object models.
tuple_gen_const (11, '', Labels)
Labels[0] := 'Calibration Object'
Labels[1] := 'Robot\'s Tool'
Labels[4] := 'Robot\'s Base'
Labels[8] := 'Camera'
//下面这个循环的意思是:已经相机坐标系和机械手末端坐标系的关系,和标定板坐标系和机械手基础坐标系之间的关系
//求出标定板坐标系和相机坐标系之间的关系。
for I := 0 to NumImages - 1 by 1
    dev_set_window (WindowHandle)
    dev_clear_window ()
    read_image (Image, ImageNameStart + I$'02d')
    dev_display (Image)
    * Obtain the pose of the tool in robot base coordinates used in the calibration.
    * The index corresponds to the index of the pose of the observation object.
    get_calib_data (CalibDataID, 'tool', PoseIds[I], 'tool_in_base_pose', ToolInBasePose)
    * Compute the pose of the calibration object relative to the camera
    calc_calplate_pose_movingcam (CalObjInBasePose, ToolInCamPose, ToolInBasePose, CalObjInCamPose)
    * Display the coordinate system
    dev_set_colored (3)
    disp_3d_coord_system (WindowHandle, CamParam, CalObjInCamPose, 0.01)
    Message := 'Using the calibration results to display '
    Message[1] := 'the coordinate system in image ' + (I + 1) + ' of ' + NumImages
    disp_message (WindowHandle, Message, 'window', 12, 12, 'black', 'true')
    gen_camera_and_tool_moving_cam_object_model_3d (ToolInCamPose, ToolInBasePose, CameraSize, CameraConeLength, OM3DToolOrigin, CamParam, OM3DCamera, OM3DTool)
    if (I == 0)
        PoseIn := [-0.006,-0.296,12,178,2,270,0]
    else
        PoseIn := PoseOut
    endif
    visualize_object_model_3d (WindowHandleR, [OM3DObject,OM3DTool,OM3DBase,OM3DCamera], [], PoseIn, ParamName, ParamValue, [], Labels, Instructions, PoseOut)
endfor
* Clear the data model
clear_calib_data (CalibDataID)
dev_set_window (WindowHandleR)
dev_close_window ()
* 
* After the hand-eye calibration the computed pose
* ToolInCamPose can be used in robotic grasping applications.
* To grasp an object with the robot, typically, its pose
* with respect to the camera is determined (which
* is simulated here by setting the object's pose to the
* pose of the calibration object)
ObjInCamPose := CalObjInCamPose
* If the tool coordinate system is placed at the gripper
* and a detected object ObjInCamPose shall be grasped
* (here the calibration object),
* the pose of the detected object relative
* to the robot base coordinate system has to be computed.
//姿态翻转,已知相机坐标系下工具坐标系的关系,转换为工具坐标系下相机坐标系下的关系。
pose_invert (ToolInCamPose, CamInToolPose)
//已经前两个姿态,求解第三个姿态
pose_compose (ToolInBasePose, CamInToolPose, CamInBasePose)
pose_compose (CamInBasePose, ObjInCamPose, ObjInBasePose)

以上标定完成后:

相机拍照把像素坐标转为机械手基础坐标系下的坐标,由机械手末端过来抓取,

这个过程会有移位,旋转,即x,y,u

因为知道相机坐标系和工具坐标系的关系,因此就知道了工具坐标系的旋转中心在哪里。




未完待续。。。。


--------------------- 

作者:hackpig

来源:www.skcircle.com

版权声明:本文为博主原创文章,转载请附上博文链接!


本文出自勇哥的网站《少有人走的路》wwww.skcircle.com,转载请注明出处!讨论可扫码加群:
  • 评论列表:

发表评论:

◎欢迎参与讨论,请在这里发表您的看法、交流您的观点。

会员中心
搜索
«    2024年4月    »
1234567
891011121314
15161718192021
22232425262728
2930
网站分类
标签列表
最新留言
    热门文章 | 热评文章 | 随机文章
文章归档
友情链接
  • 订阅本站的 RSS 2.0 新闻聚合
  • 扫描加本站机器视觉QQ群,验证答案为:halcon勇哥的机器视觉
  • 点击查阅微信群二维码
  • 扫描加勇哥的非标自动化群,验证答案:C#/C++/VB勇哥的非标自动化群
  • 扫描加站长微信:站长微信:abc496103864
  • 扫描加站长QQ:
  • 扫描赞赏本站:
  • 留言板:

Powered By Z-BlogPHP 1.7.2

Copyright Your skcircle.com Rights Reserved.

鄂ICP备18008319号


站长QQ:496103864 微信:abc496103864