osrf / car_demo

525 stars 272 forks source link

If caster angle is set to 5.1 degrees on the steering joints, front wheels slide around on mcity world #2

Open sloretz opened 7 years ago

sloretz commented 7 years ago

If the rpy attribute on the steering joints are changed to have caster angle, the car will wiggle and rotate on the mcity world. The car does not wiggle on the ground plan in empty.world.

<joint name="front_left_steer_joint" type="continuous">
    <parent link="chassis"/>
    <child link="fl_axle"/>
    <origin xyz="0.767 -1.41 0.3" rpy="-0.0 0 0"/>
    <axis xyz="0 0 1"/>
    <limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
  </joint>
  <joint name="front_right_steer_joint" type="continuous">
    <parent link="chassis"/>
    <child link="fr_axle"/>
    <origin xyz="-0.767 -1.41 0.3" rpy="-0.089 0 0"/>
    <axis xyz="0 0 1"/>
    <limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
  </joint>
scpeters commented 7 years ago

I'll take a more detailed look at this once I get back to the office. In the meantime, do you have a screenshot the joint visual with contact points visualized? Or a screen capture of the wobble?

rohitsalem commented 6 years ago

Hi ! Is this issue fixed or any leads on this? Here is a gif. which shows the sliding. And to mention the same problem persists when I spawn the Prius model in raceway.world too. sliding_prius

ptiwari0664 commented 6 years ago

Hello, Did you find any solution of it ?? I am having the same issue. Above mention wobble happens even when i didn't change anything (i.e. with the same steering wheel angle).

Does anyone has any lead on this. The advises and solutions are most welcome. Thanks in advance !!!

plumewind commented 4 years ago

me too! anyone can help?thanks a lot

plumewind commented 4 years ago

hello, I have solved it !

in the prius.urdf:

 < link name="fl_axle">
    < inertial>
      < mass value="1"/>
      < origin xyz="0 0 0"/>
      < inertia ixx="2" ixy="0" ixz="0" iyy="2" iyz="0" izz="2"/><!--it is very important !-->
    < /inertial>
  < /link>
  < link name="fr_axle">
    < inertial>
      < mass value="1"/>
      < origin xyz="0 0 0"/>
      < inertia ixx="2" ixy="0" ixz="0" iyy="2" iyz="0" izz="2"/><!--it is very important !-->
    < /inertial>
  < /link>