MapIV / eagleye

Precise localization based on GNSS and IMU.

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

Eagleye covariance values are getting too high after the return.

meliketanrikulu opened this issue · comments

Test Conditions:
I tested eagleye with my data. I am using clapb7 sensor It give us the raw gnss and raw imu data and gnss twist msg (ECEF Twist). All test field is open area , we are using RTK and the raw gnss accuracies are high.

The Problem:
In my test field, generally results are similar to sample data. But just one turning case the covariances values which output of the /eagleye/fix(sensor_msgs/NavsatFix) are getting too high and position breaks. After a while it again decrease.
Here is the result video.
For fixing this problem I changed only heading-outlier_threshold parameter as 0.000524. This breaks is solved with this parameter changes but the covariance values still getting higher. Here is the video after parameter optimization.

Videos explanations: In this videos the red line is the raw gnss data and blue one is the /eagleye/fix(sensor_msgs/NavsatFix) topics output (I use the UTM projection for both of them). You can see /eagleye/fix(sensor_msgs/NavsatFix) topics covariance values on plotjuggler screen.

For reproduce:
Parameter file is here
Test data is here
Map files are here
Please run this command for transformation between sensor and base_link:
ros2 run tf2_ros static_transform_publisher 0.0 0.5 1.1350 0 0 0 base_link GNSS_INS/gnss_ins_link

How can I fix this issue. Is there any suggestion for solving this. Thank you for the contribution and support.

Thank you @meliketanrikulu for opening the issue and providing the data!

@rsasaki0109 is looking into this.

Regarding the covariance values from Eagleye being higher than expected, it seems to be caused by how Eagleye calculates the position covariance (error), i.e., output error = gnss error + error of raw gnss position compared to output trajectory. Now, the gnss error is fixed to 0.5. Therefore, the covariance you see will always be larger than 0.5.

The figure below is how error of raw gnss position compared to output trajectory is calculated.
image

In any case, I think @rsasaki0109 might be able to clarify further if you still have questions.

I looked at the data.
The gnss twist used for eagleye can be adjusted below, but the default of 0.2 [(m/s)^2] seems too large.
Setting it to 1.0 [(m/s)^2] improves it to some extent.

<param name="twist_covariance_thresh" value="0.2"/>

https://github.com/MapIV/eagleye/blob/main-ros2/eagleye_util/gnss_converter/launch/gnss_converter.launch.xml#L13

before
Figure_1_before
after
Figure_1_after

The normal Eagleye trajectory estimation algorithm assumes lane level, so if you are using RTK FIX and have no camera, LiDAR, or other assistance, I feel the following settings should be used.
You need to remap eagleye/fix and set fix_only_publish to true in fix2pose.launch.xml.

<?xml version="1.0" encoding="UTF-8"?>
<launch>
  <arg name="output_pose_with_cov_name" default="/localization/pose_estimator/pose_with_covariance"/>
  <node pkg="eagleye_fix2pose" name="fix2pose_node" exec="fix2pose">
    <!-- /eagleye/fix or  /GNSS/fix(GNSS pose only mode)-->
    <!-- <remap from="eagleye/fix" to="eagleye/fix"/> -->
    <remap from="eagleye/fix" to="/sensing/gnss/ublox/nav_sat_fix"/>
    <remap from="eagleye/pose_with_covariance" to="$(var output_pose_with_cov_name)"/>
    <!-- plane rectangular coordinate number -->
    <param name="plane" value="7"/>
    <!-- 1 : plane rectangular coordinate  2 : MGRS -->
    <param name="tf_num" value="2"/>
    <!-- 0 : No convert  1 : ellipsoid -> altitude  2 : altitude -> ellipsoid -->
    <param name="convert_height_num" value="0"/>
    <!-- 0 : EGM2008-1  1 : Japanese Geoid 2011 Ver2.1 -->
    <param name="geoid_type" value="1"/>

    <param name="parent_frame_id" value="map"/>
    <param name="child_frame_id" value="eagleye_base_link"/>
    <param name="base_link_frame_id" value="base_link"/>
    <param name="gnss_frame_id" value="gnss_link"/>

    <param name="fix_only_publish" value="true"/>
    <!-- 0:fix.status 1:fix.position_covariance[0] (if fix_only_publish==true)-->
    <param name="fix_judgement_type" value="1"/>
    <!--Fix status(if fix_judgement_type is 0)-->
    <param name="fix_gnss_status" value="0"/>
    <!-- Minimum covariance of the pose topics to be published(if fix_judgement_type is 0)-->
    <param name="fix_std_pos_thres" value="0.1"/>
  </node>
</launch>

twist_covariance_thresh

Hello @rsasaki0109 . Its working. Thanks for your support.

error

Hello @n-patiphon . Thanks for information. I am trying to understand. :) As I understand its calculated on this lines (

enu_absolute_pos->covariance[0] = cov_x + position_parameter.gnss_error_covariance; // [m^2]
enu_absolute_pos->covariance[4] = cov_y + position_parameter.gnss_error_covariance; // [m^2]
enu_absolute_pos->covariance[8] = cov_z + position_parameter.gnss_error_covariance; // [m^2]
)

But why we are using fixed value here. I mean there is a gnss position covariance that comes from gnss in our system. Can we use these values instead of this fixed value. Thank for the support .

@meliketanrikulu
In MAP IV, we are using a proprietary GNSS driver, which does not support covariance output. If covariance is included in navsatfix, it might be better to use rtklib_nav.status.position_covariance instead of position_parameter.gnss_error_covariance in position.cpp. I'll deal with it when I have some time.

Okey Thanks for the help @rsasaki0109 . I will test with our gnss covariances instead of this default value. I can create new branch for this on eagleye if you want. Also I think close this issue. Thank you again