diff --git a/meshes/base.stl b/meshes/base.stl index 722564bf5a5c2b266af230eddba850a5bbe69595..24c364807a2b92e7f80b2d6e8b53d7a1183b2cdc 100644 Binary files a/meshes/base.stl and b/meshes/base.stl differ diff --git a/urdf/include/platform.gazebo b/urdf/include/platform.gazebo index 00c03c3f617a1ad259369090cf4c4b4eae2f06f1..4e92815fabf4628efebb49b86e32547fee55854f 100644 --- a/urdf/include/platform.gazebo +++ b/urdf/include/platform.gazebo @@ -8,7 +8,7 @@ <material>Gazebo/Grey</material> <gravity>true</gravity> <selfCollide>true</selfCollide> -<!-- <dampingFactor>0.0002</dampingFactor> --> + <dampingFactor>0.00002</dampingFactor> <!-- <mu1>0.300000</mu1> --> <!-- <mu2>1.000000</mu2> --> <!-- <kp>50000000.0</kp> --> @@ -18,13 +18,13 @@ <gazebo reference="steer_left"> <material>Gazebo/Black</material> <gravity>true</gravity> - <dampingFactor>0.2</dampingFactor> +<!-- <dampingFactor>0.002</dampingFactor>--> </gazebo> <gazebo reference="steer_right"> <material>Gazebo/Black</material> <gravity>true</gravity> - <dampingFactor>0.2</dampingFactor> +<!-- <dampingFactor>0.002</dampingFactor>--> </gazebo> <gazebo reference="base_link_2_steer_left_joint"> @@ -44,7 +44,7 @@ <robotNamespace>/model_car</robotNamespace> <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> <legacyModeNS>true</legacyModeNS> - <controlPeriod>0.02</controlPeriod> + <controlPeriod>0.001</controlPeriod> </plugin> </gazebo> diff --git a/urdf/include/wheel.gazebo b/urdf/include/wheel.gazebo index b2bdafc35c14fb9950a253c6a8bfe955825570a1..d1a59a8d55814043105c3a88ef6ab1c12c63239d 100644 --- a/urdf/include/wheel.gazebo +++ b/urdf/include/wheel.gazebo @@ -5,13 +5,14 @@ <gazebo reference="${name}_wheel"> <material>Gazebo/Black</material> - <maxContacts>2</maxContacts> + <maxContacts>10</maxContacts> <gravity>true</gravity> <selfCollide>true</selfCollide> <mu1>100.000000</mu1> <mu2>50.000000</mu2> - <kp>1e15</kp> - <kd>1e13</kd> +<!-- <kp>1e15</kp>--> +<!-- <kd>1e13</kd>--> +<!-- <minDepth>0.01</minDepth>--> </gazebo> <gazebo reference="${parent}_2_${name}_wheel_joint"> diff --git a/urdf/include/wheel.xacro b/urdf/include/wheel.xacro index 2d4d2ca3c1663c00ad0acdaaabb3a5c401f196fc..9bc453925e3672e5cd6a76a36084ac66f0d95e8b 100644 --- a/urdf/include/wheel.xacro +++ b/urdf/include/wheel.xacro @@ -37,6 +37,7 @@ <axis xyz="0 0 ${direction}"/> <limit effort="0.1" velocity="20.0" upper="1e16" lower="-1e16"/> <!-- the limits only apply to revolute and prismatic joints --> + <dynamics damping="0.001"/> </joint> <transmission name="${name}_tran">