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

Robot model moving itself #3

Closed
ChristopherAbram opened this issue Oct 25, 2018 · 3 comments
Closed

Robot model moving itself #3

ChristopherAbram opened this issue Oct 25, 2018 · 3 comments

Comments

@ChristopherAbram
Copy link

I tried this repository for a research purpose. After some time playing with it, I noticed that mobile base is moving, even if /cmd_vel topic is empty. The base is also moving very slowly right after enabling physics engines in gazebo.
I have done some review of a urdf model and all launch files, and I've noticed that it might be caused by disabling friction for wheels. I tried to change it, and if I set it in this way (in file mir_100.gazebo.xacro)

<xacro:macro name="set_all_wheel_frictions" params="prefix">
    <xacro:set_wheel_friction link="${prefix}left_wheel_link" friction="0.4"/>
    <xacro:set_wheel_friction link="${prefix}right_wheel_link" friction="0.4"/>
    <xacro:set_wheel_friction link="${prefix}fl_caster_wheel_link" friction="0.4"/>
    <xacro:set_wheel_friction link="${prefix}fr_caster_wheel_link" friction="0.4"/>
    <xacro:set_wheel_friction link="${prefix}bl_caster_wheel_link" friction="0.4"/>
    <xacro:set_wheel_friction link="${prefix}br_caster_wheel_link" friction="0.4"/>
</xacro:macro>

and small modification in mir_100_v1.urdf.xacro

<!-- disabled, because it doesn't make a difference in Gazebo: -->
<xacro:set_all_wheel_frictions prefix="${prefix}"/>

then the model was still.
I haven't calculated friction coefficients, I just have used arbitrary chosen values (for which simulator seems to be stable).

@mintar
Copy link
Member

mintar commented Oct 25, 2018

Thanks for your contribution. I've made some experiments myself (see below). The short summary is that I cannot see a change in behavior after applying your suggestions. Also note that you reduced the friction; by default it's 1.0, you reduced it to 0.4.

I've also let the simulation run for 2 minutes and 18 seconds (simulation time). Nothing special about that value, it's just the time after which I killed the first simulation. I've included the output of the /base_pose_ground_truth topic below; the robot moved between 0.4 and 6 mm forward during that time. I don't think that will be noticeable.

no modification (current kinetic branch, 54be543)

mu1 = mu2 = 1.0
kp = 2,147,483,647.0
kd = 1

rostopic echo /base_pose_ground_truth
pose: 
  pose: 
    position: 
      x: 0.00641750607671
      y: -0.00512987328118
      z: -1.1398489202e-05

only enable set_all_wheel_frictions with current URDF values (friction = 200 for wheels, 1 for casters)

mu1 = mu2 = 200 (wheels) / 1 (casters)
kp = 10,000,000
kd = 1

rostopic echo /base_pose_ground_truth
pose: 
  pose: 
    position: 
      x: 0.000424151391665
      y: -2.32785455031e-06
      z: -5.94617817326e-06

However: If you use rqt_robot_steering to make the robot turn in place and then
stop abruptly, the casters spin around funnily. That doesn't happen in the other two cases.

your proposal (friction = 0.4 for wheels + casters)

mu1 = mu2 = 0.4
kp = 10,000,000
kd = 1

rostopic echo /base_pose_ground_truth
pose: 
  pose: 
    position: 
      x: 0.00200195846341
      y: -7.47403570384e-06
      z: -7.08789661061e-06

Same behavior as current kinetic branch.


Since I cannot reproduce the bug, I don't think I'm going to merge this, sorry. :)

@mintar mintar closed this as completed Nov 9, 2018
@mbed92
Copy link

mbed92 commented May 10, 2021

Hey. Pretty old issue, but I also faced that problem recently. In my case, it was visible after ~30min and the robot rotated for ~4 degrees in the Z-axis. In my case, I changed the robot's model to fit my purposes, but the simulation part was left unchanged. Changing friction slowed down the rotation, but not stopped.

@mintar
Copy link
Member

mintar commented May 17, 2021

First of, I should mention that we did re-enable set_all_wheel_frictions in #19, after we could reproduce the bug in some other Gazebo environments.

In response to you comment: 4 degrees in 30 minutes don't sound much.

However, if you find any parameters that improve the situation, feel free to open a pull request!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants