arclab-hku / Event_based_VO-VIO-SLAM

Our Works in Event-based VO/VIO/SLAM

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

exact error metrics

knelk opened this issue · comments

commented

Dear all, thanks for the great work.

Which exact error metrics do you show in your paper?

You write that MPE (%) / MRE (deg/m) is computed with the EVO-tool. However, I can not find MPE (%) and MRE (deg/m) directly on the evo-github https://github.com/MichaelGrupp/evo/tree/master

What am I missing? Or did you adopt the EVO-tool? If yes, how exactly do you do the error computation? can you please share the logic / formula / best-case the code for evaluation?

You also write that you

The estimated and ground-truth trajectories were aligned with a 6-DOF transformation (in SE3), using 5 seconds [0-5s] of the resulting trajectory. The result is obtained through computing the mean position error (Euclidean distance in meters) as percentages of the total traveled distance of the ground truth.

which raises another set of question to me:

  1. Why do you write [0-5s]? Do you sample 5s-long pieces, or of the interval [0-5]s?
  2. Where does the 5s-interval start? Do you sample 5s intervals => so in the end, it is like a relative error?

Another open question, how do you compute MRE in deg/m, if you describe the sampling above in seconds? To get deg/m you need to compute the relative error according to this paper: https://rpg.ifi.uzh.ch/docs/IROS18_Zhang.pdf. This is at least what I understand as relative error, but please correct me.

Thanks!

Hi, thanks for your interests~

Problem 1: Which exact error metrics do you show in your paper?
Answer 1: In the paper ESVIO, we use MPE (%) / MRE (deg/m) as error metrics, these error metrics are absolute pose error (normalized by trajectory path length). In the IROS paper and PLEVIO, we use RMSE as error metrics.

Problem 2: However, I can not find MPE (%) and MRE (deg/m) directly on the evo-github https://github.com/MichaelGrupp/evo/tree/master.
Answer 2: Yes, you can not find these two error metrics directly on the evo tool. MPE (%) = The mean position error (m)/ total length (m). You can get the mean error and the total length by evo tool. MRE (deg/m) = The mean rotation error (deg)/ total length (m). You can also get the above info by evo tool. The definition of MPE and MRE can be found in Ultimate-SLAM: https://arxiv.org/pdf/1709.06310.pdf

Problem 3: Why do you write [0-5s]? Do you sample 5s-long pieces, or of the interval [0-5]s? Where does the 5s-interval start? Do you sample 5s intervals => so in the end, it is like a relative error?
Answer 3: The [0-5s] represents that we only align the estimated trajectory with the ground-truth during [0-5s]. For the rest trajectory, we do not align them so that the error can reflect the drift of the estimated trajectory after a long-term motion. It is not a relative error.

By the way, in the IROS paper, we only align the trajectory during [0-5s]. But in the ESVIO paper, we align the whole trajectory with the ground-truth.

Hope these answers can solve your problems.

commented

Thanks a lot for the very detailed answers!

This helps me a lot :) Also thanks for providing your estimated & GT trajectories, which allows for an additional clean comparison with your method.

commented

Unfortunately, I can not reproduce your numbers on vector ESVIO, using your published trajectories (ESVIO estimates & GT) [published here: https://github.com/arclab-hku/Event_based_VO-VIO-SLAM/blob/main/Results_for_comparison.md]

Do you align the trajectories? If yes, do you use correct_scale, correct_only_scale in traj_est_aligned.align(traj_ref, correct_scale=True, correct_only_scale=False)?

What is your max_diff param in:

traj_ref = file_interface.read_tum_trajectory_file(fnamegt)
traj_est = file_interface.read_tum_trajectory_file(fnameest)
max_diff = 0.01
traj_ref, traj_est = sync.associate_trajectories(traj_ref, traj_est, max_diff)

I am basically following this tutorial: https://github.com/MichaelGrupp/evo/blob/77fce6d1822e2af3f56d1ee0aa1698a46b76ac7e/notebooks/metrics.py_API_Documentation.ipynb, using APE, e.g.
ape_stats = ape_metric.get_all_statistics() APE = ape_stats["mean"] / traj_len

Do you do something else in post/pre-processing, e.g. interpolate the estimated trajectory at the ground-truth-timetamps?

For ESVIO_hku_agg_translation.bag, we use the following command to get error

evo_ape bag ESVIO_hku_agg_translation.bag /cpy_uav/viconros/odometry /pose_graph/evio_odometry -va -p

then we have the mean position error is 0.063426m as shown in this pic
微信图片_202307020011481

And we use the following command to get the path length

evo_traj bag ESVIO_hku_agg_translation.bag /cpy_uav/viconros/odometry

The path is 62.214m as shown in this pic
微信图片_20230702001148

Finally, we can calculate the result based on the formula of MPE (%) = 0.063426/62.214 = 0.0010 = 0.1%. The ESVIO result is same as the Table I. hku agg translation sequence

commented

Great, thanks for the quick answer! Following your formula and description, I can get the same MPE(%) now, but not the MRE(deg/m), e.g. not on robot-normal-esvio (vector dataset).

The GT trajectory length is:

(env) s@s:~$ evo_traj bag ESVIO_VECtor_robot_normal.bag /gt/pose
--------------------------------------------------------------------------------
name:	/gt/pose
infos:	4286 poses, 3.996m path length, 35.708s duration

but the rotational error is very large, e.g.

(env) s@s:~$ evo_ape bag ESVIO_VECtor_robot_normal.bag /gt/pose /pose_graph/evio_odometry -a -r "angle_deg"
APE w.r.t. rotation angle in degrees (deg)
(with SE(3) Umeyama alignment)

       max	135.627477
      mean	133.341757
    median	133.236530
       min	130.808601
      rmse	133.345081
       sse	76208982.977081
       std	0.941480

or alternatively without Umeyama alignment (for debugging)

(env) s@s:~$ evo_ape bag ESVIO_VECtor_robot_normal.bag /gt/pose /pose_graph/evio_odometry -r "angle_deg"
APE w.r.t. rotation angle in degrees (deg)
(not aligned)

       max	89.479937
      mean	43.858268
    median	36.403736
       min	22.552827
      rmse	47.522934
       sse	9679627.808406
       std	18.299771

Both cases would yield 133.341757deg/3.996m = 33.368 deg/m or 43.85826/3.006 = 10.9755 deg/m.
The value in your ESVIO paper is 1.17 deg/m, so I must be doing something wrong still

This is caused by the coordinate of estimated odometry is different from the coordinate of GT. So this needs to align the global attitude. However, evo is not able to align the attitude. So you can consider writing a code based on the following idea: convert both the quaternion of the estimated trajectory and the quaternion of the GT to Euler angles, and save thses Euler angles(roll, pitch, yaw) under nav_msgs::Odometry data format(x,y,z part). Then you can use evo to align the estimated Euler angle with the Euler angle of GT. Finally MRE(deg/m) = The mean rotation error(deg) / total length(m).

Similarly, although the coordinate system of ESVIO is the same as the GT coordinate in the HKU Dataset. To ensure that all data are processed identically. So we have also used evo to align the attitude and obtain the MRE(deg/m).

Here we presents the codes of changing quaternion to Euler angles:

void gt_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& gt_pose){
    Vector3d vio_rpy;
    Quaterniond vio_q;
    vio_q.w() = gt_pose->pose.orientation.w;
    vio_q.x() = gt_pose->pose.orientation.x;
    vio_q.y() = gt_pose->pose.orientation.y;
    vio_q.z() = gt_pose->pose.orientation.z;

    // roll (x-axis rotation)
    double sinr_cosp = +2.0 * (vio_q.w() * vio_q.x() + vio_q.y() * vio_q.z());
    double cosr_cosp = +1.0 - 2.0 * (vio_q.x() * vio_q.x() + vio_q.y() * vio_q.y());
    double roll = atan2(sinr_cosp, cosr_cosp) * 180 / M_PI;

    // pitch (y-axis rotation)
    double sinp = +2.0 * (vio_q.w() * vio_q.y() - vio_q.z() * vio_q.x());
    double pitch;
    if (fabs(sinp) >= 1)
        pitch = copysign(M_PI / 2, sinp) * 180 / M_PI; // use 90 degrees if out of range
    else
        pitch = asin(sinp) * 180 / M_PI;

    // yaw (z-axis rotation)
    double siny_cosp = +2.0 * (vio_q.w() * vio_q.z() + vio_q.x() * vio_q.y());
    double cosy_cosp = +1.0 - 2.0 * (vio_q.y() * vio_q.y() + vio_q.z() * vio_q.z());
    double yaw = atan2(siny_cosp, cosy_cosp) * 180 / M_PI;

    ///publish odometry
    nav_msgs::Odometry new_gt_pose;
    new_gt_pose.header = gt_pose->header;
    new_gt_pose.header.frame_id = "world";
    new_gt_pose.pose.pose.position.x = roll;
    new_gt_pose.pose.pose.position.y = pitch;
    new_gt_pose.pose.pose.position.z = yaw;
    new_gt_pose.pose.pose.orientation.x = vio_q.x();
    new_gt_pose.pose.pose.orientation.y = vio_q.y();
    new_gt_pose.pose.pose.orientation.z = vio_q.z();
    new_gt_pose.pose.pose.orientation.w = vio_q.w();
    new_gt_pose.twist.twist.linear.x = 0;
    new_gt_pose.twist.twist.linear.y = 0;
    new_gt_pose.twist.twist.linear.z = 0;
    pub_gt_pose.publish(new_gt_pose);
}