13
13
from std_msgs .msg import Float64
14
14
from cv_bridge import CvBridge , CvBridgeError
15
15
from ar_track_alvar_msgs .msg import AlvarMarkers
16
- import forward_kinematics_extrinsics
16
+ from forward_kinematics_extrinsics import forwardKinematics
17
17
18
18
ROSTOPIC_SET_ARM_JOINT = '/goal_dynamixel_position'
19
19
ROSTOPIC_SET_PAN_JOINT = '/pan/command'
@@ -65,7 +65,7 @@ def main(noiter=15):
65
65
rospy .sleep (2 )
66
66
Calib = rospy .wait_for_message ("/camera/color/camera_info" , CameraInfo )
67
67
K_matrix = np .array (Calib .K )
68
- fk = forward_kinematics_extrinsics . forwardKinematics ('bottom_plate' , 'ar_tag' )
68
+ fk = forwardKinematics ('bottom_plate' , 'ar_tag' )
69
69
70
70
positions = np .zeros ((noiter , 3 ))
71
71
orientations = np .zeros ((noiter , 4 ))
@@ -130,32 +130,45 @@ def artagcallback(i):
130
130
np .savez ("../data/calibration/calibration_info.npz" , position = positions , orientation = orientations , camerainfo = K_matrix , \
131
131
joint_angles = joint_angles , forward_kinematics = end_effector_positions )
132
132
133
- R = calculate_extrinsic (positions , K_matrix , end_effector_positions , noiter )
134
- print (R )
133
+ calculate_extrinsic (positions , K_matrix , end_effector_positions , noiter )
134
+ print ("\n ================================\n " )
135
+ calculate_extrinsic_opencv (positions , K_matrix , end_effector_positions )
135
136
136
137
137
138
def calculate_extrinsic (positions , K_matrix , end_effector_positions , noiter ):
138
- min_error = np . inf
139
+ max_inliers = 0
139
140
p = get_p (K_matrix , positions )
140
141
P = get_P (end_effector_positions )
141
- for i in range (0 ,5000 ):
142
+ for i in range (0 ,50000 ):
143
+ # Sample 6 points
142
144
indices = np .random .randint (0 , noiter , size = 6 )
143
145
M = get_projection_matrix (p [indices ,:], P [indices ,:])
146
+
147
+ # Calculate reprojection error
144
148
homogeneous_P = np .hstack ((P , np .ones ((P .shape [0 ], 1 ))))
145
149
estimated_p = np .matmul (M ,homogeneous_P .T )
146
150
estimated_p = estimated_p / estimated_p [2 ,:]
147
- error = np .linalg .norm (p - estimated_p [0 :2 ,:].T )
148
- print (error )
149
- if error < min_error :
150
- min_error = error
151
- final_M = M
151
+ error = p - estimated_p [0 :2 ,:].T
152
+ error = error [:,0 ]* error [:,0 ] + error [:,1 ]* error [:,1 ]
153
+
154
+ # Find inliers
155
+ inlier_indices = np .unique (np .where (np .abs (error )< 3 ))
156
+ noinliers = np .sum (np .abs (error )< 2 )
157
+ if noinliers > max_inliers :
158
+ max_inliers = noinliers
159
+ final_inliers = inlier_indices
160
+
161
+ final_M = get_projection_matrix (p [final_inliers ,:], P [final_inliers ,:])
162
+ # RQ decomposition
152
163
K ,R = linalg .rq (final_M [:,0 :3 ])
153
- print (K / K [2 ,2 ])
154
- T = np .matmul (np .linalg .inv (K ),final_M [:,3 ])
155
- H = np .vstack ((np .hstack ((R ,T .reshape ((3 ,1 )))),np .array ([[0 ,0 ,0 ,1 ]])))
156
- print (np .linalg .inv (H ))
157
- print (min_error )
158
- return H
164
+ rvec = forwardKinematics .getEulerAngles (np .linalg .inv (R ))
165
+ tvec = np .matmul (np .linalg .inv (K ),final_M [:,3 ])
166
+ H = np .vstack ((np .hstack ((R ,tvec .reshape ((3 ,1 )))),np .array ([[0 ,0 ,0 ,1 ]])))
167
+ print ("Using PnP Algorithm without non-linear optimization " )
168
+ print ("Orientation : {0}" .format (rvec ))
169
+ print ("Position : {0}" .format (tvec ))
170
+ return np .linalg .inv (H )
171
+
159
172
160
173
def get_projection_matrix (p , P ):
161
174
num_points = p .shape [0 ]
@@ -187,7 +200,17 @@ def get_P(end_effector_position):
187
200
point_3D_world_frame = end_effector_position [:,0 :3 ,3 ]
188
201
return point_3D_world_frame
189
202
203
+
204
+ def calculate_extrinsic_opencv (positions , K_matrix , end_effector_positions ):
205
+ p = get_p (K_matrix , positions )
206
+ P = get_P (end_effector_positions )
207
+ success , rvec , tvec , inliers = cv2 .solvePnPRansac (P , p , K_matrix .reshape ((3 ,3 )), distCoeffs = None )
208
+ print ("Using OpenCV solvePnPRansac" )
209
+ print ("Orientation : {0}" .format (rvec .T [0 ]))
210
+ print ("Position : {0}" .format (tvec .T [0 ]))
211
+
190
212
if __name__ == "__main__" :
191
213
main (50 )
192
214
# calib_info = np.load("../data/calibration/calibration_info.npz")
193
- # calculate_extrinsic(calib_info['position'], calib_info['camerainfo'], calib_info['forward_kinematics'], 20)
215
+ # calculate_extrinsic(calib_info['position'], calib_info['camerainfo'], calib_info['forward_kinematics'], 20)
216
+ # calculate_extrinsic_opencv(calib_info['position'], calib_info['camerainfo'], calib_info['forward_kinematics'])
0 commit comments