jbehley / point_labeler

My awesome point cloud labeling tool
MIT License
647 stars 161 forks source link

About poses.txt #44

Closed zeng-hello-world closed 2 years ago

zeng-hello-world commented 3 years ago
  1. What is the unit of measurement of x,y,z, miter or millimiter?
  2. Which coordinate frame does pose refer to, world coordinate or last frame coordinate?

Thanks!

jbehley commented 3 years ago
  1. KITTI uses meters, I think.
  2. We follow the convention of the original KITTI dataset that these poses are in the coordinate frame of the camera. Therefore, internally the transformation from calib.txt are used to convert it in the LiDAR coordinate system. For custom datasets, you can set these calibration poses to identity and directly use the LiDAR poses in the poses.txt file.
mrsandipandas commented 3 years ago

@jbehley First of all thank you for open-sourcing this amazing toolbox. I have used the code template below to capture the poses for my custom dataset to fit to the need of SemanticKitti. Please review it. I would be happy to open a pull request to put it in your wiki if you feel this is correct and helpful for future users.

Eigen::Vector3d t(x, y, z); // Get the translation from your last pose
Eigen::Quaterniond q(qx, qy, qz, qw); // Get the rotation from your last pose
Eigen::Matrix3d R = q.normalized().toRotationMatrix();
Eigen::Matrix<double, 3, 4> T;
T.block<3,3>(0,0) = R;
T.block<3,1>(0,3) = t;
Eigen::Matrix<double, 4, 3> T_transposed = T.transpose();
Eigen::Map<const Eigen::RowVectorXd> flattened_T (T_transposed.data(), T_transposed.size());

Saving to file to be used along with your point clouds:

std::ofstream filestream;
filestream.open(std::string("~/poses.txt"));
std::stringstream ss;
ss << flattened_T;
filestream << ss.str() << "\n";
filestream.flush();
jbehley commented 3 years ago

thanks for sharing and seems okay, even though I didn't compile it. (I assume that you have to make the transpose of the Eigen Matrix as it is stored in column-major format and then T.data() would give you the columns instead of the rows.) As this is very specific for your use case, I think it's okay to leave it here.

For other people trying to understand how the poses.txt works (you can also look this up in the KITTI Odometry devkit), I here shortly summarize it for future reference:

Each line of the poses.txt is a global transformation for the scan at time t represented as a homogeneous transformation matrix (4x4) in row-wise format, where the last line is implicit. (Therefore only 12 values instead of 16).

More concretely, suppose your transformation is T = [R|t], with Rotation matrix R and translation vector t :

    [R_11 R_12 R_13 t_1]
T = [R_21 R_22 R_23 t_2]
    [R_31 R_32 R_33 t_3]
    [  0    0   0    1 ]

Then the t-th row contains 12 values corresponding to:

R_11  R_12  R_13  t_1 R_21  R_22  R_23  t_2 R_31  R_32  R_33  t_3
zeng-hello-world commented 3 years ago

2. We follow the convention of the original KITTI dataset that these poses are in the coordinate frame of the camera

means use coordinate system like below? image

jbehley commented 3 years ago

See http://www.cvlibs.net/datasets/kitti/setup.php

The x axis points right, the y axis points downward and the z axis points forward. (right-handed coordinate system.)

jbehley commented 2 years ago

As there seems to be no update on the issue, I will close it for now. If you have further questions, then reopen the issue again.