机械臂手眼标定C++ opencv(眼在手上)

目录


一、介绍

  • 手眼标定是指求解出工业机器人的末端法兰坐标系与相机坐标系之间的坐标变换关系,或者工业机器人的基底坐标系与相机坐标系之间的坐标变换关系。手眼标定有两种情形:第一种是相机(眼)固定在机器臂(手)的末端,相机相对于机器臂末端是固定的,相机跟随机器臂移动,这种方式的手眼标定成为 Eye-in-hand;第二种是相机(眼)和机器臂(手)分离,相机相对于工业机器人的基座是固定的,机器臂的运动对相机没有影响, 这种方式的手眼标定成为 Eye-to-hand。
  • 本文主要实现的是眼在手上的手眼标定,主要基于opencv的calibrateHandEye手眼标定函数,通过linux  C++代码进行实现,并最终通过代码获取到相机内参和法兰盘相机之间的变化矩阵。

二、准备

  1. 标定板,测量获取标定板角点行列数,标定板角点间距,并最终固定好标定板,保证每次拍照标定板位置一致。
  2. 机械臂,需要设定机械臂用户坐标系为地球坐标系、设定机械臂的工具头为法兰盘中心,以及能够实时获取工具头位姿。本文用到的机械臂是节卡MiniCobo.
  3. 定焦相机,将相机固定在法兰中心末端,确保牢固。

三、源码介绍

源码链接

https://download.csdn.net/download/mengfanji_5995/86726861

/*
 * CalibrateHandEye.h
 *
 *  Created on: 2022年6月1日
 *      Author: mfj
 */

#ifndef CALIBRATEHANDEYE_H_
#define CALIBRATEHANDEYE_H_

#include <opencv2/opencv.hpp>
#include <math.h>
using namespace cv;
using namespace std;
class CalibrateHandEye {
private:
	vector<String> m_vImgsPath;			//创建容器存放读取图像路径
	vector<Mat> m_vImgs;				//创建容器存放图像
	vector<Mat> m_vRotGrip2BaseMat;		//当前工具姿态R
	vector<Mat> m_vTransGrip2BaseMat;	//当前工具的偏移量T
	vector<Mat> m_vRotTar2CamMat;		//目标到相机的R
	vector<Mat> m_vTransTar2CamMat;		//目标到相机的T
	String m_sSeq;						//指定欧拉角xyz的排列顺序如:"xyz" "zyx"

	//标定板信息
	Size m_sBoardSize;					//标定板角点数目Size(11,8),(width,height)
	Size2f m_sSquareSize;					//棋盘格每个方格的真实尺寸,单位mm

	//内参参数
	Mat m_matCameraK;
	Mat m_matCameraD;

	//手眼参数
	vector<Mat> m_vecRotTar2CamMat;
	vector<Mat> m_vecTransTar2CamMat;
	Mat   m_matRotCam2Grip;
	Mat   m_matTransCam2Grip;




public:
	CalibrateHandEye();
	virtual ~CalibrateHandEye();

	int   m_nRobotImgCount;			//机器人交互需要摄制的总图象数
	String m_sImgsDir;

	//HandinEye算法
	void InitConfig(int nRobotImgCount,String sImgsDir,String seq, Size boardSize, Size2f squareSize);			//对需要图片数量和图片存储路径进行配置
	void InsertImgsPathAndImgs(String imgPath, Mat img);									//保存图片路径和图片
	void InsertRTGrip2BaseMat(Mat R, Mat T);												//保存当前工具的位资
	void InsertRTTar2CamMat(Mat R, Mat T);												//保存目标在相机坐标系内的位资

	void calibrateRobotHandEye();															//标定相机内参和手眼标定

	bool IsRotationMatrix(const cv::Mat& R);												//判断是否是旋转矩阵
	Mat EulerAngleToRotatedMatrix(const cv::Mat& eulerAngle);
	Mat QuaternionToRotatedMatrix(const cv::Vec4d& q);
	Mat AttitudeVectorToMatrix(cv::Mat& m, bool useQuaternion);

	void printResult();

};

#endif /* CALIBRATEHANDEYE_H_ */



/*
 * CalibrateHandEye.cpp
 *
 *  Created on: 2022年6月1日
 *      Author: mfj
 */

#include "../inc/CalibrateHandEye.h"

CalibrateHandEye::CalibrateHandEye() {
	// TODO Auto-generated constructor stub

}

CalibrateHandEye::~CalibrateHandEye() {
	// TODO Auto-generated destructor stub
}

/*
 	* @brief 手眼标定初始化配置
	* @param nRobotImgCount 需要机器人和相机交互拍照个数
	* @param sImgsDir 图片存储路径
	* @param seq 指定欧拉角xyz的排列顺序如:"xyz" "zyx"
	* @param boardSize 标定板拐角像素宽度width height
	* @param squareSize 标定板方框边长
	* @return ERR_SUCC 成功 其他失败
 */
void CalibrateHandEye::InitConfig(int nRobotImgCount,String sImgsDir,String seq,Size boardSize, Size2f squareSize){
	this->m_nRobotImgCount = nRobotImgCount;
	this->m_sImgsDir = sImgsDir;
	this->m_sSeq = seq;
	this->m_sBoardSize = boardSize;
	this->m_sSquareSize = squareSize;
}

void CalibrateHandEye::InsertImgsPathAndImgs(String imgPath, Mat img){
	this->m_vImgsPath.push_back(imgPath);
	this->m_vImgs.push_back(img);
}

void CalibrateHandEye::InsertRTGrip2BaseMat(Mat R, Mat T){
	this->m_vRotGrip2BaseMat.push_back(R);
	this->m_vTransGrip2BaseMat.push_back(T);
}

void CalibrateHandEye::InsertRTTar2CamMat(Mat R, Mat T){
	this->m_vRotTar2CamMat.push_back(R);
	this->m_vTransTar2CamMat.push_back(T);
}

//判断是否为旋转矩阵
bool CalibrateHandEye::IsRotationMatrix(const cv::Mat& R)
{
	cv::Mat tmp33 = R({ 0,0,3,3 });
	cv::Mat shouldBeIdentity;

	shouldBeIdentity = tmp33.t() * tmp33;

	cv::Mat I = cv::Mat::eye(3, 3, shouldBeIdentity.type());

	return  cv::norm(I, shouldBeIdentity) < 1e-6;
}

/*********************************************************************
说明: 欧拉角转换为 3*3 的旋转矩阵R。
参数:
    eulerAngle:弧度值
	seq		  :指定欧拉角xyz的排列顺序如:"xyz" "zyx"
**********************************************************************/
Mat CalibrateHandEye::EulerAngleToRotatedMatrix(const Mat& eulerAngle)
{
	Matx13d m(eulerAngle);
	auto rx = m(0, 0), ry = m(0, 1), rz = m(0, 2);
	auto xs = sin(rx), xc = cos(rx);
	auto ys = sin(ry), yc = cos(ry);
	auto zs = sin(rz), zc = cos(rz);

	Mat rotX = (cv::Mat_<double>(3, 3) << 1, 0, 0, 0, xc, -xs, 0, xs, xc);
	Mat rotY = (cv::Mat_<double>(3, 3) << yc, 0, ys, 0, 1, 0, -ys, 0, yc);
	Mat rotZ = (cv::Mat_<double>(3, 3) << zc, -zs, 0, zs, zc, 0, 0, 0, 1);

	Mat rotMat;

	if (this->m_sSeq == "zyx")
	{
		rotMat = rotX * rotY * rotZ;
	}
	else if (this->m_sSeq == "yzx")
	{
		rotMat = rotX * rotZ * rotY;
	}
	else if (this->m_sSeq == "zxy")
	{
		rotMat = rotY * rotX * rotZ;
	}
	else if (this->m_sSeq == "xzy")
	{
		rotMat = rotY * rotZ * rotX;
	}
	else if (this->m_sSeq == "yxz")
	{
		rotMat = rotZ * rotX * rotY;
	}
	else if (this->m_sSeq == "xyz")
	{
		rotMat = rotZ * rotY * rotX;
	}
	else
	{
		cv::error(cv::Error::StsAssert, "Euler angle sequence string is wrong.",
			__FUNCTION__, __FILE__, __LINE__);
	}

	if (!IsRotationMatrix(rotMat))
	{
		cv::error(cv::Error::StsAssert, "Euler angle can not convert to rotated matrix",
			__FUNCTION__, __FILE__, __LINE__);
	}

	return rotMat;
}

/*********************************************************************
说明: 四元数转换为旋转矩阵。数据类型double; 四元数定义
q = w + x*i + y*j + z*k

参数:
	q:四元数。
	seq		  :指定欧拉角xyz的排列顺序如:"xyz" "zyx"。
返回:
	3*3旋转矩阵。
**********************************************************************/
Mat CalibrateHandEye::QuaternionToRotatedMatrix(const Vec4d& q)
{
	double w = q[0], x = q[1], y = q[2], z = q[3];

	double x2 = x * x, y2 = y * y, z2 = z * z;
	double xy = x * y, xz = x * z, yz = y * z;
	double wx = w * x, wy = w * y, wz = w * z;

	Matx33d res{
		1 - 2 * (y2 + z2),	2 * (xy - wz),		2 * (xz + wy),
		2 * (xy + wz),		1 - 2 * (x2 + z2),	2 * (yz - wx),
		2 * (xz - wy),		2 * (yz + wx),		1 - 2 * (x2 + y2),
	};
	return Mat(res);
}

/************************************************************************
说明: 将四元数或者欧拉角,或旋转向量加上平移向量转换为4x4坐标变换矩阵。

参数:
	m:1*6 || 1*10的矩阵,
		形式:6  {x,y,z, rx,ry,rz} 或 10 {x,y,z, qw,qx,qy,qz, rx,ry,rz};
	useQuaternion:如果是1*10的矩阵,判断是否使用四元数计算旋转矩阵;
	seq:指定欧拉角xyz的排列顺序如:"xyz" "zyx",为空表示旋转向量。
返回:
	4*4坐标变换矩阵。
*************************************************************************/
Mat CalibrateHandEye::AttitudeVectorToMatrix(cv::Mat& m, bool useQuaternion)
{
	CV_Assert(m.total() == 6 || m.total() == 10);

	if (m.cols == 1)
	{
		m = m.t();
	}

	Mat tmp = Mat::eye(4, 4, CV_64FC1);

	//如果使用四元数转换成旋转矩阵则读取m矩阵的第第四个成员,读4个数据
	if (useQuaternion)	// normalized vector, its norm should be 1.
	{
		Vec4d quaternionVec = m({ 3, 0, 4, 1 });
		QuaternionToRotatedMatrix(quaternionVec).copyTo(tmp({ 0, 0, 3, 3 }));
	}
	else
	{
		Mat rotVec;
		if (m.total() == 6)
		{
			rotVec = m({ 3, 0, 3, 1 });		//6
		}
		else
		{
			rotVec = m({ 7, 0, 3, 1 });		//10
		}

		//如果seq为空表示传入的是旋转向量,否则"xyz"的组合表示欧拉角
		if (0 == this->m_sSeq.compare(""))
		{
			Rodrigues(rotVec, tmp({ 0, 0, 3, 3 }));
		}
		else
		{
			EulerAngleToRotatedMatrix(rotVec).copyTo(tmp({ 0, 0, 3, 3 }));
		}
	}
	tmp({ 3, 0, 1, 3 }) = m({ 0, 0, 3, 1 }).t();

	return tmp;
}

void CalibrateHandEye::calibrateRobotHandEye(){

	vector<vector<Point2f>> imgsPoints;		//所有图像中角点的像素坐标(u,v)
	for(size_t i = 0; i < this->m_vImgs.size(); i++){

		cout << this->m_vImgsPath[i] << endl;

		Mat gray1;
		Mat temp;
		cvtColor(this->m_vImgs[i], gray1, COLOR_BGR2GRAY);

		this->m_vImgs[i].copyTo(temp);
		//图片中所有角点的图像坐标
		vector<Point2f> img1_points;
		vector<Point2f> temp_points;


		findChessboardCorners(gray1,this->m_sBoardSize, temp_points);
		cv::find4QuadCornerSubpix(gray1, temp_points, Size(3,3));

		if(temp_points[0].x*temp_points[0].y >
			temp_points[temp_points.size()-1].x*temp_points[temp_points.size()-1].y){

			for(size_t i = 0; i < temp_points.size(); i++){
				img1_points.push_back(temp_points[temp_points.size() - 1 - i]);
			}
		}
		else
		{
			for(size_t i = 0; i < temp_points.size(); i++){
				img1_points.push_back(temp_points[i]);
			}
		}


		imgsPoints.push_back(img1_points);

		printf("point 0 : x = %f, y = %f\n",img1_points[0].x,img1_points[0].y);
		printf("point end : x = %f, y = %f\n",img1_points[temp_points.size()-1].x,img1_points[temp_points.size()-1].y);

		drawChessboardCorners(temp, this->m_sBoardSize, img1_points,true);

		char picName[128] = {};
        sprintf(picName,"%s/%d-.jpg",this->m_sImgsDir,(int)i);
		imwrite(picName, temp);  //校正后图像

//		imshow("temp", img);
//		waitKey(1000);
	}
	vector<vector<Point3f>> objectsPoints;
	for(size_t i = 0; i < imgsPoints.size(); i++){

		vector<Point3f> tempPointSet;
		for(int j = 0; j < this->m_sBoardSize.height; j++){
			for(int k = 0; k < this->m_sBoardSize.width; k++){

				Point3f realPoint;
				//假设标定板世界坐标系的z平面,z=0
				realPoint.x = (float)k*this->m_sSquareSize.width;  //
				realPoint.y = (float)j*this->m_sSquareSize.height;
				realPoint.z = 0;
				tempPointSet.push_back(realPoint);
			}
		}
		objectsPoints.push_back(tempPointSet);
	}
	//图像尺寸
	Size imageSize;
	imageSize.width = this->m_vImgs[0].cols;
	imageSize.height = this->m_vImgs[0].rows;

	//4.将三维坐标、角点像素坐标传入获取内参、畸变系数、旋转向量和平移向量
		Mat cameraMatrix = Mat(3, 3, CV_32FC1, Scalar::all(0));
		//相机五个畸变系数
		Mat distCoeffs = Mat(1, 5, CV_32FC1, Scalar::all(0));
		//每幅图像的旋转向量
		vector<Mat> rvecs;
		//每幅图像的平移向量
		vector<Mat> tvecs;
		calibrateCamera(objectsPoints, imgsPoints, imageSize, cameraMatrix, distCoeffs, rvecs,tvecs,0);
		this->m_matCameraK = cameraMatrix;
		this->m_matCameraD = distCoeffs;

		cout << "cameraMatrix:" << endl;
		cout << cameraMatrix << endl;
		cout << "distCoeffs:" << endl;
		cout << distCoeffs << endl;

		for(size_t i = 0; i < rvecs.size(); i++){

			cout << "第" <<i <<"张 :"<< endl;
			cout << "Rotation vector:" << endl;
			Mat R;
			Rodrigues(rvecs[i], R);
			this->m_vecRotTar2CamMat.push_back(R);
			this->m_vecTransTar2CamMat.push_back(tvecs[i]);
			cout << R << endl;
			cout << tvecs[i] << endl;
		}
		//手眼标定,CALIB_HAND_EYE_TSAI法为11ms,最快
		calibrateHandEye(this->m_vRotGrip2BaseMat, this->m_vTransGrip2BaseMat,
			this->m_vecRotTar2CamMat, this->m_vecTransTar2CamMat, this->m_matRotCam2Grip,
			this->m_matTransCam2Grip, CALIB_HAND_EYE_TSAI);

}


void CalibrateHandEye::printResult(){

	cout << "cameraMatrix:" << endl;
	cout << m_matCameraK << endl;

	cout << "distCoeffs:" << endl;
	cout << m_matCameraD << endl;

	cout << "handEye:" << endl;
	cout << m_matRotCam2Grip << endl;
	cout << m_matTransCam2Grip << endl;

}






/*
 * main.cpp
 *
 *  Created on: 2022年6月1日
 *      Author: mfj
 */
#include <iostream>
#include <string>
#include <time.h>
#include <opencv2/opencv.hpp>
#include <stdio.h>
#include <stdlib.h>
#include <sys/socket.h>
#include <sys/stat.h>
#include <netinet/in.h>
#include <unistd.h>
#include <arpa/inet.h>
#include "inc/CalibrateHandEye.h"
#include "JAKAZuRobot.h"

using namespace std;
using namespace cv;


void InsertRobotRT(CartesianPose* tcp_position,CalibrateHandEye *calibrateHandEye){

    Mat eulerAngle = (cv::Mat_<double>(1,3) << tcp_position->rpy.rx,tcp_position->rpy.ry,tcp_position->rpy.rz);
    cout << "eulerAngle:" << endl;
    cout << eulerAngle << endl;

    Mat T = (cv::Mat_<double>(3,1) << tcp_position->tran.x,tcp_position->tran.y,tcp_position->tran.z);
    Mat R = calibrateHandEye->EulerAngleToRotatedMatrix(eulerAngle);
    cout << "tcp R:" << endl;
    cout << R << endl;
    cout << "tcp T:" << endl;
    cout << T << endl;
    calibrateHandEye->InsertRTGrip2BaseMat(R,T);


}

void takeImgsAndTcpPoss(int camId,CalibrateHandEye *calibrateHandEye){
    JAKAZuRobot jaka;
    std::cout << jaka.login_in("192.168.11.102")<< std::endl;
    jaka.power_on();
    jaka.enable_robot();

    //设置法兰中心为工具头
    jaka.set_tool_id(0);
    //设置地球坐标系为参考系
    jaka.set_user_frame_id(0);

    VideoCapture cap;
    cap.open(camId);
    cap.set(CAP_PROP_FRAME_WIDTH, 640.0);

    cap.set(CAP_PROP_FRAME_HEIGHT, 480.0);
    cap.set(CAP_PROP_FPS, 10);
    cap.set(CAP_PROP_CONTRAST, 50);
    cap.set(CAP_PROP_BRIGHTNESS, 50);
    if(!cap.isOpened()){
        cout << "The camera open failed!" << endl;
    }

    char pic_Name[128] = {};                //照片名称
    int picCount = 0;
    while(1)
    {
        Mat img;
        cap >> img;
        if(img.empty())
            break;
        imshow("temp",img);
        if(waitKey(30)  == ' ')         //按下空格键进行拍照
        {
            sprintf(pic_Name,"%s/%d.jpg",calibrateHandEye->m_sImgsDir.c_str(),picCount++);
            printf("pic_Name = %s\n",pic_Name);
            imwrite(pic_Name, img);   //将Mat数据写入文件
            calibrateHandEye->InsertImgsPathAndImgs(pic_Name,img);
            printf("%s\n",pic_Name);
            //获取对应的机器人位资
            CartesianPose tcp_position;
            jaka.get_tcp_position(&tcp_position);

            InsertRobotRT(&tcp_position,calibrateHandEye);
        }
        if(picCount >= calibrateHandEye->m_nRobotImgCount)
            break;
    }
}

int main()
{
    CalibrateHandEye calibrateHandEye;
    //创建存储图片的路径
    mkdir("./pic",0x777);
    calibrateHandEye.InitConfig(9,"./pic","xyz",Size(11,8),Size2f(15,15));

    //获取当前工具姿态 R,T
    int camId = 2;
    takeImgsAndTcpPoss(camId, &calibrateHandEye);
    calibrateHandEye.calibrateRobotHandEye();
    calibrateHandEye.printResult();
    return 0;
}

四、源码运行

1.修改对应的源码

  • 将代码中机械臂相关的操作函数换成自己机械臂相关操作函数,主要功能是切换坐标系和工具头,然后每次拍照是获取当前法兰中心的位姿。
  • 修改InitConfig函数中的参数,图片数量,存储图片路径,标定板的宽度和高度,标定板角点之间的间距。
  • 检查获取tcp位姿中欧拉角单位,如果是角度,则EulerAngleToRotatedMatrix中需要将角度转换成弧度。
  • 修改相机的Id,修改成对应的自己的相机,修改相机拍照分辨率。

2.运行代码

  • 进入到build目录,执行./calibrateHandEye运行程序。
  • 拖动机械臂,让相机尽量能够拍到各种情况下的图片,也就是让位姿的六个变量在8张图片中,都有很大的变化。
  • 这是最关键的一步,确保标定板左上角在每次拍照时距离像素坐标原点最近,这样可以保证每次角点位置从左上角开始,如下图所示。

五、运行结果

1. 拍的图片

机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)机械臂手眼标定C++ opencv(眼在手上)

2.标定结果

  • 包括拍照时工具头的8个位姿
  • 8张图片的路径,8张图片在相机坐标系内的位姿
  • 相机内参和畸变系数
  • 手眼变化矩阵

pic_Name = pic/0.jpg
pic/0.jpg
eulerAngle:
[2.837364540120381, -1.403451198394465, 0.2472442780240197]
tcp R:
[0.161499994896073, -0.05289558106246462, 0.9854541131643992;
 0.04076398505685564, -0.9973527328627583, -0.06021481357167888;
 0.9860304504278014, 0.04989572882774462, -0.1589162265909159]
tcp T:
[445.2547683079717;
 50.91646471702672;
 452.6936268932307]
pic_Name = pic/1.jpg
pic/1.jpg
eulerAngle:
[-2.634779945654813, -1.482408187017663, -0.6281232321858047]
tcp R:
[0.07142456707337645, -0.122546365981062, 0.9898893470500713;
 -0.05187167619816675, -0.9915374475537024, -0.1190076439019004;
 0.9960963108187748, -0.04284715023808022, -0.07717681834399558]
tcp T:
[381.3491789200403;
 25.17330740716023;
 526.197810974184]
pic_Name = pic/2.jpg
pic/2.jpg
eulerAngle:
[-2.526196793948303, -1.524994648395364, -0.5892965816868264]
tcp R:
[0.03806308169034934, 0.02559302406084916, 0.9989475456357327;
 -0.02544659218493138, -0.9993229643561545, 0.02657223845673439;
 0.9989512864791794, -0.02643123209100474, -0.03738605638127481]
tcp T:
[393.3798240967378;
 82.37535715508236;
 519.6829137521122]
pic_Name = pic/3.jpg
pic/3.jpg
eulerAngle:
[0.4818012844008769, -1.430672735795063, 2.724773316724912]
tcp R:
[-0.127707512757848, 0.06078340735197858, 0.9899475584978669;
 0.05654415779064989, -0.9960507024412376, 0.0684525849480009;
 0.9901987423769787, 0.06471766031772649, 0.1237662112131142]
tcp T:
[436.6858684716935;
 13.51551574880432;
 316.6709643994483]
pic_Name = pic/4.jpg
pic/4.jpg
eulerAngle:
[-0.01135679002441985, -0.9710778791503957, -3.03696560901973]
tcp R:
[-0.5613236456052914, 0.09510602359791469, 0.8221135013851665;
 -0.05894487750916427, -0.9954465125731367, 0.07491156133341223;
 0.8254945586130867, -0.006409748932123456, 0.5643736783539893]
tcp T:
[364.8117279882118;
 24.83182858079266;
 309.7239188420555]
pic_Name = pic/5.jpg
pic/5.jpg
eulerAngle:
[2.625835928434015, -1.155726873862147, 0.541197216165697]
tcp R:
[0.3456255533169887, 0.06133095846776045, 0.9363661091836629;
 0.2077410686692057, -0.9781024994328529, -0.01261542672216763;
 0.915088315564406, 0.1988819100286194, -0.3507981764218086]
tcp T:
[356.5613429445592;
 47.63507650361141;
 472.3034868229475]
pic_Name = pic/6.jpg
pic/6.jpg
eulerAngle:
[1.007588532302291, -1.382038307514443, 2.589325395140222]
tcp R:
[-0.1597441746085744, 0.4269650093277467, 0.890046447938748;
 0.09843900533848306, -0.8902407694608832, 0.444725909541669;
 0.9822380367846663, 0.1586576603869217, 0.1001807660878714]
tcp T:
[441.1230178169002;
 -32.97211239015633;
 428.5393735991261]
pic_Name = pic/7.jpg
pic/7.jpg
eulerAngle:
[-0.8733390957144501, -1.35744738823443, -2.571139546347784]
tcp R:
[-0.1782073473538803, -0.2836496633419452, 0.9422234394426273;
 -0.1143392596496625, -0.945095229394955, -0.3061397410949194;
 0.9773273121384977, -0.1622894816705579, 0.1359906213208879]
tcp T:
[357.2194411301201;
 189.0084273676453;
 416.8966025814369]
pic_Name = pic/8.jpg
pic/8.jpg
eulerAngle:
[1.011927832192954, -1.231147663822825, 1.755366613749689]
tcp R:
[-0.06114213897300201, -0.3745086802516266, 0.9252053216762164;
 0.3274972628802729, -0.8831506367824982, -0.3358429626426576;
 0.9428717737040045, 0.2824680533562212, 0.1766482866755617]
tcp T:
[355.3489430092143;
 176.9577067524453;
 444.5771653153134]
pic/0.jpg
point 0 : x = 168.443649, y = 107.958328
point end : x = 494.725647, y = 338.585663
pic/1.jpg
point 0 : x = 29.252792, y = 77.697044
point end : x = 297.669464, y = 231.451447
pic/2.jpg
point 0 : x = 30.287731, y = 239.152573
point end : x = 295.061432, y = 404.104279
pic/3.jpg
point 0 : x = 316.160248, y = 109.772141
point end : x = 595.769897, y = 321.371368
pic/4.jpg
point 0 : x = 46.783520, y = 171.132843
point end : x = 288.634033, y = 318.244629
pic/5.jpg
point 0 : x = 332.924377, y = 167.658157
point end : x = 540.160339, y = 368.633240
pic/6.jpg
point 0 : x = 133.504120, y = 201.569626
point end : x = 388.708649, y = 416.262512
pic/7.jpg
point 0 : x = 112.914200, y = 258.456024
point end : x = 370.338715, y = 350.219360
pic/8.jpg
point 0 : x = 104.669037, y = 120.615677
point end : x = 304.532410, y = 326.573608
cameraMatrix:
[458.1525092355417, 0, 325.6881659756511;
 0, 457.5119355506856, 243.9388070314256;
 0, 0, 1]
distCoeffs:
[0.1053444333627627, -0.2762127911085805, -0.0004634971392161804, -0.001047475579189504, 0.1964663197014163]
第0张 :
Rotation vector:
[0.9837331591649157, 0.005586688567928906, 0.1795490475337022;
 0.006805578513997235, 0.9976396423239678, -0.06832882382124897;
 -0.1795069794200339, 0.06843926485980423, 0.9813731764038311]
[-74.64001098872089;
 -64.51620370401209;
 220.4478762236214]
第1张 :
Rotation vector:
[0.9907613702827252, 0.09784477831133621, 0.09390583854426851;
 -0.08486328401243932, 0.9874123833616041, -0.1334728744381446;
 -0.1057834116585432, 0.1242706101271017, 0.9865934751844435]
[-175.2918503865942;
 -98.24868603988743;
 274.1631320407814]
第2张 :
Rotation vector:
[0.995747582640551, 0.07018854582727455, 0.05966841459391953;
 -0.07095788496150521, 0.9974200677538458, 0.01087138462678587;
 -0.05875142744894869, -0.01505909946066837, 0.9981590521034935]
[-174.0155524320604;
 -2.769963308967208;
 273.1368992613557]
第3张 :
Rotation vector:
[0.9935856641339714, -0.01796246289514884, -0.1116462178230652;
 0.02351540205321312, 0.9985404602042134, 0.04862072810472468;
 0.1106099177005871, -0.05093426412444009, 0.9925578808534902]
[-4.61431254199576;
 -67.43523163966927;
 232.4065856837365]
第4张 :
Rotation vector:
[0.8309458103671667, 0.08069286492488165, -0.5504704549596348;
 -0.0446810880143971, 0.9959089896860334, 0.07854224746207483;
 0.554556273616215, -0.04066873261805565, 0.8311518474864499]
[-160.8396574403255;
 -42.0133311530394;
 267.4005148414381]
第5张 :
Rotation vector:
[0.9156179745546328, -0.1612890833322529, 0.3682791825101079;
 0.1548045605109507, 0.9868120947863885, 0.04730156052722853;
 -0.3710515768966401, 0.01370113795059508, 0.9285111771547909]
[5.322745795855546;
 -53.89332628097564;
 325.2347760818477]
第6张 :
Rotation vector:
[0.9888167200742997, -0.06165621761470144, -0.1357939797301513;
 0.1134828723140077, 0.9018524789624902, 0.4168737745176275;
 0.09676327708829825, -0.4276220492662414, 0.8987637349094997]
[-109.7108162076043;
 -24.17677592227406;
 264.9660853054841]
第7张 :
Rotation vector:
[0.9743372565047543, 0.1547119305717964, -0.1634965722134145;
 -0.1987261575480997, 0.9323578523983674, -0.3020211075028895;
 0.1057110443281896, 0.3267614628591501, 0.9391762994758714]
[-130.0833097297625;
 9.245502079013947;
 284.1915625789431]
第8张 :
Rotation vector:
[0.9578490342767028, -0.2851743060316426, -0.03465317755356561;
 0.2513437317677799, 0.8903474762628238, -0.3796151999241688;
 0.1391098703767428, 0.3549041936801979, 0.9244952445913253]
[-128.7356194458108;
 -71.95294846318892;
 270.9486870166976]
cameraMatrix:
[458.1525092355417, 0, 325.6881659756511;
 0, 457.5119355506856, 243.9388070314256;
 0, 0, 1]
distCoeffs:
[0.1053444333627627, -0.2762127911085805, -0.0004634971392161804, -0.001047475579189504, 0.1964663197014163]
handEye:
[0.9999885473614986, -0.0008636063031679353, -0.004707369753178672;
 0.0008201373013736612, 0.9999570813992839, -0.009228365740097774;
 0.004715137394276899, 0.009224399361435053, 0.9999463375280565]
[9.622578378491772;
 -50.90404022640985;
 16.43068277125978]
 

文章出处登录后可见!

已经登录?立即刷新

共计人评分,平均

到目前为止还没有投票!成为第一位评论此文章。

(0)
扎眼的阳光的头像扎眼的阳光普通用户
上一篇 2023年2月25日 下午10:16
下一篇 2023年2月25日 下午10:17

相关推荐