Acerca de BumblebeeXB3 y la recopilación de información relacionada con la conversión de calibración ojo-mano y la visualización de códigos

Hace mucho tiempo, quería ordenar los proyectos que había hecho en los últimos años, ahora solo hay tiempo para animarme, ¡vamos! YapethsDY


Permítanme presentarles brevemente la situación general del proyecto
: utilice el robot colaborativo multi-articulado de desarrollo propio Siasun + cámara Bumblebee XB3 (resolución 1024 * 768) + entorno de desarrollo VS2010 + Halcon 18.05. Modificar: 2020/7/13 agregar sistema de coordenadas de cámara


El primer paso es aclarar los sistemas de coordenadas BBX2 y BBX3

Método: Sostenga la clavija de la cámara en su mano y mire el conector 1394A de la cámara. El lado derecho es la cámara del ojo derecho, el lado izquierdo es la cámara del ojo izquierdo, la parte frontal de la cámara es la dirección Z positiva y el centro del ojo derecho alejado de la cámara del ojo izquierdo es la dirección X positiva. Luego, de acuerdo con la regla de la mano derecha, se puede determinar la dirección Y de la cámara.

  • Sistema de coordenadas involucrado
  1. Sistema de coordenadas de pieza
  2. Sistema de coordenadas de la herramienta
  3. Sistema de coordenadas de la cámara

Hay un sistema de coordenadas de imagen y un sistema de coordenadas de píxeles en el sistema de coordenadas de la cámara.

La cámara BumblebeeXB3 utilizada en este proyecto tiene el origen de las coordenadas en el centro del ojo derecho.

El formulario de calibración ojo-mano del segundo paso

Según si la cámara está fija con respecto al origen de la coordenada del robot, podemos dividirla en los dos modos siguientes:

  • Cámara fija (ojo a mano)
  • La cámara no está fija (ojo en mano)

El resultado final que necesitamos es obtener la relación de posición espacial entre la cámara y la herramienta, que es una matriz NOAP 4 * 4. Esto se puede hacer fijando la placa de calibración y cambiando la pose del robot para que la cámara dispare la placa de calibración varias veces en diferentes posiciones y ángulos. Calcular. (No puedo hacer dibujos, los dibujos son extractos)

  • La posición relativa de la cámara y la herramienta permanece sin cambios, y la matriz de cambio se establece como .
  • La relación de transformación del sistema de coordenadas de la herramienta al sistema estándar base también es cierta, sea la matriz de transformación .
  • Una vez que el robot se coloca en una posición de posicionamiento, el sistema de coordenadas de la pieza de trabajo también es constante en relación con el sistema de coordenadas de la base, y se establece una matriz de transformación .

 

Una vez calculada la relación de conversión entre la cámara y el sistema de coordenadas del robot, se pueden realizar las operaciones posteriores.


El tercer paso de la calibración ojo-mano

  • Obtener los parámetros internos de la cámara

Hay 8 parámetros relacionados con la calibración de la cámara: Focus, Kappa, Sy, Sx, Cx, Cy, ImageWidth, ImageHeight.

/// <summary>
/// 相机内参
/// 确定摄像机从三维空间到二维图像的投影关系
/// </summary>
/// <param name="fFocal">镜头焦距 单位m</param>
/// <version BBX3-13S2C-60指的是焦距为0.006m>
/// <version BBX3-13S2G-38指的是焦距为0.0038m>
/// <前者为彩色相机,后者为灰度相机>
/// <param name="fCenterRow">图像中心坐标行</param>
/// <param name="fCenterCol">图像中心坐标列</param>
/// <param name="fKappa">径向畸变量级<0则为桶型,>0则为枕型,在标定的时候设置为0</param>
/// <缩放比例因子,对相机来讲,表示图像传感器上水平和垂直方向上相邻像素之间的距离>
/// <像素在世界坐标系中的尺寸>
/// <param name="fSx"></param>
/// <param name="fSy"></param>
/// <param name="nImageHeight">图像分辨率高</param>
/// <param name="nImageWidth">图像分辨率宽</param>
/// <returns>执行结果</returns>
bool CFastRecognizeAndLocattedVisionDoc::GetCameraParam(CString strFilePath)
{
	if (m_bCameraConnectted)
	{
		HTuple hv_CamParam;
		float fFocalLength	= 0.0f;
		//镜头焦距 单位m
		float fFocal		= 0.0038f;
		float fCenterRow	= 0.0f;
		float fCenterCol	= 0.0f; 
		float fKappa		= 0.0f;
		float fSx			= 0.0f;
		float fSy			= 0.0f;
		int nImageWidth		= 0;
		int nImageHeight	= 0;
		CString strCamParamFileName;

		triclopsGetImageCenter(m_triclopsContext,&fCenterRow,&fCenterCol);
		//归一化焦距
		triclopsGetFocalLength(m_triclopsContext,&fFocalLength);
		triclopsGetResolution(m_triclopsContext,&nImageHeight,&nImageWidth);

		fSx = fFocal / fFocalLength;
		fSy = fFocal / fFocalLength;
		strCamParamFileName = strFilePath + CAM_PARAM_FILE_NAME;
		WriteCameraParamIntoFile("area_scan_division",fFocal,fKappa,fSx,fSy,fCenterCol,fCenterRow,nImageWidth,nImageHeight,strCamParamFileName);
		CString strText;
		strText.Format(_T("相机内参文件写入成功,路径为%s"),strCamParamFileName);
		m_LogUtl.AddMsgInLogFile(strText);
		return true;
	}
	else
	{
		m_LogUtl.AddMsgInLogFile(_T("相机未连接,无法获取相机内参"));
		return false;
	}
}
  • Después de obtener los parámetros internos de la cámara, comience a mover el extremo del robot (seguimiento de la cámara), tome la imagen de corrección del ojo derecho de la cámara de disparo (tablero de calibración fijo en el campo de disparo), preste atención al entorno circundante durante el disparo, observe el efecto de imagen de la imagen y preste especial atención para asegurarse de que cada La amplitud del segundo robot móvil debe ser grande (el cambio de ángulo de múltiples ejes es de más de 5 grados) y se requieren 10-15 grupos de imágenes. El sistema de coordenadas de la herramienta se puede seleccionar al almacenar la pose final del robot, y se sigue el formato F2 al guardar la pose final. El código de calibración es el siguiente:

bool CFastRecognizeAndLocattedVisionDoc::CalculateCalibrationTransform(CString strFileName, int nDataNum, TRANSFORMPOSE& transRobotCalibration)
{
	m_LogUtl.AddMsgInLogFile(_T("系统开始执行标定矩阵计算"));
	// Local iconic variables
	HObject  ho_Image, ho_Caltab;

	// Local control variables
	HTuple  hv_ImageNameStart, hv_DataNameStart, hv_NumImages;
	HTuple  hv_Width, hv_Height, hv_WindowHandle, hv_ParamName;
	HTuple  hv_ParamValue, hv_Labels, hv_Instructions, hv_ArrowThickness;
	HTuple  hv_ArrowLength, hv_OM3DToolOrigin, hv_OM3DBase;
	HTuple  hv_CalTabFile, hv_StartCamParam, hv_CalibDataID;
	HTuple  hv_WindowHandleR, hv_I, hv_RCoord, hv_CCoord, hv_Index;
	HTuple  hv_PoseForCalibrationPlate, hv_ToolInBasePose, hv_PoseIn;
	HTuple  hv_PoseOut, hv_OM3DTool, hv_Warnings, hv_Errors;
	HTuple  hv_CamCalibError, hv_CamParam, hv_ToolInCamPose;
	HTuple  hv_CalObjInBasePose, hv_PlaneInBasePose, hv_Exception;
	HTuple  hv_CalibObjIdx, hv_PoseIds, hv_CameraSize, hv_CameraConeLength;
	HTuple  hv_PX, hv_PY, hv_PZ, hv_OM3DObjectOrig, hv_OM3DObject;
	HTuple  hv_CalObjInCamPose, hv_Message, hv_OM3DCamera, hv_ObjInCamPose;
	HTuple  hv_CamInToolPose, hv_CamInBasePose, hv_ObjInBasePose;

	hv_ImageNameStart = (LPCTSTR)(strFileName + m_strCalibrationImage);
	hv_DataNameStart = (LPCTSTR)(strFileName + m_strCalibrationRobotPose);
	hv_NumImages = nDataNum;

	hv_CalTabFile = (LPCTSTR)(strFileName + CALTAB_FILE_NAME);
	//读取相机内参
	ReadCamPar((LPCTSTR)(strFileName + CAM_PARAM_FILE_NAME), &hv_StartCamParam);
	//创建Halcon标定数据模型返回输出数据模型句柄
	CreateCalibData("hand_eye_moving_cam", 1, 1, &hv_CalibDataID);
	//设置在相机校准模型的类型和初始参数
	SetCalibDataCamParam(hv_CalibDataID, 0, HTuple(), hv_StartCamParam);
	//在标定模型中设定标定对象 设定标定对象句柄索引 标定板坐标点储存地址
	SetCalibDataCalibObject(hv_CalibDataID, 0, hv_CalTabFile);
	//设定标定数据模型最优化的方式
	SetCalibData(hv_CalibDataID, "model", "general", "optimization_method", "nonlinear");
	{
		HTuple end_val72 = hv_NumImages-1;
		HTuple step_val72 = 1;
		//遍历处理每个标定位姿的标定图像
		for (hv_I=0; hv_I.Continue(end_val72, step_val72); hv_I += step_val72)
		{
			ReadImage(&ho_Image, hv_ImageNameStart+(hv_I.TupleString("02d")));
			//搜索标定区域并识别标定轮廓和标定点信息
			//获取标定板轮廓信息
			//获取标定板标定点信息
			//若图像太亮会出现一点问题 可以可使用HALCON进行验证
			FindCalibObject(ho_Image, hv_CalibDataID, 0, 0, hv_I, HTuple(), HTuple());
			GetCalibDataObservContours(&ho_Caltab, hv_CalibDataID, "caltab", 0, 0, hv_I);
			GetCalibDataObservPoints(hv_CalibDataID, 0, 0, hv_I, &hv_RCoord, &hv_CCoord, &hv_Index, &hv_PoseForCalibrationPlate);
			//hv_ToolInBasePose指机器人末端p点位姿
			ReadPose((hv_DataNameStart+(hv_I.TupleString("02d")))+".dat", &hv_ToolInBasePose);
			if (0 != (hv_I==0))
			{
				hv_PoseIn.Clear();
				hv_PoseIn[0] = -0.006;
				hv_PoseIn[1] = -0.296;
				hv_PoseIn[2] = 12;
				hv_PoseIn[3] = 178;
				hv_PoseIn[4] = 2;
				hv_PoseIn[5] = 270;
				hv_PoseIn[6] = 0;
			}
			else
			{
				hv_PoseIn = hv_PoseOut;
			}
			//将工具初始坐标OM3DToolOrigin值通过ToolInBasePose即工具坐标在机器人基坐标中的位姿转换矩阵转换为工具在基坐标下的表示形式 OM3DTool
			RigidTransObjectModel3d(hv_OM3DToolOrigin, hv_ToolInBasePose, &hv_OM3DTool);
			SetCalibData(hv_CalibDataID, "tool", hv_I, "tool_in_base_pose", hv_ToolInBasePose);
		}
	}
	//开始进行手眼标定
	//从手眼标定结果中获取所需的参数具体数值
	CalibrateHandEye(hv_CalibDataID, &hv_Errors);
	GetCalibData(hv_CalibDataID, "model", "general", "camera_calib_error", &hv_CamCalibError);
	GetCalibData(hv_CalibDataID, "camera", 0, "params", &hv_CamParam);
	GetCalibData(hv_CalibDataID, "camera", 0, "tool_in_cam_pose", &hv_ToolInCamPose);
	GetCalibData(hv_CalibDataID, "calib_obj", 0, "obj_in_base_pose", &hv_CalObjInBasePose);
	//考虑标定板的厚度 延z向做一个0.005m的平移
	SetOriginPose(hv_CalObjInBasePose, 0, 0, 0.005, &hv_PlaneInBasePose);
	ClearCalibData(hv_CalibDataID);
	//获取相机坐标系在机器人坐标系下的坐标
	PoseInvert(hv_ToolInCamPose, &hv_CamInToolPose);
	
	transRobotCalibration.PointX = float(hv_CamInToolPose[0].D() * 1000);
	transRobotCalibration.PointY = float(hv_CamInToolPose[1].D() * 1000);
	transRobotCalibration.PointZ = float(hv_CamInToolPose[2].D() * 1000);
	transRobotCalibration.RollAngle = float(hv_CamInToolPose[3].D());
	transRobotCalibration.PitchingAngle = float(hv_CamInToolPose[4].D());
	transRobotCalibration.YawAngle = float(hv_CamInToolPose[5].D());

	CString str;
	str.Format(_T("机器人和视觉标定完成,标定结果为:横滚%5.2f,俯仰%5.2f,偏航%5.2f,X%5.2f,Y%5.2f,Z%5.2f")
		,transRobotCalibration.RollAngle,transRobotCalibration.PitchingAngle,transRobotCalibration.YawAngle
		,transRobotCalibration.PointX,transRobotCalibration.PointY,transRobotCalibration.PointZ);
	m_LogUtl.AddMsgInLogFile(str);

	return true;
}

Durante la calibración:

  • Ecuaciones de cinemática directa e inversa que involucran actitud.
  • Incluirá ángulo de balanceo, ángulo de cabeceo, ángulo de guiñada (balanceo, cabeceo, guiñada, RPY)
  • Punta Euler

El ángulo de balanceo, el ángulo de cabeceo y el ángulo de guiñada giran respectivamente alrededor de los ejes a, o y n en tres secuencias, que pueden ajustar el robot a la postura deseada.

/// Alrededor del eje a (el eje z del sistema de coordenadas de movimiento) se llama balanceo;
/// Alrededor del eje o (el eje y del sistema de coordenadas de movimiento) se llama paso;
/// Alrededor del eje n (el eje x del sistema de coordenadas de movimiento) Llamado guiñada

Implicará la conversión directa e inversa entre la posición final y la actitud y la matriz NOAP El proceso de implementación específico cargará el código de ingeniería más adelante.

¡Final feliz! ¡Bienvenidos todos a corregirme! Dingyi 24/08/2020

 

 

 

Supongo que te gusta

Origin blog.csdn.net/Ding86341631/article/details/108192459
Recomendado
Clasificación