头部相机标定文件
This commit is contained in:
28
calibration_mat/eye_to_hand.json
Normal file
28
calibration_mat/eye_to_hand.json
Normal file
@@ -0,0 +1,28 @@
|
||||
{
|
||||
"T": [
|
||||
[
|
||||
0.01868075138315295,
|
||||
0.8881359544145228,
|
||||
0.45920099738999437,
|
||||
-0.19284748723617093
|
||||
],
|
||||
[
|
||||
0.002854261818715398,
|
||||
-0.4593266423892484,
|
||||
0.8882628489252997,
|
||||
0.057154511710361816
|
||||
],
|
||||
[
|
||||
0.9998214254141742,
|
||||
-0.01528273756969839,
|
||||
-0.011115539354645598,
|
||||
-0.04187423675125192
|
||||
],
|
||||
[
|
||||
0.0,
|
||||
0.0,
|
||||
0.0,
|
||||
1.0
|
||||
]
|
||||
]
|
||||
}
|
||||
@@ -192,13 +192,13 @@ class _Calibration:
|
||||
np.linalg.inv(
|
||||
self._function(
|
||||
self._hand[i], self._hand[i + 1], self._hand[i + 2],
|
||||
self._hand[i + 3], self._hand[i + 4], self._hand[i + 5], self._hand[i + 6]
|
||||
self._hand[i + 6], self._hand[i + 3], self._hand[i + 4], self._hand[i + 5]
|
||||
)
|
||||
)
|
||||
if self._mode == 'eye_to_hand' else
|
||||
self._function(
|
||||
self._hand[i], self._hand[i + 1], self._hand[i + 2],
|
||||
self._hand[i + 3], self._hand[i + 4], self._hand[i + 5], self._hand[i + 6]
|
||||
self._hand[i + 6], self._hand[i + 3], self._hand[i + 4], self._hand[i + 5]
|
||||
)
|
||||
)
|
||||
self._Hcs.append(
|
||||
|
||||
@@ -52,7 +52,7 @@ def calculate(mode, hand_path, camera_path, hand_eye_path):
|
||||
for i in range(sum_):
|
||||
hand = [hand_all[i*7], hand_all[i*7+1], hand_all[i*7+2], hand_all[i*7+3], hand_all[i*7+4], hand_all[i*7+5], hand_all[i*7+6]]
|
||||
camera = [camera_all[i*7], camera_all[i*7+1], camera_all[i*7+2], camera_all[i*7+3], camera_all[i*7+4], camera_all[i*7+5], camera_all[i*7+6]]
|
||||
T_hand_in_base = get_matrix_quat(hand[0], hand[1], hand[2], hand[3], hand[4], hand[5], hand[6])
|
||||
T_hand_in_base = get_matrix_quat(hand[0], hand[1], hand[2], hand[6], hand[3], hand[4], hand[5])
|
||||
T_cal_in_camera = get_matrix_quat(camera[0], camera[1], camera[2], camera[3], camera[4], camera[5], camera[6])
|
||||
|
||||
if mode == "eye_to_hand":
|
||||
|
||||
@@ -70,6 +70,13 @@ class GetCameraPose(Node):
|
||||
self.get_logger().info(f"Have not camera data")
|
||||
return
|
||||
|
||||
|
||||
|
||||
def timer_callback(self):
|
||||
self.collect = self.get_parameter('start_collect_once').value
|
||||
self.save = self.get_parameter('save').value
|
||||
self.class_name = self.get_parameter('class_name').value
|
||||
|
||||
if self.save:
|
||||
print(self.camera)
|
||||
self.get_logger().info(f'Save as camera_pose_data.json')
|
||||
@@ -78,11 +85,6 @@ class GetCameraPose(Node):
|
||||
|
||||
self.done = True
|
||||
|
||||
def timer_callback(self):
|
||||
self.collect = self.get_parameter('start_collect_once').value
|
||||
self.save = self.get_parameter('save').value
|
||||
self.class_name = self.get_parameter('class_name').value
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
|
||||
Reference in New Issue
Block a user