Giter Club home page Giter Club logo

eagleye's Introduction

example workflow

Demo Video

What is Eagleye

Eagleye is an open-source software for vehicle localization utilizing GNSS and IMU[1]. Eagleye provides highly accurate and stable vehicle position and orientation by using GNSS Doppler[2][3][4][5][6]. The flowchart of the algorithm is shown in the figure below. The algorithms in this software are based on the outcome of the research undertaken by Machinery Information Systems Lab (Meguro Lab) in Meijo University.

Flowchart of Eagleye

Architecture

Architecture of Eagleye

Recommended Sensors

GNSS receiver

GNSS Antenna

IMU

Wheel speed sensor

  • Eagleye uses vehicle speed acquired from CAN bus.

How to install

RTKLIB

Clone and Build MapIV's fork of RTKLIB. You can find more details about RTKLIB here.

sudo apt-get install gfortran
cd $HOME
git clone -b rtklib_ros_bridge_b34 https://github.com/MapIV/RTKLIB.git
cd $HOME/RTKLIB/lib/iers/gcc/
make
cd $HOME/RTKLIB/app/consapp
make

ROS Packages

Clone and build the necessary packages for Eagleye.

pip install vcstool
cd $HOME/catkin_ws/src
git clone https://github.com/MapIV/eagleye.git -b main-ros1
vcs import . < eagleye/eagleye.repos
sudo apt-get install -y libgeographic-dev geographiclib-tools geographiclib-doc
sudo geographiclib-get-geoids best
sudo mkdir /usr/share/GSIGEO
sudo cp llh_converter/data/gsigeo2011_ver2_1.asc /usr/share/GSIGEO/
cd ..
rosdep install --from-paths src --ignore-src -r -y
catkin_make -DCMAKE_BUILD_TYPE=Release

Configuration

GNSS

ublox f9p settings

septentrio mosaic settings

IMU

  1. IMU settings.
  • Output rate 50Hz
  1. Check the rotation direction of z axis of IMU being used. If you look from the top of the vehicle, if the left turn is positive, set pitch to 3.14159 in eagleye/eagleye_util/tf/config/sensors_tf.yaml.

      pitch: 3.14159
    

Start each sensor driver

  1. Check if wheel speed (vehicle speed) is published in /can_twist topic.
  • Topic name: /can_twist
  • Message type: geometry_msgs/TwistStamped twist.liner.x
  1. Check if the IMU data is published in /imu/data_raw topic.

  2. Start RTKLIB.

    ex. single point positioning

     cd $HOME/RTKLIB
     bash rtklib_ros_bridge_single.sh
    

    ex. Real Time Kinematic

     cd $HOME/RTKLIB
     bash rtklib_ros_bridge_meijo_rtk.sh
    
  3. Check if RTKLIB is working by execute the following command in the terminal. If the RTKLIB is working correctly, positioning information is appeared continuously in the terminal.

     status 0.1
    
  4. Start rtklib_ros_bridge.

     roslaunch rtklib_bridge rtklib_bridge.launch
    
  5. Start nmea_comms in f9p or nmea_ros_bridge in mosaic.

     roslaunch nmea_comms f9p_nmea_sentence.launch
    

    or

     roslaunch nmea_ros_bridge nmea_udp.launch
    

eagleye_rt

Optional Features

can_less mode

While normal eagleye requires CAN (wheel speed) information, this option allows localization estimation with GNSS/IMU alone, without vehicle speed.

However, in this mode, note the following

  • Accuracy degrades in non-open sky environments.
  • RTK positioning is required.
  • Localization estimating is not possible when driving backward.

To use this mode

  • Use launch/eagleye_rt_can_less.launch for eagleye_rt instead of launch/eagleye_rt.launch.

dual antenna mode

This option allows for more immediate heading estimatiion, and allows GNSS to estimate heading even at low speeds.

To use this mode

  • Use launch/eagleye_rt_dualantenna.launch for eagleye_rt instead of launch/eagleye_rt.launch.

Sample data

ROSBAG

No. Date Place Sensors Link
1 2020/01/27 Moriyama, Nagoya
route
GNSS: Ublox F9P
IMU: Tamagawa AU7684
LiDAR: Velodyne HDL-32E
Download
2 2020/07/15 Moriyama, Nagoya
route
GNSS: Ublox F9P with RTK
IMU: Tamagawa AU7684
LiDAR: Velodyne VLP-32C
Download

Maps

The 3D maps (point cloud and vector data) of the route is also available from Autoware sample data.

Research Papers for Citation

  1. A. Takanose, et., al., "Eagleye: A Lane-Level Localization Using Low-Cost GNSS/IMU", Intelligent Vehicles (IV) workshop, 2021 Link

  2. J Meguro, T Arakawa, S Mizutani, A Takanose, "Low-cost Lane-level Positioning in Urban Area Using Optimized Long Time Series GNSS and IMU Data", International Conference on Intelligent Transportation Systems(ITSC), 2018 Link

  3. Takeyama Kojiro, Kojima Yoshiko, Meguro Jun-ichi, Iwase Tatsuya, Teramoto Eiji, "Trajectory Estimation Based on Tightly Coupled Integration of GPS Doppler and INS" -Improvement of Trajectory Estimation in Urban Area-, Transactions of Society of Automotive Engineers of Japan 44(1) 199-204, 2013 Link

  4. Junichi Meguro, Yoshiko Kojima, Noriyoshi Suzuki, Teramoto Eiji, "Positioning Technique Based on Vehicle Trajectory Using GPS Raw Data and Low-cost IMU", International Journal of Automotive Engineering 3(2) 75-80, 2012 Link

  5. K Takeyama, Y Kojima, E Teramoto, "Trajectory estimation improvement based on time-series constraint of GPS Doppler and INS in urban areas", IEEE/ION Position, Location and Navigation Symposium(PLANS), 2012 Link

  6. Junichi Meguro, Yoshiko Kojima, Noriyoshi Suzuki, Eiji Teramoto, "Automotive Positioning Based on Bundle Adjustment of GPS Raw Data and Vehicle Trajectory", International Technical Meeting of the Satellite Division of the Institute of Navigation (ION), 2011 Link

  7. Yoshiko Kojima, et., al., "Precise Localization using Tightly Coupled Integration based on Trajectory estimated from GPS Doppler", International Symposium on Advanced Vehicle Control(AVEC), 2010 Link

License

Eagleye is provided under the BSD 3-Clause License.

Contacts

If you have further question, email to [email protected].

eagleye's People

Contributors

aoki-takanose avatar n-hachi avatar osamusekino avatar rsasaki0109 avatar takahirokashimoto avatar tomoya-sato avatar wat-r avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

eagleye's Issues

Position seems to be offsetted in Eagleye. What could be causing this?

The yellow dot in the below video is the ground truth and the blue dot is the estimated location provided by Eagleye. I am using the autoware-main branch

Here is the parameter file being used

/**: #GNSS cycle 5Hz, IMU cycle 50Hz.
  ros__parameters:
    # Estimate mode
    use_gnss_mode: rtklib
    use_can_less_mode: false
    use_multi_antenna_mode: true

    # Topic
    twist:
      twist_type: 0 # TwistStamped : 0, TwistWithCovarianceStamped: 1
      twist_topic: /eagleye_input/can_twist
    imu_topic: /novatel_interface/imu
    gnss:
      velocity_source_type: 3 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3
      velocity_source_topic: /novatel_interface/twist
      llh_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
      llh_source_topic: /novatel_interface/fix
    sub_gnss:
      llh_source_type: 2 # nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
      llh_source_topic:  /sensing/sub_gnss/ublox/nav_sat_fix

    # TF
    tf_gnss_frame:
      parent: "base_link"
      child: "novatel"

    # Origin of GNSS coordinates (ECEF to ENU)
    ecef_base_pos:
      x: 0.0
      y: 0.0
      z: 0.0
      use_ecef_base_position: false

    reverse_imu_wz: false

    # Navigation Parameters
    # Basic Navigation Functions
    common:
      imu_rate: 100
      gnss_rate: 20
      stop_judgment_threshold: 0.01
      slow_judgment_threshold: 0.278
      moving_judgment_threshold: 2.0

    velocity_scale_factor:
      estimated_minimum_interval: 20
      estimated_maximum_interval: 400
      gnss_receiving_threshold: 0.25
      save_velocity_scale_factor: false
      velocity_scale_factor_save_duration: 100.0
      th_velocity_scale_factor_percent: 10.0

    yaw_rate_offset_stop:
      estimated_interval: 3
      outlier_threshold: 0.002

    yaw_rate_offset:
      estimated_minimum_interval: 30
      gnss_receiving_threshold: 0.25
      outlier_threshold: 0.002
      1st:
        estimated_maximum_interval: 300
      2nd:
        estimated_maximum_interval: 500

    heading:
      estimated_minimum_interval: 10
      estimated_maximum_interval: 30
      gnss_receiving_threshold: 0.25
      outlier_threshold: 0.0524
      outlier_ratio_threshold: 0.5
      curve_judgment_threshold: 0.0873
      init_STD: 0.0035 #[rad] (= 0.2 [deg])

    heading_interpolate:
      sync_search_period: 2
      proc_noise: 0.0005 #[rad] (= 0.03 [deg])

    slip_angle:
      manual_coefficient: 0.0

    slip_coefficient:
      estimated_minimum_interval: 2
      estimated_maximum_interval: 100
      curve_judgment_threshold: 0.017453
      lever_arm: 0.0

    rolling:
      filter_process_noise: 0.01
      filter_observation_noise: 1

    trajectory:
      curve_judgment_threshold: 0.017453
      timer_update_rate: 10
      deadlock_threshold: 1
      sensor_noise_velocity: 0.05
      sensor_scale_noise_velocity: 0.02
      sensor_noise_yaw_rate: 0.01
      sensor_bias_noise_yaw_rate: 0.1

    smoothing:
      moving_average_time: 3
      moving_ratio_threshold: 0.1

    height:
      estimated_minimum_interval: 200
      estimated_maximum_interval: 2000
      update_distance: 0.1
      gnss_receiving_threshold: 0.1
      outlier_threshold: 0.3
      outlier_ratio_threshold: 0.5
      moving_average_time: 1

    position:
      estimated_interval: 300
      update_distance: 0.1
      outlier_threshold: 3.0
      gnss_receiving_threshold: 0.25
      outlier_ratio_threshold: 0.5

    position_interpolate:
      sync_search_period: 2

    # Optional Navigation Functions
    angular_velocity_offset_stop:
      estimated_interval: 4
      outlier_threshold: 0.002

    rtk_dead_reckoning:
      rtk_fix_STD: 0.3 #[m]
      proc_noise: 0.05 #[m]

    rtk_heading:
      update_distance: 0.3
      estimated_minimum_interval: 10
      estimated_maximum_interval: 30
      gnss_receiving_threshold: 0.25
      outlier_threshold: 0.0524
      outlier_ratio_threshold: 0.5
      curve_judgment_threshold: 0.0873

    enable_additional_rolling:
      update_distance: 0.3
      moving_average_time: 1
      sync_judgment_threshold: 0.01
      sync_search_period: 1

    velocity_estimator:
      gga_downsample_time: 0.5
      stop_judgment_velocity_threshold: 0.2
      stop_judgment_interval: 1
      variance_threshold: 0.000025
      pitch_rate_offset:
        estimated_interval: 8
      pitching:
        estimated_interval: 5
        outlier_threshold: 0.0174
        gnss_receiving_threshold: 0.2
        outlier_ratio_threshold: 0.5
      acceleration_offset:
        estimated_minimum_interval: 30
        estimated_maximum_interval: 500
        filter_process_noise: 0.01
        filter_observation_noise: 1
      doppler_fusion:
        estimated_interval: 4
        gnss_receiving_threshold: 0.2
        outlier_ratio_threshold: 0.5
        outlier_threshold: 0.1

And here is the launch file

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from base_common.launch import create_node_name_with_launch_var, get_sim_time_launch_arg, get_share_file

## TODO(github/sisaha9): Look into replacing all the namespaces with PushRosNamespace

def generate_launch_description():
    declare_use_sim_time_cmd, use_sim_time = get_sim_time_launch_arg()
    eagleye_config_fp = DeclareLaunchArgument("eagleye_config_fp", default_value="None", description="Path to the eagleye config file to use")
    unique_identifier = DeclareLaunchArgument("unique_identifier", default_value="None", description="Unique identifier to use")
    
    twist_relay_node = Node(
        package="eagleye_rt",
        executable="twist_relay",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_twist_relay",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time
        ],
    )
    
    tf_converted_imu_node = Node(
        package="eagleye_rt",
        executable="tf_converted_imu",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_tf_converted_imu",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time
        ]
    )
    
    velocity_scale_factor_node = Node(
        package="eagleye_rt",
        executable="velocity_scale_factor",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_velocity_scale_factor",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            { "velocity_scale_factor_save_str": (
                get_share_file("autoware_localization_launch", "config"),
                "/",
                LaunchConfiguration("unique_identifier"),
                "/velocity_scale_factor.txt",
            ),
            "yaml_file" : LaunchConfiguration("eagleye_config_fp")
            }
        ]
    )
    
    yaw_rate_offset_stop_node = Node(
        package="eagleye_rt",
        executable="yaw_rate_offset_stop",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_yaw_rate_offset_stop",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    yaw_rate_offset_node_1st = Node(
        package="eagleye_rt",
        executable="yaw_rate_offset",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_yaw_rate_offset_1st",
        arguments=["1st"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    yaw_rate_offset_node_2nd = Node(
        package="eagleye_rt",
        executable="yaw_rate_offset",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_yaw_rate_offset_2nd",
        arguments=["2nd"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    heading_node_1st = Node(
        package="eagleye_rt",
        executable="heading",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_heading_1st",
        arguments=["1st"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    heading_node_2nd = Node(
        package="eagleye_rt",
        executable="heading",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_heading_2nd",
        arguments=["2nd"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]   
    )
    
    heading_node_3rd = Node(
        package="eagleye_rt",
        executable="heading",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_heading_3rd",
        arguments=["3rd"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]   
    )
    
    heading_interpolate_node_1st = Node(
        package="eagleye_rt",
        executable="heading_interpolate",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_heading_interpolate_1st",
        arguments=["1st"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    heading_interpolate_node_2nd = Node(
        package="eagleye_rt",
        executable="heading_interpolate",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_heading_interpolate_2nd",
        arguments=["2nd"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    heading_interpolate_node_3rd = Node(
        package="eagleye_rt",
        executable="heading_interpolate",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_heading_interpolate_3rd",
        arguments=["3rd"],
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    slip_angle_node = Node(
        package="eagleye_rt",
        executable="slip_angle",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_slip_angle",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    distance_node = Node(
        package="eagleye_rt",
        executable="distance",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_distance",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time
        ]
    )
    
    trajectory_node = Node(
        package="eagleye_rt",
        executable="trajectory",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_trajectory",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    position_node = Node(
        package="eagleye_rt",
        executable="position",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_position",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    position_interpolate_node = Node(
        package="eagleye_rt",
        executable="position_interpolate",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_position_interpolate",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    smoothing_node = Node(
        package="eagleye_rt",
        executable="smoothing",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_smoothing",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    height_node = Node(
        package="eagleye_rt",
        executable="height",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_height",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    angular_velocity_offset_stop_node = Node(
        package="eagleye_rt",
        executable="angular_velocity_offset_stop",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_angular_velocity_offset_stop",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")},
        ]
    )
    
    correction_imu_node = Node(
        package="eagleye_rt",
        executable="correction_imu",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_correction_imu",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time
        ]
    )
    
    rolling_node = Node(
        package="eagleye_rt",
        executable="rolling",
        namespace=LaunchConfiguration("unique_identifier"),
        name="eagleye_rolling",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time,
            {"yaml_file" : LaunchConfiguration("eagleye_config_fp")}
        ]
    )
    
    gnss_converter_node = Node(
        package="eagleye_gnss_converter",
        executable="gnss_converter",
        namespace=(
            LaunchConfiguration("unique_identifier"),
            "/gnss"
        ),
        name="eagleye_gnss_converter",
        parameters=[
            LaunchConfiguration("eagleye_config_fp"),
            use_sim_time
        ]
    )
    
    return LaunchDescription([
        declare_use_sim_time_cmd,
        eagleye_config_fp,
        unique_identifier,
        twist_relay_node,
        tf_converted_imu_node,
        velocity_scale_factor_node,
        yaw_rate_offset_stop_node,
        yaw_rate_offset_node_1st,
        yaw_rate_offset_node_2nd,
        heading_node_1st,
        heading_node_2nd,
        heading_node_3rd,
        heading_interpolate_node_1st,
        heading_interpolate_node_2nd,
        heading_interpolate_node_3rd,
        slip_angle_node,
        distance_node,
        trajectory_node,
        position_node,
        position_interpolate_node,
        smoothing_node,
        height_node,
        angular_velocity_offset_stop_node,
        correction_imu_node,
        rolling_node,
        gnss_converter_node
    ])

”slip_angle” Possible bug

The estimated coefficient is too large (eg -9.53e + 220)

As a result, heading and yaw-rate errors cannot be estimated.

eagleye for robots

Hello, this is a great package. Has there been any testing done with differential drive vehicles/robots?

Neccessary topics for bag file

Hi, i want to run with rosbag file. eagle_topic.yaml include rtklib_nav_topic: /rtklib_nav
navsatfix_topic: /f9p/fix nmea_sentence_topic: /f9p/nmea_sentence topics. Are these topics neccessary for bag file, and what topics neccessary for bag file.

Add heading information from driver

First of all thanks for the amazing package.
I have a question regarding the heading source. In dual antenna setups you are fusing the input from both antennas seperately.
I understand that the driver is intended to work with raw values through rtk lib instead of driver specific messages.
For me it would be interesting to fuse heading from the driver directly (as sensor_msg/Imu) instead of using multi antenna mode. Is this possible?
My intention to use this package this way is to use params like antenna::hading offset.

There is a problem in the calculation of slip angle in heading.cpp and heading interpolate.cpp

There is a problem with the calculation of slip angle in heading.cpp and heading interpolate.cpp, so the estimated trajectory is strange.

eagleye_config.yaml

slip_angle:
slip_angle_estimate: false #When the estimate is not valid, the manual_coefficient factor is used
manual_coefficient: 0.0 #If you do not want to correct slip angle, set slip angle estimate to false and set the coefficient here to 0
estimated_number_min: 200
estimated_number_max: 2000
estimated_velocity_threshold: 2.77
estimated_yawrate_threshold: 0.017453
stop_judgment_velocity_threshold: 0.01 #Speed threshold for judgment at stop. (m/s)

There is no problem with this setting, so there may be a problem with heading.cpp and / or heading_interpolate.cpp.

Error while executing nmea launch file

Hi team thanks for the great package.
I am using ublox zed f9p module GPS.
I am getting navsat fix with ublox ros package
I am getting speed from wheel sensor via can message and then to ros.
I am getting IMU from zed camera.
I want to achieve localization using these with your package.
but when I tried I saw rtklib_nav is working fine but nmea launch files are not working properly.
instead of using rtklib nav and nmea can I launch kumar robotics ublox package where I will get /ublox/fix which consists gps coordinates.
eagleye: #GNSS cycle 5Hz, IMU cycle 50Hz.

Using Topic Name

twist_topic: /can_twist
imu_topic: /imu/data_raw
rtklib_nav_topic: /rtklib_nav
navsatfix_topic: /f9p/fix
nmea_sentence_topic: /f9p/nmea_sentence

if its available what changes I had to make in this conf file

raw gnss data and eagleye output look mirrored to each other

I visualize raw gnss data and eagleye's output (navsatfix msgs ) as local cartesian UTM. For your sample rosbag data output is as we wait . Sample data output is here:
eagleye_default_test
The red one is raw gnss data output and blue one is eagleye output (/eagleye/fix) pose.

But I have interesting problem when i tested with my data. The poses looks mirrored. Here is the results:
eagleye_mirror_error_3

My calibration is correct . I am using default parameters .

How long does IMU only solution can stand

Hello,

Thank you so much for very impressive work and haring source.

After going through, i just curious to know, how long does localization node stable using only imu odometry ? when there is no GPS and No NDT output.

Existing autoware Localization module needs position input either from GPS or NDT, failing of both (Ex: Inside long straight Tunnel, nieghter GPS, nor NDT works) would result in immediate failure of entire localization module.

Alternatively, if IMU only can handle for at least shorter period of time would be more beneficial in order to perform vehicle emergency maneuvers.

Appreciate your response !

Regards,
Ajay

Failed to lookup transform: "imu_link" passed to lookupTransform argument source_frame does not exist.

I want to run my own rosbag package, but its message does not contain /rtklib_nav. Can it be used? At the same time, I also changed the eagleye_config.yaml file to match my bag.
But the error "Failed to lookup transform: "imu_link" passed to lookupTransform argument source_frame does not exist. " is still reported when running.
"
path: 2022-07-14-19-51-21.bag
version: 2.0
duration: 2:34s (154s)
start: Jul 14 2022 19:51:21.53 (1657799481.53)
end: Jul 14 2022 19:53:55.56 (1657799635.56)
size: 14.1 MB
messages: 46161
compression: none [19/19 chunks]
types: gps_common/GPSFix [3db3d0a7bc53054c67c528af84710b70]
rosgraph_msgs/Log [acffd30cd6b6de30f120938c17c593fb]
sensor_msgs/Imu [6a62c6daae103f4ff57a132d6f95cec2]
sensor_msgs/NavSatFix [2d3a8cd499b9b4a0249fb98fd05cfa48]
topics: /gps_fix 15385 msgs : gps_common/GPSFix
/imu_raw 15386 msgs : sensor_msgs/Imu
/nav_sat_fix 15386 msgs : sensor_msgs/NavSatFix
/rosout 4 msgs : rosgraph_msgs/Log

"

abs or std::abs ?

Hello
(Sorry, my English is pool...)
In distance.cpp line 38
used "abs"
function abs is from stdlib.h,it only supports "int"
function std::abs is from c++ "cmath", it's able to support "double" "float" "long double"

Is this your intention?
But when I run code by eagleye_sample.bag , distance ---> height and pitch were zero for a long time

I don't know if this is normal...

F9P settings

First, thanks for the brilliant packages.

My zed-f9p firmware version is 1.32 and I don't want to change the firmware version.
image
I am using three ardusimple rtk2b board, one at base station, two on robot.

(1) Settings for receivers that output aircraft that output NMEA (positioning results RTK'd by the F9P internal engine)
eagleye_f9p_nmea_conf.txt
https://www.dropbox.com/s/3viqyqutipn5dpj/eagleye_f9p_nmea_conf.txt?dl=0
(2) Settings for receivers that measure RAW data through RTKLIB and output Doppler velocity.
eagleye_f9p_raw_conf.txt
https://www.dropbox.com/s/acz98v30rtgbmsx/eagleye_f9p_raw_conf.txt?dl=0

Regarding above, can I understand that the first zed-f9p on robot should output NMEA only like image below
image

while the second zed-f9p on robot should output Raw message only like the image below only?
image

Or other settings need to be configured?

candles driving backward localization

In canless mode " Localization estimating is not possible when driving backward ", does the situation happen even if the RTK position works well?

rtkrcv server start error

I am getting an error related to the inpstr1-path. When I run the node, the first thing that I get is rtkrcv server start error where it cannot find the receiver.

Solutions that I've tried:

  • renamed inpstr1-path to match ttyACM0 and ttyUSB0, still the same error
  • tried the sample inpstr1-path by MapIV and only changed the baud rate, still the same error

I am assuming I have to input the serial number of the chip somewhere in the config file? At least that's what I understood from the instructions. Any suggestions are highly valued, thank you!

ROS2 Bag

Hello everyone. I want to try eagleye on ROS2 bag, but somehow cannot find ros2 bag(download link) to follow instructions. Can anyone please guide me where is the link for ROS2 bag file.
Thank you.

ros2-foxy build error

Current branch main-ros2

~$ colcon build --packages-up-to eagleye_rt --symlink-install
Starting >>> geographic_msgs
Starting >>> rtklib_msgs
Starting >>> nmea_msgs
Finished <<< rtklib_msgs [0.59s]
Starting >>> eagleye_msgs
Finished <<< nmea_msgs [0.95s]
Finished <<< geographic_msgs [1.41s]
Starting >>> geodesy
Finished <<< geodesy [0.30s]
Starting >>> geographic_info
Finished <<< eagleye_msgs [1.22s]
Finished <<< geographic_info [0.19s]
Starting >>> eagleye_coordinate
Finished <<< eagleye_coordinate [0.27s]
Starting >>> eagleye_navigation
Finished <<< eagleye_navigation [0.43s]
Starting >>> eagleye_rt
[Processing: eagleye_rt]
[Processing: eagleye_rt]
--- stderr: eagleye_rt
In file included from /usr/include/c++/9/ext/alloc_traits.h:36,
from /usr/include/c++/9/bits/basic_string.h:40,
from /usr/include/c++/9/string:55,
from /usr/include/c++/9/bits/locale_classes.h:40,
from /usr/include/c++/9/bits/ios_base.h:41,
from /usr/include/c++/9/ios:42,
from /usr/include/c++/9/ostream:38,
from /usr/include/c++/9/iostream:39,
from /home/david/Documents/ros2/localization/gnss_imu/install/geodesy/include/geodesy/utm.h:43,
from /home/david/Documents/ros2/localization/gnss_imu/install/eagleye_coordinate/include/eagleye_coordinate/eagleye_coordinate.hpp:30,
from /home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:31:
/usr/include/c++/9/bits/alloc_traits.h: In instantiation of ‘struct std::allocator_traits<std::allocator<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&> >’:
/opt/ros/foxy/include/rclcpp/message_memory_strategy.hpp:47:9: required from ‘class rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >’
/opt/ros/foxy/include/rclcpp/node_impl.hpp:91:1: required by substitution of ‘template<class MessageT, class CallbackT, class AllocatorT, class CallbackMessageT, class SubscriptionT, class MessageMemoryStrategyT> std::shared_ptr rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = eagleye_msgs::msg::VelocityScaleFactor_<std::allocator >; CallbackT = void (&)(const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&); AllocatorT = std::allocator; CallbackMessageT = const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&; SubscriptionT = rclcpp::Subscription<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator, rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >]’
/home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:135:142: required from here
/usr/include/c++/9/bits/alloc_traits.h:399:13: error: forming pointer to reference type ‘const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&’
399 | using pointer = Tp*;
| ^~~~~~~
/usr/include/c++/9/bits/alloc_traits.h:402:13: error: forming pointer to reference type ‘const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor
<std::allocator > >&’
402 | using const_pointer = const Tp*;
| ^~~~~~~~~~~~~
In file included from /usr/include/c++/9/bits/locale_conv.h:41,
from /usr/include/c++/9/locale:43,
from /usr/include/c++/9/iomanip:43,
from /home/david/Documents/ros2/localization/gnss_imu/install/geodesy/include/geodesy/utm.h:44,
from /home/david/Documents/ros2/localization/gnss_imu/install/eagleye_coordinate/include/eagleye_coordinate/eagleye_coordinate.hpp:30,
from /home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:31:
/usr/include/c++/9/bits/unique_ptr.h: In instantiation of ‘struct std::default_delete<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor
<std::allocator > >&>’:
/opt/ros/foxy/include/rclcpp/message_memory_strategy.hpp:119:18: required from ‘class rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >’
/opt/ros/foxy/include/rclcpp/node_impl.hpp:91:1: required by substitution of ‘template<class MessageT, class CallbackT, class AllocatorT, class CallbackMessageT, class SubscriptionT, class MessageMemoryStrategyT> std::shared_ptr rclcpp::Node::create_subscription(const string&, const rclcpp::QoS&, CallbackT&&, const rclcpp::SubscriptionOptionsWithAllocator&, typename MessageMemoryStrategyT::SharedPtr) [with MessageT = eagleye_msgs::msg::VelocityScaleFactor_<std::allocator >; CallbackT = void (&)(const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&); AllocatorT = std::allocator; CallbackMessageT = const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&; SubscriptionT = rclcpp::Subscription<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator, rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator > >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&, std::allocator >]’
/home/david/Documents/ros2/localization/gnss_imu/src/eagleye-1.3.0-ros2/eagleye_rt/src/enable_additional_rolling_node.cpp:135:142: required from here
/usr/include/c++/9/bits/unique_ptr.h:71:9: error: forming pointer to reference type ‘const std::shared_ptr<eagleye_msgs::msg::VelocityScaleFactor_<std::allocator > >&’
71 | default_delete(const default_delete<_Up>&) noexcept { }

Sample rosbag

Hi, I would like to try out the package with the sample rosbags.
However, the provided dropbox links in the README doesn't work anymore.

Download 404

HI, I got a 404 error when I downloaded the bag data and opened the website you provided.

"inputting RTK results from the F9P" need two separate C099-F9P boards?

"When inputting RTK results from the F9P into the Eagleye, two F9Ps are used as follows.
(1) A receiver that outputs NMEA (RTK results from the F9P internal engine)
(2) A receiver that measures RAW data through RTKLIB and outputs Doppler velocity."
as this said.

by the way, "A receiver that measures RAW data", the RAW data is the RTCM V3 raw data ?
or rtcm v3 data can be used to calc velocity?

Thanks

Bad performance on example bag in ros2

Hello,
I am working on the eagleye on ros2 branch.
I plot the result by Foxglove, but found the localization is not stable.

The result was showed as follow,
Purple: localization from gnss
Blue: localization from eagleye
Screenshot 2023-12-07 at 9 25 54 AM

The localization is matched perfect initially but having the jump somewhere and misdirection after few seconds.
Any Suggestion or idea to fix it,
Thanks.

Environment: Ubuntu 20.04/foxy, Ubuntu 20.04/humble
Config: eagleye_config.yaml in main-ros2 branch
Launch: eagleye_rt.launch.xml in main-ros2 branch
Bag: ros2 in https://drive.google.com/drive/folders/1TEaVRn7F6t8PhEfZe59gE_C1B8jZUkJo

About the result of “smoothing”

The GNSS positioning solution may be affected by multipath and deviate. (Especially in the height direction)
If there are large outliers, the averaging effect will be negated.
Countermeasures are needed.

eagleye autoware

Hi again!
Can I run eagleye with autoware, simulation running in awsim?
awsim does not provide NavSatFix msg on gnss, it only provides pose without orientation.
Thank you.

Eagleye covariance values are getting too high after the return.

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.

RTK GPS latency

My GPS has RTK correction, but there is about 150ms latency. Can this code work with that?

eagle_rt output

Hi, i run eagle_rt launch file with eagle_sample bag file. When I start launch file, i wait 100 seconds then some status true but others false. Is that normally?
image

How to use yaw_rate_offset_parameter.estimated_minimum_interval and estimated_maximum_interval

Hi,
I'm not sure how to use estimated_minimum_interval and estimated_maximum_interval in yaw rate offset parameter.

According to https://github.com/MapIV/eagleye/tree/main-ros1/eagleye_rt/config, these are set as the follow for default.

yaw_rate_offset:
estimated_minimum_interval: 30
1st:
estimated_maximum_interval: 300
2nd:
estimated_maximum_interval: 500

I understand these parameters mean the time of yaw rate offset estimation and also offset is decided after two times of least squares estimation, but I don't when they are applied. Could you tell me more details?

In the case of default for 1st estimation, I guess as bellow behavior. Is this correct?
t: driving time
i) t<30s ; not estimate
ii) t=30s ; estimate with gnss velocity and yaw rate data for last 30s
iii) 30s<t<=300s ; estimate with data for last t[s]
iv) t>300s ; estimate with data for last 300s

BR,

Real-time trajectory visualization

The viewpoint of the real-time trajectory visualization is fixed, but it would be better to change it as the trajectory transitions.
This can be achieved with the following

https://github.com/MapIV/eagleye/tree/main-ros2/eagleye_util/fix2kml

<LookAt>
  <longitude>-122.0849</longitude>
  <latitude>37.4223</latitude>
  <altitude>50</altitude>
  <heading>0</heading>
  <tilt>45</tilt>
  <range>500</range>
  <altitudeMode>relativeToGround</altitudeMode>
</LookAt>

Also, this package does not have readme.md, which would be nice to have.

draft

This package can be visualized using [the app version of Google Eartrh](https://www.google.co.jp/earth/about/versions/#download-pro) by opening networklink.kml.
networklink.kml reads the kml file specified by href at refreshInterval [sec] intervals and visualizes it in real time.
      <href>eagleye_fix.kml</href>.
      <refreshMode>onInterval</refreshMode>.
      <refreshInterval>0.02</refreshInterval>
https://github.com/MapIV/eagleye/blob/main-ros2/eagleye_util/fix2kml/kml/networklink.kml#L26-L28 (

can_less mode with custom dataset

Thank you for your great work

I can't apply can less mode other rosbag with /nmea_sentence and /imu/data like below.

Screenshot from 2023-08-02 02-19-39

here are rosbag and my eagleye_config.yaml.

error for imu frame_id :"/base_imu", I republish frame_id: "imu" to /imu/data2

Thank you.

rosbag: https://drive.utbm.fr/s/6NcE2GSqNdGyELg

eagleye_config.yaml.


# Estimate mode
use_gnss_mode: NMEA
use_can_less_mode: True

# Topic
twist:
  twist_type: 0 # TwistStamped : 0, TwistWithCovarianceStamped: 1
  twist_topic: /can_twist
imu_topic: /imu/data2
gnss:
  velocity_source_type: 1 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3
  velocity_source_topic:  /nmea_sentence
  llh_source_type: 1 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
  llh_source_topic: /nmea_sentence
sub_gnss:
  llh_source_type: 1 # nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
  llh_source_topic: /nmea_sentence
# TF
tf_gnss_frame:
  parent: "base_link"
  child: "gnss"

reverse_imu_wz: false
reverse_imu_ax: false

# Origin of GNSS coordinates (ECEF to ENU)
ecef_base_pos:
  x : 0.0
  y : 0.0
  z : 0.0
  use_ecef_base_position : false

# Eagleye Navigation Parameters
# Basic Navigation Functions
common:
  imu_rate: 50
  gnss_rate: 5
  stop_judgement_threshold: 0.01
  slow_judgement_threshold: 0.278
  moving_judgement_threshold: 2.78

velocity_scale_factor:
  estimated_minimum_interval: 20
  estimated_maximum_interval: 400
  gnss_receiving_threshold: 0.25
  velocity_scale_factor_save_str: /config/velocity_scale_factor.txt
  save_velocity_scale_factor: false
  velocity_scale_factor_save_duration: 100.0
  th_velocity_scale_factor_percent: 10.0

yaw_rate_offset_stop:
  estimated_interval: 4
  outlier_threshold: 0.002

yaw_rate_offset:
  estimated_minimum_interval: 30
  gnss_receiving_threshold: 0.25
  outlier_threshold: 0.002
  1st:
    estimated_maximum_interval: 300
  2nd:
    estimated_maximum_interval: 500

heading:
  estimated_minimum_interval: 10
  estimated_maximum_interval: 30
  gnss_receiving_threshold: 0.25
  outlier_threshold: 0.0524
  outlier_ratio_threshold: 0.5
  curve_judgement_threshold: 0.0873
  init_STD: 0.0035 #[rad] (= 0.2 [deg])

heading_interpolate:
  sync_search_period: 2
  proc_noise: 0.0005 #[rad] (= 0.03 [deg])

slip_angle:
  manual_coefficient: 0.0

slip_coefficient:
  estimated_minimum_interval: 2
  estimated_maximum_interval: 100
  curve_judgement_threshold: 0.017453
  lever_arm: 0.0

rolling:
  filter_process_noise: 0.01
  filter_observation_noise: 1

trajectory:
  curve_judgement_threshold: 0.017453
  timer_updata_rate: 10
  deadlock_threshold: 1
  sensor_noise_velocity: 0.05
  sensor_scale_noise_velocity: 0.02
  sensor_noise_yaw_rate: 0.01
  sensor_bias_noise_yaw_rate: 0.1

smoothing:
  moving_average_time: 3
  moving_ratio_threshold: 0.1

height:
  estimated_minimum_interval: 200
  estimated_maximum_interval: 2000
  update_distance: 0.1
  gnss_receiving_threshold: 0.1
  outlier_threshold: 0.3
  outlier_ratio_threshold: 0.5
  moving_average_time: 1

position:
  estimated_interval: 300
  update_distance: 0.1
  outlier_threshold: 3.0
  gnss_receiving_threshold: 0.25
  outlier_ratio_threshold: 0.5
  gnss_error_covariance: 0.5

position_interpolate:
  sync_search_period: 2
  proc_noise: 0.05 #[m]


monitor:
  print_status: true
  log_output_status: false
  update_rate: 10.0
  th_gnss_deadrock_time: 10.0
  use_compare_yaw_rate: false
  comparison_twist_topic: /calculated_twist
  th_diff_rad_per_sec: 0.17453
  th_num_continuous_abnormal_yaw_rate: 25
  th_dr_distance: 50.0

# Optional Navigation Functions
angular_velocity_offset_stop:
  estimated_interval: 4
  outlier_threshold: 0.002

rtk_dead_reckoning:
  rtk_fix_STD: 0.3 #[m]
  proc_noise: 0.05 #[m]

rtk_heading:
  update_distance: 0.3
  estimated_minimum_interval: 10
  estimated_maximum_interval: 30
  gnss_receiving_threshold: 0.25
  outlier_threshold: 0.0524
  outlier_ratio_threshold: 0.5
  curve_judgement_threshold: 0.0873

enable_additional_rolling:
  update_distance: 0.3
  moving_average_time: 1
  sync_judgement_threshold: 0.01
  sync_search_period: 1

velocity_estimator:
  gga_downsample_time: 0.5
  stop_judgement_velocity_threshold: 0.2
  stop_judgement_interval: 1
  variance_threshold: 0.000025
  pitchrate_offset:
    estimated_interval: 8
  pitching:
    estimated_interval: 5
    outlier_threshold: 0.0174
    gnss_receiving_threshold: 0.2
    outlier_ratio_threshold: 0.5
  acceleration_offset:
    estimated_minimum_interval: 30
    estimated_maximum_interval: 500
    filter_process_noise: 0.01
    filter_observation_noise: 1
  doppler_fusion:
    estimated_interval: 4
    gnss_receiving_threshold: 0.2
    outlier_ratio_threshold: 0.5
    outlier_threshold: 0.1

Is it possible to localization without using actual machine and RTKLIB?

I have IMU and GNSS data of a traffic scene, and I'm trying to use ROS nodes to send data directly to eagleye_core and to fetch the output.

Judging by the sample data, eagleye seems able to do the localization without RTKLIB and actual machine.

So I wondering is it possible to generate all the necessary information that eagleye needs to localization without using RTKLIB and actual machine?
If yes, could you please also tell me which topics should be published from outside to make eagleye perform properly?

I'm not quite familiar with localization, sorry for asking vague questions.
Looking forward to your feedback.

cannot play sample data ROS 1 with ROS2 foxy environment

Hi,

I have problem to run the sample data in ROS2 (foxy) environment. The error are as below:

Files: eagleye_sample.bag
Bag size: 3.5 GiB
Storage id: rosbag_v2
Duration: 1673.60s
Start: Jan 27 2020 12:12:52.310 (1580098372.310)
End: Jan 27 2020 12:40:45.370 (1580100045.370)
Messages: 252597
Topic information: Topic: /can_twist | Type: geometry_msgs/msg/TwistStamped | Count: 135508 | Serialization Format: rosbag_v2
Topic: /imu/data_raw | Type: sensor_msgs/msg/Imu | Count: 83653 | Serialization Format: rosbag_v2
Topic: /fix | Type: sensor_msgs/msg/NavSatFix | Count: 8360 | Serialization Format: rosbag_v2

Please note that for both ROS1(noetic) and ROS2(foxy), the msg missing has been installed.But still cant play the bag. Please help to advice.

ROS Packages uses wrong path for installation

Hi,

I would like to confirm that the path of gsigeo2011_ver2_1.asc.

I followed step but there is not such file in the path eagleye/eagleye_util/llh_converter/data/gsigeo2011_ver2_1.asc. It turns out the file is under llh_converter/data/gsigeo2011_ver2_1.asc.

Therefore, the line should be:

sudo cp llh_converter/data/gsigeo2011_ver2_1.asc /usr/share/GSIGEO/

This issue also appears in main-ros1 branch. I know it is going to reach EOF but this fix will be useful for beginners. I have update the step in my fork in main-ros2 branch but not sure if it is correct. Please let me know if I should create a PR.

Thank you for all these efforts 🙂

Canless eagleye

Is eagleye_rt_canless.launch means that the package now are supporting only using GNSS and IMU data to estimate the position without out twist_topic?

Eagleye is not woring when use_can_less_mode is false

I tested with default test data and default parameter. Just I set use_can_less_mode parameter as false. It not give an output in /eagleye/fix topic. Here is the eagleye terminal output. Can I use eagleye without vehicle twist msg. How can I fix this issue

eagleye_canless

Sample data

How to use the sample data to test? I am playing the rosbag file and check that the topics /imu/data_raw and /can_twist are publishing. Then I start RTKLIB with bash rtklib_ros_bridge_sample.sh

If I leave the original path, then I get a server start error:

rtkrcv> rtk server start error (str1 open error path=/serial/by-id/usb-u-blox_AG_-_www.u-blox.com_u-blox_GNSS_receiver-if00:9600:8:n:1:off)

However, I get the following error when changing the path to /dev/ttyACM0:

no navigation data: rtkrcv.nav

** rtkrcv ver.2.4.3 b31 console (h:help) **
rtkrcv> rtk server start error (str1 open error path=/dev/ttyACM0)

Can I try the sample data without having the actual sensors? How can I do that?

Bag not work for ros2

when using ros2 bag play -s rosbag_v2 eagleye_sample.bag play bag , the rosbag_v2 only support default msgs that included in ros1 and ros2 standard msg, the rtklib_msgs/RtklibNav msg will be ignored.

  1. is there a way to not using rtklib_msgs/RtklibNav msg ,just using sensor_msgs/NavSatFix to replace gnss source as input ?

How to use RTKLIB and Eagle Eye for Localization

Hi,

After reading through the documentations, I'm still a little vague about the whole idea of using eagle eye for localization, so here are my questions:

  1. Is the input from RTKLIB necessary? I realised that the rosbag contains the topic "/rtklib_nav", which is from RTKLIB ros bridge. It seems like this input is required to run eagle eye rt based on the config file.

  2. In RTKLIB configurations, I noticed that a base station input is required. However, I do not have that so does that mean that I cannot use RTKLIB to output the rtklib_nav topics?

  3. Currently, I only have the IMU topic as well as a fix type GPS data. I assume that I can use the eagle eye rt with the canless mode, but if I have the wheel odometry data, I can use the CAN mode by just using the odometry twist data right?

These are my questions and I hope that you can assist me here. I am hoping to perform localization of my robot with the use of GPS data along with the IMU for a more precise pose in the map.

Thank you.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.