sliding problem: friction does not work
Boxes on a plane are supposed to move with the plane, which has a sinusoidal movement. The problematic situations are as follows.
sliding
The boxes, however, slide when the plane starts to move from a static pose.moving
1) When the plane is moving, the boxes can move with the plane if I manually change the boxes pose.
2) When the plane is moving, the boxes can move with the plane if I manually change the solver iteration number.
video: https://streamable.com/qj7uh5
The far box has a small mass, 40kg; the close box has a large mass, 500kg.
Thanks for helping!
prismastic_box.launch
<launch>
<include file="$(find gazebo_ros)/launch/empty_world.launch"/>
<param name = "robot_description" command="cat $(find pbr_gazebo)/models/prismatic_box/model.urdf"/>
<node name = "spawn_robot" pkg = "gazebo_ros" type = "spawn_model" args="-file $(find pbr_gazebo)/models/prismatic_box/model.urdf -urdf -model prismatic_box"/>
<rosparam file="$(find pbr_gazebo)/config/prismatic_box_controller.yaml" command="load"/>
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/prismatic_box_controller" args="prismatic_joint_controller joint_state_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/prismatic_box_controller/joint_states" />
</node>
</launch>
model.urdf
<robot name="prismatic_box">
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/prismatic_box_controller</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<link name="world"/>
<link name="world_box">
<inertial>
<mass value="50000" />
<origin xyz="0 0 0" />
<inertia ixx="833333" ixy="0.0" ixz="0.0" iyy="1366666" iyz="0.0" izz="2166666" />
<!--Ixx = 1/12/m*(y^2+z^2)-->
</inertial>
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="18 14 2" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" />
<geometry>
<box size="18 14 2" />
</geometry>
</collision>
</link>
<gazebo reference="world_box">
<material>Gazebo/Gray</material>
</gazebo>
<joint name="world_box_joint" type="fixed">
<origin xyz="0 0 1.0" rpy="0 0 0" />
<parent link="world"/>
<child link="world_box" />
</joint>
<link name="prismatic_box">
<inertial>
<mass value="10000" />
<origin xyz="0 0 0" />
<inertia ixx="120208" ixy="0.0" ixz="0.0" iyy="270208" iyz="0.0" izz="390000" />
<!--Ixx = 1/12/m*(y^2+z^2)-->
</inertial>
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="18 12 0.5" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" />
<geometry>
<box size="18 12 0.5" />
</geometry>
</collision>
</link>
<gazebo reference="prismatic_box">
<material>Gazebo/Blue</material>
</gazebo>
<joint name="prismatic_box_joint" type="fixed">
<origin xyz="0 0 1.25" rpy="0 0 0" />
<parent link="world_box"/>
<child link="prismatic_box" />
</joint>
<link name="box">
<inertial>
<mass value="10000" />
<origin xyz="0 0 0" />
<inertia ixx="83541" ixy="0.0" ixz="0.0" iyy="83541" iyz="0.0" izz="166666" />
<!--Ixx = 1/12/m*(y^2+z^2)-->
</inertial>
<visual>
<origin xyz="0 0 0" />
<geometry>
<box size="10 10 0.1" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" />
<geometry>
<box size="10 10 0.1" />
</geometry>
<surface>
<friction>
<ode>
<mu>0.6</mu>
<mu2>0.6</mu2>
</ode>
</friction>
<contact>
<ode>
<min_depth>0.003</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<gazebo reference="box">
<material>simple_terrain</material>
<mu1>0.6</mu1>
<mu2>0.6</mu2>
</gazebo>
<joint name="box_joint" type="prismatic">
<origin xyz="0 0 0.3" rpy="0 0 0" />
<parent link="prismatic_box"/>
<child link="box" />
<xis xyz = "1 0 0"/>
<limit effort="1000000" lower="-4" upper="4" velocity="20" />
</joint>
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="box_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>
prismaticboxcontroller.yaml
prismatic_box_controller:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position Controllers ---------------------------------------
prismatic_joint_controller:
type: effort_controllers/JointVelocityController
joint: box_joint
pid: {p: 1000000.0, i: 1000.0, d: 1000.0}
edit 1:
Friction and contact params are able to be specified in urdf. Here is the results of gz sdf -p model.urdf
:
C:\fakepath\model.sdf
Asked by tom8o on 2020-10-17 02:07:35 UTC
Answers
surface
is not part of the urdf spec, so when the description is parsed, the surface section is being ignored. You can verify that by running gz sdf -p model.urdf
.
You need to specify your surface parameters as described here. Other than that you are on the right path. You do wanna set a min depth, and perhaps you might wanna increase the friction.
Edit: I was able to make it work by increasing the friction and setting min depth in both the platform and the box.
Asked by nlamprian on 2020-10-17 15:11:11 UTC
Comments
Hi nlamprian, thanks for answering. I tried gz sdf -p model.urdf
. The friction and contact params of the link box
are passed to the parsed sdf. I attached the results to the new edit. Also, as you can see in the video, the friction works only in some conditions. So I guess there might be other problems. Additionally, in this project, I need the friction coefficient 0.6.
Asked by tom8o on 2020-10-17 21:28:08 UTC
Examine carefully the sdf you attached. For example, there is no min_depth
. Please follow the instructions on the page I mentioned above.
Asked by nlamprian on 2020-10-18 10:20:23 UTC
I added min_depth
according to the page you shared and verified it is there in the parsed sdf. However, it doesn't help the sliding problem. I'm not sure if we are in the correct direction, because when I simply update the solver rate (as shown in the video), the friction just works. But this can only be done when the plane is already moving, which is not expected.
Asked by tom8o on 2020-10-20 14:34:38 UTC
Hey nlamprian, that's very interesting. Can you get it to work if the friction is set to 0.6? This friction coefficient is essential to my project.
Asked by tom8o on 2020-10-20 21:25:03 UTC
I deleted the code by now. Probably min depth is enough to get you going.
Asked by nlamprian on 2020-10-20 21:46:15 UTC
When a surfface has a small friction coefficient, e.g. 0.6, ODE cannot solve the physics properly. I solved this problem by using Bullet engine.
Asked by tom8o on 2020-12-09 13:09:59 UTC
Comments