Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Localization rapidly gets worse while sliding through the low-friction area. #6919

Open
3 tasks done
Kim-mins opened this issue May 2, 2024 · 22 comments
Open
3 tasks done
Labels
CARLA Issue when using the CARLA simulator component:localization Vehicle's position determination in its environment. (auto-assigned) type:bug Software flaws or errors.

Comments

@Kim-mins
Copy link

Kim-mins commented May 2, 2024

Checklist

  • I've read the contribution guidelines.
  • I've searched other issues and no duplicate issues were found.
  • I'm convinced that this is not my fault but a bug.

Description

Hi team,

I'm currently running Autoware with Carla, and I found a situation that the localization gets worse while sliding through the low-friction area.

Here's the frontview video:

report.mp4

From 0:06 of the video, the ego vehicle starts to slide through, since there's a blue box that indicates the low-friction area.
After the sliding, the vehicle fails to drive again and stops forever.

Here's the corresponding RViz video: [rviz]

At the RViz video, while the ego vehicle is sliding, the localization rapidly goes bad, and it eventually thinks itself crossed the centerline, but the car is actually close to the sidewalk, not the centerline.

Expected behavior

I thought that, even though the ego vehicle slides through, the localization should not make any error.

Actual behavior

But the localization rapidly goes bad while sliding through.

Steps to reproduce

Here's a ros2bag file for the reproduction: [ros2bag]

Versions

Possible causes

No response

Additional context

No response

@idorobotics idorobotics added the type:bug Software flaws or errors. label May 2, 2024
@YamatoAndo YamatoAndo added the component:localization Vehicle's position determination in its environment. (auto-assigned) label May 7, 2024
@YamatoAndo
Copy link
Contributor

@Kim-mins
I think there might be an issue with setting up the tf between base_link and velodyne_top correctly.
Could you please comfirm it?

@Kim-mins
Copy link
Author

Kim-mins commented May 8, 2024

Thank you for the response @YamatoAndo!

Actually, my current version is before this PR, and it seems I can't check velodyne_top since there's no component managing it individually.
Could you please tell me the way to confirm my setting?

Thanks!

@YamatoAndo
Copy link
Contributor

You can check the TF between velodyne_top and base_link using the following command:

$ ros2 run tf2_ros tf2_echo base_link velodyne_top

and this is the result in your rosbag

At time 0.0
- Translation: [0.000, 0.000, 2.466]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
- Rotation: in RPY (radian) [0.000, -0.000, 0.000]
- Rotation: in RPY (degree) [0.000, -0.000, 0.000]
- Matrix:
  1.000  0.000  0.000  0.000
  0.000  1.000  0.000  0.000
  0.000  0.000  1.000  2.466
  0.000  0.000  0.000  1.000

Does this match the placement of the LiDAR in the simulator?

@Kim-mins
Copy link
Author

Kim-mins commented May 8, 2024

Thank you for the investigation @YamatoAndo!

According to the setting of the bridge I'm using now, the translation of z is 2.4, and 0.0 for others. [link]
But I cannot know about the offset 0.066.

@YamatoAndo
Copy link
Contributor

YamatoAndo commented May 8, 2024

When checking the TF tree, it seems to have the structure of base_link <-> sensor_kit_base_link <-> velodyne_top_base_link <-> velodyne_top.

$ ros2 run tf2_tools view_frames

Screenshot from 2024-05-08 20-16-31

And velodyne_top_base_link <-> velodyne_top looked like this.

$ ros2 run tf2_ros tf2_echo velodyne_top_base_link velodyne_top
At time 0.0
- Translation: [0.000, 0.000, 0.066]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
- Rotation: in RPY (radian) [0.000, -0.000, 0.000]
- Rotation: in RPY (degree) [0.000, -0.000, 0.000]
- Matrix:
  1.000  0.000  0.000  0.000
  0.000  1.000  0.000  0.000
  0.000  0.000  1.000  0.066
  0.000  0.000  0.000  1.000

I believe 0.066 represents the height from the bottom of the sensor to the laser's emission position.

@YamatoAndo
Copy link
Contributor

From my tests, it seems that the LiDAR is correctly positioned approximately +1.5 m along the x-axis from the base_link.

Could you adjust the TF to achieve the display results as follows?

$ ros2 run tf2_ros tf2_echo base_link velodyne_top

At time 0.0
- Translation: [1.500, 0.000, 2.466]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]

@YamatoAndo
Copy link
Contributor

Alternatively, this line modify to x=-1.5 might also work.

@Kim-mins
Copy link
Author

Kim-mins commented May 9, 2024

Thank you for the details @YamatoAndo!

To my understanding, my current setting is as below:

  • base_link <-> sensor_kit_base_link: [link]: z += 1.6
  • sensor_kit_base_link <-> velodyne_top_base_link: [link]: z += 0.8

So, at the bridge code, the sensor was spawned with +2.4 of z value to be aligned with the calibration above.

I cannot find the calibration for velodyne_top_base_link <-> velodyne_top, sorry for that. But there seems no translation, since the values match to what you provided.

So.. I think I can make x to be +1.5 by modifying the calibration of one of those two above.
Then, do you mean to run the scenario again after the modification, and check if still there's the issue?

By the way, I have a question for the value 1.5. Could you please tell me the reason for adding 1.5 to the translation on x-axis? I could not find documentations for this..

Thank you!

@YamatoAndo
Copy link
Contributor

I cannot find the calibration for velodyne_top_base_link <-> velodyne_top, sorry for that. But there seems no translation, since the values match to what you provided.

see here!
https://github.com/evshary/autoware_carla_launch/blob/b9e3161b2515ab3ed1940141c7ac2d0192341225/src/carla_sensor_kit_description/urdf/sensor_kit.xacro#L26-L35

https://github.com/tier4/sensor_component_description/blob/main/vls_description/urdf/VLS-128.urdf.xacro

@YamatoAndo
Copy link
Contributor

YamatoAndo commented May 9, 2024

By the way, I have a question for the value 1.5. Could you please tell me the reason for adding 1.5 to the translation on x-axis?

When I tested with your rosbag, adjusting x to +1.5 resulted in stable localization.
My speculation is that in the Carla simulator, the LiDAR is correctly positioned at the center of the vehicle body, not at the base_link (rear axle center).

I'm not sure how far it is from the base_link to the center of the vehicle in reality, but the value 1.5m from the base_link seemed to work well.

@YamatoAndo
Copy link
Contributor

YamatoAndo commented May 9, 2024

It seems like you're using the tesla.model3 vehicle, but did you get it from this repository?

The wheel_base of this vehicle is 3.0046, so I think 1.5023 would be appropriate for the center of the vehicle.

@YamatoAndo YamatoAndo added the CARLA Issue when using the CARLA simulator label May 9, 2024
@Kim-mins
Copy link
Author

Kim-mins commented May 9, 2024

Thank you @YamatoAndo!

I've tried to check the issue with the modification for here (0 to 1.5), but the ego vehicle does not move as it considers the vehicle itself as an obstacle.

Screenshot 2024-05-09 17_28_35

I also checked that the result from ros2 run tf2_ros tf2_echo base_link velodyne_top is as below:

At time 0.0
- Translation: [1.500, 0.000, 2.466]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
- Rotation: in RPY (radian) [0.000, -0.000, 0.000]
- Rotation: in RPY (degree) [0.000, -0.000, 0.000]
- Matrix:
  1.000  0.000  0.000  1.500
  0.000  1.000  0.000  0.000
  0.000  0.000  1.000  2.466
  0.000  0.000  0.000  1.000

@Kim-mins
Copy link
Author

Kim-mins commented May 9, 2024

Well, right. I'm using tesla model3, but the bridge I'm using now is this.
I think I should check if this bridge also referencing 3.0046 for wheel_base.

Thank you!

@YamatoAndo
Copy link
Contributor

I thought changing here (0 to 1.5) wouldn't affect the acquired point cloud.
You didn't change this line, right?

@Kim-mins
Copy link
Author

Kim-mins commented May 9, 2024

Oh, my mistake.. sorry I modified both..

I tested again with the only modification on here, and the result is as below:

rviz2.mp4

The vehicle repeats driving and stopping, and it just stops at all.

I also confirmed that the result from ros2 run tf2_ros tf2_echo base_link velodyne_top is as below:

At time 0.0
- Translation: [1.500, 0.000, 2.466]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
- Rotation: in RPY (radian) [0.000, -0.000, 0.000]
- Rotation: in RPY (degree) [0.000, -0.000, 0.000]
- Matrix:
  1.000  0.000  0.000  1.500
  0.000  1.000  0.000  0.000
  0.000  0.000  1.000  2.466
  0.000  0.000  0.000  1.000

@YamatoAndo
Copy link
Contributor

The vehicle repeats driving and stopping, and it just stops at all.

I think it's because the LiDAR point cloud is hitting the back of the vehicle.

@YamatoAndo
Copy link
Contributor

Please crop the LiDAR point cloud.

Alternatively, consider placing the LiDAR in a position where it doesn't hit the vehicle body.It might be better to set it at a higher position.

@Kim-mins
Copy link
Author

Kim-mins commented May 9, 2024

Thank you for the response @YamatoAndo!

I'll try your suggestion soon.
Maybe I should adjust here and here both. Could you please confirm it?

By the way, I have a question that, is this issue caused by my sensor calibrations?
I thought that this calibration is ok since it have worked well for most of the situation.
If my calibration is the problem, I think I should ask to the bridge maintainer.

Thank you!

@YamatoAndo
Copy link
Contributor

Maybe I should adjust here and here both. Could you please confirm it?

Please configure the sensor placement in ROS to match the sensor placement in the simulator.

Probably, it would be correct to do as follows:

  velodyne_top_base_link:
    x: 1.5023  #  wheel_base(3.0046) / 2.0
    y: 0.0
    z: 0.734  # {sensor_height(2.4)} - {base_link <-> sensor_kit_base_link (1.6)} - {velodyne_top_base_link <-> velodyne_top (0.066)}
    roll: 0.0
    pitch: 0.0
    yaw: 0.0
  trans = Transform(Location(x=0.0, y=0.0, z=2.4),
    Rotation(pitch=0.0, roll=0.0, yaw=270.0))

You may also consider making fine adjustments to ensure that LiDAR points do not hit the vehicle body.

For example,

  velodyne_top_base_link:
    x: 1.5023  #  wheel_base(3.0046) / 2.0
    y: 0.0
    z: 1.034  # {sensor_height(2.7)} - {base_link <-> sensor_kit_base_link (1.6)} - {velodyne_top_base_link <-> velodyne_top (0.066)}
    roll: 0.0
    pitch: 0.0
    yaw: 0.0
  trans = Transform(Location(x=0.0, y=0.0, z=2.7),
    Rotation(pitch=0.0, roll=0.0, yaw=270.0))

is this issue caused by my sensor calibrations?

I don't think it's just a sensor calibration issue.
However, since the calibration error seemed critical, I pointed it out.

@Kim-mins
Copy link
Author

Sorry for late reply @YamatoAndo..

I tested the scenario with your sensor calibration(the latter one), and it seems the issue remains.
Here's the ros2bag file and video: [ros2bag] [video]
From 0:20 of the video, when the vehicle slides through the low-friction area, the localization grows bad either..

Should I tune the sensor calibration more? I think your calibration is correct, but I cannot know what to do more.

Thank you!

@YamatoAndo
Copy link
Contributor

I checked the rosbag.
It seems that the vehicle is drifting significantly, because of the low-friction area.
The motion model implemented in the ekf_localizer may not be able to handle such large drifts effectively.

Unfortunately, it's difficult for the current version of Autoware to run in this location.

@Kim-mins
Copy link
Author

Thank you for checking @YamatoAndo!
I got your point. It seems really challenging to handle the case for low-friction area..

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
CARLA Issue when using the CARLA simulator component:localization Vehicle's position determination in its environment. (auto-assigned) type:bug Software flaws or errors.
Projects
Development

No branches or pull requests

3 participants