Fix joint name. Adjust friction.
authorWalter Fetter Lages <w.fetter@ieee.org>
Thu, 17 Mar 2022 02:07:05 +0000 (23:07 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Thu, 17 Mar 2022 02:07:05 +0000 (23:07 -0300)
twil_description/xacro/caster_wheel.urdf.xacro
twil_description/xacro/fixed_wheel.urdf.xacro
twil_description/xacro/tower.urdf.xacro
twil_description/xacro/twil.urdf.xacro

index a1aaf19..d0b904f 100644 (file)
 
   <gazebo reference="${name}">
     <material>Gazebo/Grey</material>
-<!--
-    <mu1>1</mu1>
-    <mu2>1</mu2>
-    <kp>1000000.0</kp>
-    <kd>100.0</kd>
+    <!-- Values from Rivera, Zandra B., Marco C.  De Simone, and Domenico Guida.  2019.
+    "Unmanned Ground Vehicle Modelling in Gazebo/ROS-Based Environments"
+    Machines 7, no.  2: 42.  https://doi.org/10.3390/machines7020042
+    -->
+    <mu1>0.8</mu1>
+    <mu2>0.8</mu2>
+    <kp>100000000.0</kp>
+    <kd>10.0</kd>
     <minDepth>0.001</minDepth>
+<!--
     <maxVel>1.0</maxVel>
     <fdir1>1 0 0</fdir1>
 -->
index 31d48dc..a432dec 100644 (file)
 
   <gazebo reference="${name}">
     <material>Gazebo/FlatBlack</material>
-<!--
-    <mu1>100000.0</mu1>
-    <mu2>100000.0</mu2>
-    <kp>500000.0</kp>
+    <!-- Values from Rivera, Zandra B., Marco C.  De Simone, and Domenico Guida.  2019.
+    "Unmanned Ground Vehicle Modelling in Gazebo/ROS-Based Environments"
+    Machines 7, no.  2: 42.  https://doi.org/10.3390/machines7020042
+    -->
+    <mu1>0.8</mu1>
+    <mu2>0.8</mu2>
+    <kp>100000000.0</kp>
     <kd>10.0</kd>
     <minDepth>0.001</minDepth>
+<!--
     <maxVel>0.1</maxVel>
     <fdir1>1 0 0</fdir1>
 -->
index b724cd6..d5c16f7 100644 (file)
@@ -36,6 +36,7 @@
     <child link="${name}" />
     <axis xyz="0 0 1" />
     <limit effort="100.0" velocity="${1.8*M_PI/180*1000}" />
+    <dynamics friction="1.0"/>
   </joint>
 
   <transmission name="${name}_transmission">
index 76c84f9..b67f4fc 100644 (file)
                <plugin>gazebo_ros2_control/GazeboSystem</plugin>
        </hardware>
 
-       <joint name="right_wheeljoint">
+       <joint name="right_wheel_joint">
                <command_interface name="effort">
                        <param name="min">-100</param>
                        <param name="max">100</param>