Open yenlunliao opened 8 months ago
Please change the following true/false values. Alternatively, modifying the tf of base_link-imu is also acceptable. https://github.com/MapIV/eagleye/blob/autoware-main/eagleye_rt/config/eagleye_config.yaml#L30
Thanks for the response,
I changed reverse_imu_wz
factor to true, but it seems that the result is not improved.
It may not be an issue with the IMU coordinate system. If you could provide the rosbag, I can check what the problem might be. If the problem seems complex, I might not be able to provide a solution right away, though...
This is the link of the ros2 bag: https://drive.google.com/drive/folders/1gwB4HfVbIHz_Lkaxrx9eUYSB5y6vEhls?usp=drive_link
I am using:
/rav4/ma65/fix #gnss position (2 hz)
/rav4/ma65/gnss_vel #gnss velocity (2 hz)
/rav4/adv_nav0/can_twist # wheel speed
/imu/data # tamagawa imu (200 hz)
/rav4/adv_nav0/imu # another imu (50 hz)
I only have geometry_msgs/TimeStamped
for gnss velocity topic in the bag. So I canceled the covariance checking in https://github.com/MapIV/eagleye/blob/main-ros2/eagleye_util/gnss_converter/src/gnss_converter_node.cpp#L112 to make it works.
Thanks you a lot, sorry for taking your time.
I can't say for sure if this is the cause, but it feels like the car speed sensor's resolution is too rough. It seems a bit difficult, so I'll take another look at it later.
Some update: I try to use canless mode to get rid of the influence of the speed sensor. Eagleye will start as every gnss point it received and predict the path until getting next gnss signal. However, it seems that the direction of predicted path is incorrect as well.
Can you show me the YAML file you're using?
I checked the /rav4/ma65/nmea_sentence in your rosbag, but it seems like it's not RTK, right? Since the canless mode requires RTK positioning, I feel like it wouldn't be able to position... https://github.com/MapIV/eagleye?tab=readme-ov-file#can_less-mode
This is my settings of config:
ros__parameters:
# Estimate mode
use_gnss_mode: RTKLIB
use_can_less_mode: true
# Topic
twist:
twist_type: 0 # TwistStamped : 0, TwistWithCovarianceStamped: 1
twist_topic: /rav4/adv_nav0/can_twist
imu_topic: /imu/data_raw
gnss:
velocity_source_type: 4 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3
velocity_source_topic: /rav4/ma65/gnss_vel
llh_source_type: 1 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
llh_source_topic: /rav4/ma65/nmea_sentence
sub_gnss:
llh_source_type: 1 # nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
llh_source_topic: /sensing/sub_gnss/nmea_sentence
I added a message of type geometry_msgs/TwistStamped
to receive gnss message. It is similar to geometry_msgs/TwistWithCovarianceStamped
but without check of covariance.
I am not using RTK, so I set up the RTK bit manually. My target is receive an acceptable localization result with more than 10 hz. So I try to replace the computed velocity with wheel speed to find whether it works.
I will check the hardware settings and test whether it is the speed sensor yeild the bad performance. Thanks for the suggestion.
Sorry to bother,
I had update the speed sensor and made it usable. I used tamagawa IMU with x point to driving direction, y to right door.
I set the roll of imu to 180 degree in tf.launch.xml
file to correct the coordination system and working on the main-ros2 branch.
<group>
<push-ros-namespace namespace="imu"/>
<node name="static_transform_publisher" pkg="tf2_ros" exec="static_transform_publisher" args="0 0 0 0 0 3.1415926 base_link imu">
</node>
</group>
However the result is not satisfied, the moving distance can be correct while the direction is incorrect. Is there some idea of how to correct it, thanks.
The blue dot is orignal gps signal with 1 Hz, and the red line is eagleye fix.
It was the issue of gnss coordinate system. I used NED to record speed rather than ECEF previously, the result is more reliable after I changed it to ECEF coordinate system, thank.
And some random question, will Eagleye work when gnss signal is unstable? For example: The signal may disappear some seconds when and resume.
If there are no GNSS observations, Eagleye will perform dead reckoning using vehicle speed and the IMU, so it won't be a problem for a few seconds, but the error will gradually increase over time.
Sorry to bother again, after I change the unit of gnss velocity, I collect the data again. Eagleye route has similar direction with gps initially, but the error grows and the direction is wrong after a turn.
I am doing the following settings when using eagleye
tf_converted_imu_.angular_velocity.y = (-1) * transformed_angular_velocity.vector.y;
tf_converted_imu_.angular_velocity.z = (-1) * transformed_angular_velocity.vector.z;
tf_converted_imu_.linear_acceleration.y = (-1) * transformed_linear_acceleration.vector.y;
tf_converted_imu_.linear_acceleration.z = (-1) * transformed_linear_acceleration.vector.z;
Since I setup tamagawa imu with x point to driving direction and y to the right door. I add 3.1415926 to roll
<node name="static_transform_publisher" pkg="tf2_ros" exec="static_transform_publisher" args="0 0 0 0 0 3.1415926 base_link imu">
It will be grateful if you can give some suggestions of how to modify the settings, thanks a lot.
If you set log_output_status to true, a log CSV file will be generated in the install/eagleye_rt/share/eagleye_rt/log/ directory, so could you please upload that?
https://github.com/MapIV/eagleye/blob/main-ros2/eagleye_rt/config/eagleye_config.yaml#L129
Here is the csv file.
https://drive.google.com/file/d/1GhdjTwzGbspmCjXY2dL0LocrYHegyP2Q/view?usp=sharing
Could you please change the imu_rate from the default of 50Hz? https://github.com/MapIV/eagleye/blob/main-ros1/eagleye_rt/config/eagleye_config.yaml#L37
I feel like the GNSS speed performance is poor, which seems to be degrading the performance of the velocity scale factor. Could you filter the GNSS speed input to Eagleye using covariance or something similar?
Dear author, Sorry to bother.
I have tried a bunch of methods but still not able to get something like covariance of velocity in my current gps, but I found the position information from gps is much more reliable. Can I make eagleye run with more weight on position information?
Or can the prediction always start from the known latitude and longitude given by gps?
Thanks.
Hmm... Eagleye estimates the heading using GNSS velocity (so it can accurately estimate the attitude even without RTK FIX). Therefore, if the heading is incorrect, the position estimation will also become inaccurate...
As an alternative, you can use RTKLIB and rtklib_ros_bridge to calculate GNSS velocity that is more suitable for Eagleye, but the setup can be quite challenging. https://github.com/MapIV/rtklib_ros_bridge
By the way, could there be a possibility that the vehicle speed is incorrect?
Sorry to bother,
I am using Tamagawa TAG300N1000 IMU in egaleye, but the result is not satisfied. The movement that eagleye predicts seems having a wrong direction against the gnss signal.
Blue line is gnss signals and the red line is the prediction from eagleye. When the prediction activates, it owns a correct distance but wrong direction.
I guessed it is due to wrong coordinate system. I would like to make sure whether my IMU settings is correct. IMU in my system has x-direction for head of car, y-direction indicates the right of car, and z-direction points to the ground currently. Do I need to add transform or change the settings of the imu to make the eagleye works?
Thanks.