ros-simulation / gazebo_ros_pkgs

Wrappers, tools and additional API's for using ROS with Gazebo
http://wiki.ros.org/gazebo_ros_pkgs
774 stars 772 forks source link

[ROS2] Ackermann drive plugin issue with reversing #1132

Open Benjamin-Tan opened 4 years ago

Benjamin-Tan commented 4 years ago

Description

I tried the example world for ackermann drive demo but couldn't drive the vehicle around smoothly, especially when the vehicle is reversing.

To Reproduce

Steps to reproduce the behavior:

  1. Go to '/opt/ros/eloquent/share/gazebo_plugins/worlds'
  2. 'gazebo gazebo_ros_ackermann_drive_demo.world'
  3. New terminal 'ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=demo/cmd_demo'
  4. Just drive the vehicle around.
  5. The front wheels will oscillate heavily when reversing.

Expected behavior

Able to drive the vehicle around smoothly is expected. (at least without undesirable oscillation in the front wheels)

Environment (please complete the following information):

Additional context

Add any other context here.

iggyrrieta commented 4 years ago

I am facing exactly same issue with libgazebo_ros_diff_drive plugin. Also using Ubuntu 18.04, Gazebo 9.13.1 and ROS2 Eloquent.

@Benjamin-Tan did you manage to get any solution?

saoto28 commented 4 years ago

I feel we should modify this for easy control.

line 461 in gazebo_ros_pkgs/gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp

  auto target_rot = target_rot_ * copysign(1.0, target_linear_);

to

  auto target_rot = target_rot_;

Though, I don't check it yet.

Benjamin-Tan commented 4 years ago

@iggyrrieta I did not have any issue with diff drive. Navigation2 is using that plugin heavily and I don't think they have any issue with it either.

@saoto28 the behavior is still the same even after the changes you recommended.

SivertHavso commented 3 years ago

I've been experiencing the same issues on ROS2 Foxy, Ubuntu 20.04, Gazebo 11.3.0. While I haven't managed to find an actual fix for it there are a couple of things you can try.

Oscillations For my own robot the problem mostly boiled down to fluctuating contact points causing issues with traction, and tuning the PID controller. For cylindrical wheels I set their width to something unrealistically thin which caused the contact point(s) to be more stable.

Also, as I am working with an all-wheel drive vehicle I modified the following:

joints_[REAR_RIGHT]->SetForce(0, linear_cmd);
joints_[REAR_LEFT]->SetForce(0, linear_cmd);

to:

joints_[REAR_RIGHT]->SetForce(0, linear_cmd);
joints_[REAR_LEFT]->SetForce(0, linear_cmd);
joints_[FRONT_RIGHT]->SetForce(0, linear_cmd);
joints_[FRONT_LEFT]->SetForce(0, linear_cmd);

which improved the traction.

Never got the demo/test car and world to work properly though.

Reversing I had problems with the target steering angle flipping when going from a positive linear velocity to a negative and vice versa. Applying @saoto28's suggestion solved this problem for me.