preventing bouncing of object?
I have created an movable 3 wheel object ... but the problem is when i increase its velocity suddenly it begins to bounce .How exactly do i stop this from happening
<?xml version="1.0"?>
<robot xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"
name="test">
<link name="base_footprint"/>
<!--BASE Link-->
<link name="base_link">
<inertial>
<mass value="100"/>
<inertia ixx="1000" ixy="0" ixz="0" iyy="800" iyz="0" izz="600" />
</inertial>
<visual>
<geometry>
<box size="0.3 0.4 0.1"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.3 0.4 0.1"/>
</geometry>
</collision>
</link>
<!--Left Wheel-->
<link name="left_wheel">
<inertial>
<mass value="1"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="80" iyz="0" izz="60" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.1"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.1"/>
</geometry>
<surface>
<friction>
<torsional>
<coefficient>10000.0</coefficient>
<surface_radius>0.5</surface_radius>
<use_patch_radius>false</use_patch_radius>
</torsional>
</friction>
</surface>
</collision>
</link>
<!--Right wheel-->
<link name="right_wheel">
<inertial>
<mass value="1"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="80" iyz="0" izz="60" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.1"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.1"/>
</geometry>
<surface>
<friction>
<torsional>
<coefficient>10000.0</coefficient>
<surface_radius>0.5</surface_radius>
<use_patch_radius>false</use_patch_radius>
</torsional>
</friction>
</surface>
</collision>
</link>
<!--front wheel-->
<link name="front_wheel">
<inertial>
<mass value="1"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="80" iyz="0" izz="60" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.1"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.1"/>
</geometry>
<surface>
<friction>
<torsional>
<coefficient>10000.0</coefficient>
<surface_radius>0.5</surface_radius>
<use_patch_radius>false</use_patch_radius>
</torsional>
</friction>
</surface>
</collision>
</link>
<!--CONNECTORS WHEEL TO BODY-->
<!--link name="left_connector">
<inertial>
<mass value="1"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="8" iyz="0" izz="6" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
</link-->
<!--link name="right_connector">
<inertial>
<mass value="1"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="8" iyz="0" izz="6" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
</link-->
<link name="front_connector">
<inertial>
<mass value="0.1"/>
<inertia ixx="0.10" ixy="0" ixz="0" iyy="0.8" iyz="0" izz="0.6" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
</link>
<!--connector to connector-->
<link name="con_to_front_con">
<inertial>
<mass value="10"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="80" iyz="0" izz="60" />
</inertial>
<visual>
<origin xyz="0 0 -0.1"/>
<geometry>
<box size="0.02 0.1 0.2"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0"/>
<geometry>
<box size="0.02 0.1 0.2"/>
</geometry>
</collision>
</link>
<!--POST-->
<link name="post">
<inertial>
<mass value="10"/>
<inertia ixx="10" ixy="0" ixz="0" iyy="80" iyz="0" izz="60" />
</inertial>
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="0.03 0.04 0.109"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" />
<geometry>
<box size="0.03 0.04 0.109"/>
</geometry>
</collision>
</link>
<!--POST TO UPPER CONNECTOR-->
<link name="up_conn">
<inertial>
<mass value="0.1"/>
<inertia ixx="0.10" ixy="0" ixz="0" iyy="0.8" iyz="0" izz="0.6" />
</inertial>
<visual>
<origin xyz="0 0.2 0" />
<geometry>
<box size="0.02 0.36 0.02"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" />
<geometry>
<box size="0.02 0.36 0.02"/>
</geometry>
</collision>
</link>
<!--steer-->
<link name="steer">
<inertial>
<mass value="0.1"/>
<inertia ixx="0.10" ixy="0" ixz="0" iyy="0.8" iyz="0" izz="0.6" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0"/>
<geometry>
<box size="0.02 0.05 0.05 "/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 1.57 0"/>
<geometry>
<box size="0.02 0.05 0.2 "/>
</geometry>
</collision>
</link>
<!--LASER>
<link name="laser_base_link" type="fixed">
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>
</link>
<joint name="base_scan_joint" type="fixed" >
<origin xyz="0 0 0.15" rpy="0 0 1.7" />
<parent link="laser_base_link" />
<child link="base_scan_link"/>
</joint>
<link name="base_scan_link" type="laser">
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.0229" length="0.028"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius="0.0229" length="0.028"/>
</geometry>
</collision>
</link>
<gazebo reference="base_scan_link">
<sensor type="ray" name="laser">
<update_rate>100</update_rate>
<visualize>true</visualize>
<ray>
<scan>
<horizontal>
<samples>684</samples>
<resolution>1</resolution>
<min_angle>-2.35</min_angle>
<max_angle>2.35</max_angle>
</horizontal>
</scan>
<range>
<min>0.06</min>
<max>8.0</max>
<resolution>0.001</resolution>
</range>
</ray>
<plugin name="gazebo_ros_base_scan_link_controller" filename="libgazebo_ros_laser.so">
<topicName>/base_scan/scan</topicName>
<frameName>base_scan_link</frameName>
<robotNamespace>/</robotNamespace>
</plugin>
</sensor>
</gazebo>
<!--LASER JOINTS>
<joint name="post_laser_base" type="fixed">
<parent link="post"/>
<child link="laser_base_link"/>
<origin xyz="0 0 0.054"/>
<origin rpy="1.57 0 0"/>
</joint-->
<!--JOINTS-->
<joint name="left_wheel_to_connector" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="-0.161 -0.1 0"/>
</joint>
<!--joint name="left_conn_to_base" type="fixed">
<parent link="base_link"/>
<child link="left_connector"/>
<origin xyz="-0.161 -0.1 0"/>
</joint-->
<joint name="right_wheel_to_connector" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0.161 -0.1 0"/>
</joint>
<!--joint name="right_conn_to_base" type="fixed">
<parent link="base_link"/>
<child link="right_connector"/>
<origin xyz="0.161 -0.1 0"/>
</joint-->
<joint name="base_footprint_to_base_link" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin rpy="0 0 -1.57"/>
</joint>
<joint name="front_wheel_to_con" type="continuous">
<parent link="front_connector"/>
<child link="front_wheel"/>
<origin xyz="-0.01 0 0"/>
</joint>
<joint name="front_con_to_con" type="fixed">
<parent link="con_to_front_con"/>
<child link="front_connector"/>
<origin xyz="0 0 -0.14"/>
</joint>
<joint name="base_to_post" type="fixed">
<child link="post"/>
<parent link="base_link"/>
<origin xyz="0 0 0.1"/>
</joint>
<joint name="post_up" type="fixed">
<parent link="post"/>
<child link="up_conn"/>
<origin xyz="0 0 0.04"/>
</joint>
<joint name="up_steer" type="fixed">
<parent link="up_conn"/>
<child link="steer"/>
<origin xyz="-0.03 0.36 0"/>
<!--axis xyz="0 0 1"/-->
</joint>
<joint name="steer_conn" type="continuous">
<parent link="steer"/>
<child link="con_to_front_con"/>
<origin xyz="0.03 0 0"/>
<axis xyz="0 0 1"/>
<!--limit lower="-1.57" upper="1.57"/-->
</joint>
<gazebo>
<plugin name="model_tri_ackermann" filename="dynamic_model.so">
</plugin>
</gazebo>
</robot>
Asked by Rajnunes on 2016-06-02 08:17:50 UTC
Answers
here are a couple of sources of undesired "bouncing behavior" that I've commonly seen with vehicles:
- cause: interpenetration correction applies an impulse that pushes the object away from interpenetrating collision, but if the impulse is too large it causes the object to "bounce/fly away". fix: set maximum velocity impulse (max_vel) to 0 will enforce pure position correction with no added momentum from interpenetration correction. It is recommended to set a finite minimum allowable interpenetration depth (min_depth) of 1mm or something small in comparison to the colliding objects.
- cause: controller exerts unrealistically large efforts on joints or links. fix: double check the forces/torques commanded by your controller and make sure they are physically realistic if you are looking for physically realistic responses.
- cause: unrealistically high velocity / momentum buildup. fix: add dissipation by adding joint damping and set implicit_spring_damper flag to true to avoid numerical instability. Joint damping value is in the units of (effort / velocity). One extremely simplistic way to try and come up with viscous damping estimates is this: at what joint velocity do you want significant effort opposing your actuation forces? Assuming for example, we are controlling a hinged joint, and the actuator is capable of putting out 1 Nm of torque. A damping coefficient of 2 means the damping force opposing your actuator will neutralize actuation torque of 1 Nm when the joint is rotating at 0.5 rad/s.
- cause: friction coefficients are too large, combined with failure of dynamics solver to resolve all constraints sufficiently in allotted time. This is especially true of you have opposing frictional forces at work such as in the cases of skid-steer or non-ackerman steering. fix: use friction coefficient of 1 or lower, and potentially increase number of inner iterations.
Here's an example for specifying contact parameters discussed above in URDF as Gazebo extensions, this example applies the parameters to all collision shapes specified under a link named my_link
:
<gazebo reference="my_link">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<maxVel>0.0</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
Asked by hsu on 2016-06-02 14:19:26 UTC
Comments
@hsu how exactly do i set the friction coefficient to one through urdf?and prevent skidding of the bot.?
Also is there anyway to add gazebo tags in the urdf to add friction to the bot thanks :)
Asked by Rajnunes on 2016-06-02 14:35:41 UTC
@chapulin you were right centre of mass problem thanks
Asked by Rajnunes on 2016-06-03 01:58:35 UTC
Comments
Could you share the vehicle's SDF? Maybe share a video of what you're observing? How are you controlling its velocity?
Asked by chapulina on 2016-06-02 10:50:49 UTC
i control it through ros rqt. is there anyway that i can reduce the bouncing and skidding of the bot.. im using gazebo 2.2 as the latest models are not that compatable with ros ..this is in urdf format @chapulina
Asked by Rajnunes on 2016-06-02 11:49:47 UTC