-
Notifications
You must be signed in to change notification settings - Fork 60
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Transformation for 'camera-pose-matrix' ? #56
Comments
Thank you very much for using MC-Calib; from the plot you shared, it seems that MC-Calib did a great job at calibrating your system if the camera system is indeed a full-surrounding vision system. Did you get a satisfying reprojection error for this? Is the 3D object reconstruction consistent with your cube? My first guess is simply that the poses should all be inverted for your reconstruction pipeline. Maybe you can try modifying the line by removing the Please let us know if this modification resolves your problem. |
Thanks for reply, it's reprojection error is good for our application but seems some things of results does not match with our pipeline. Actually I've already tried with 'removing .inv()' as you've mentioned and our pipline worked with that, but result seems very small parts of object was processed in our pipeline. Check this:
I found some differences in above results, values of Y-axis are too low than our old result, so I think it does not get whole object as a pipeline target. Is there any simple solution to adjust Y-axis value to place on higher position in plot results ? Thanks, |
Thank you very much for the details; the problem is not strictly coming from the calibration itself, but mostly from the 3D reconstruction pipeline you are using, which requires some specifications that are unknown to me. Are you using an open-source reconstruction software? What I can see is that in your original calibration result, the referential is located more or less at the converging point of all the principal axes of your cameras. import numpy as np
import cv2
def load_camera_data(file_path):
fs = cv2.FileStorage(file_path, cv2.FILE_STORAGE_READ)
nb_cameras = int(fs.getNode("nb_camera").real())
camera_data = {}
for i in range(nb_cameras):
cam_id = f"camera_{i}"
camera_data[cam_id] = {
"camera_pose_matrix": fs.getNode(cam_id).getNode("camera_pose_matrix").mat(),
# Load other data as needed
}
fs.release()
return camera_data, nb_cameras
import numpy as np
from scipy.optimize import minimize
def extract_principal_axes(camera_data):
axes = []
for cam_id, data in camera_data.items():
pose_matrix = data["camera_pose_matrix"]
position = pose_matrix[:3, 3]
direction = pose_matrix[:3, 2] # Assuming the principal axis is the Z-axis of the camera
axes.append((position, direction))
return axes
def distance_to_line(point, line):
point = np.asarray(point)
position, direction = line
return np.linalg.norm(np.cross(direction, point - position)) / np.linalg.norm(direction)
def convergence_point(axes):
def objective(point):
return sum(distance_to_line(point, line)**2 for line in axes)
initial_guess = np.mean([pos for pos, _ in axes], axis=0)
result = minimize(objective, initial_guess, method='Powell')
return result.x
def update_camera_poses(camera_data, center):
for cam_id, data in camera_data.items():
pose_matrix = data["camera_pose_matrix"]
# Adjust pose here. Example: subtract center from translation part
pose_matrix[:3, 3] -= center
camera_data[cam_id]["camera_pose_matrix"] = pose_matrix
return camera_data
def save_camera_data(file_path, camera_data, nb_cameras):
fs = cv2.FileStorage(file_path, cv2.FILE_STORAGE_WRITE)
fs.write("nb_camera", nb_cameras)
for cam_id, data in camera_data.items():
fs.startWriteStruct(cam_id, cv2.FileNode_MAP)
fs.write("camera_pose_matrix", data["camera_pose_matrix"])
# Write other data as needed
fs.endWriteStruct()
fs.release()
# Load original data
path_calib_results = "calib.yml"
camera_data, nb_cameras = load_camera_data(path_calib_results)
# Extract principal axes from camera data
principal_axes = extract_principal_axes(camera_data)
# Find convergence point
convergence_center = convergence_point(principal_axes)
# Update camera poses
camera_data = update_camera_poses(camera_data, convergence_center)
# Save modified data
path_modified_calib_results = "modified_calibration.yml"
save_camera_data(path_modified_calib_results, camera_data, nb_cameras) If you want to modify the Y-axis elevation of your cameras, you might want to modify this code. Please let me know if it helps and also do not hesitate to share what 3D reconstruction software you are using, it might help us understand better how to adjust the calibration results. |
Hi, thanks a lot, Your recent advice does not make sense in our pipeline, although removing ".inv()" couldn't make good result(seems part of 3D volume were inspected) but it worked through final step in pipeline but it couldn't do any further process with above code (seems some translation values were changed). Actually our 3D reconstruction pipeline uses 'voxel' based carving from synchronized multiple camera images so first step of 'making voxel set from visual-hull' is very important (precised extrinsics will make more quality in mixing carved volume). (Sorry about to share our software because of internal rule and license issues.) Anyway, I tried some changes like below to match plotted data as above 'old calibration data' (so it turned all camera direction were heading to outside of center, but not worked in pipeline):
Is above logic make sense ? |
Hello, sorry for the delayed reply, I am just back to work. I think I figure out how to transform the MC-Calib extrinsic into your original format, I figured this out by experimenting with Matlab. Here is my code snippet: % Poses mc_calib
P1_0 = [ 1., 0., 0., 0., 0., 1., 0., 0., 0., 0., 1., 0., 0., 0., 0., 1. ]
P1_1 = [ 9.3721409754506535e-01, -4.8487413819241591e-02, 3.4536749422015706e-01, -1.1615160240120219e+00, 4.7096107136164231e-02, 9.9881310030790837e-01, 1.2423660729542174e-02, -5.1198943311429670e-02, -3.4555996882655204e-01, 4.6218345302971794e-03, 9.3838528685725175e-01, 2.8873852221720903e-01, 0., 0., 0., 1. ]
P1_2 = [ 4.7959549131053109e-01, -2.5165862374442388e-01, 8.4062839698030223e-01, -2.5089514028069484e+00, 2.4081171318453279e-01, 9.5895834391790491e-01, 1.4969506813305264e-01, -3.3914593353855838e-01, -8.4379967024628555e-01, 1.3064008468035934e-01, 5.2051444241919742e-01, 1.1763415917803814e+00, 0., 0., 0., 1. ]
P1_0 = reshape(P1_0,4,4)'
P1_1 = reshape(P1_1,4,4)'
P1_2 = reshape(P1_2,4,4)'
% wand
P2_0 = [ 0.977376, -0.00253638, 0.211494, 0.18243, 0.107001, 0.868464, -0.484067, 1.59661, -0.182447, 0.495745, 0.849087, 6.56182, 0., 0., 0., 1. ]
P2_1 = [ 0.983759, -0.133839, -0.119605, -0.871716, 0.0586753, 0.869522, -0.490396, 1.60601, 0.169634, 0.475414, 0.863253, 6.38071, 0., 0., 0., 1. ]
P2_2 = [ 0.651279, -0.208894, -0.72952, -2.82728, -0.165888, 0.898918, -0.405497, 1.9035, 0.740485, 0.38511, 0.550793, 5.33995, 0., 0., 0., 1. ]
P2_0 = reshape(P2_0,4,4)'
P2_1 = reshape(P2_1,4,4)'
P2_2 = reshape(P2_2,4,4)'
% put in the same referencial
P1_0_Corrected = inv(P1_0)*P2_0
P1_1_Corrected = inv(P1_1)*P2_0
P1_2_Corrected = inv(P1_2)*P2_0
% error
P1_0_Corrected - P2_0
P1_1_Corrected - P2_1
P1_2_Corrected - P2_2 Basically, I used the pose of your first camera as refencial that I can call I hope it helps! |
Thanks, But I couldn't fully understood, did u found solution after above simulation or just experiment against two results ? You've used pose of first camera from our Wand results as a reference but this Wand result couldn't be used before we do 'wand-style' calibration steps, ( I'm not sure, did you consider this situation ?) Do you mean 'inv(MC-Calib_pose)' is 'inverting' after general MC-Calib process (it already has 'inv' when return results) ? |
Sorry for the super delayed reply. Regarding the invention of the poses, it is all a matter of convention, MC-Calib seems to output the inverse of Wand. It is like instead of providing M_{12} it returns the pose is M_{21} (M being a 4x4 homogeneous transformation matrix). |
System information (version)
Vision system
calib_configuration.zip
(i.e.
*.yml
)Describe the issue / bug
Please provide a clear and concise description of what the issue / bug is.
Hi, we're tried to use this toolbox for multi-view camera system based reconstruction,
but we couldn't get proper results in our reconstruction pipeline (this pipeline were worked properly with our old style calibration data).
F.Y.I)
We made ChAruCo-Cube for multi-camera setup:
calibration for old pipeline were done with 'camera-matrix' from MC-Calib and get extrinsic using old style 'Wand' approaches.
Actually we found 'camera-pose-matrix' values are not match to our old pipeline, but we're not sure any custom could be done in your MC-Calib sources. Here're comparison MC-Calib and our old pipeline data (just modified 'calibrated_cameras_data.yml' file in 'camera-pose-matrix' block):
And check these original results with 'python_utils':
result_1.zip
result_2.zip
Could you give some advice for this problem ? (I think some transformation in 'camera-pose-matrix' can clear this issue but don't know where to start...)
Thanks,
The text was updated successfully, but these errors were encountered: