mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
Set soft cart suspension parameters
This commit is contained in:
parent
c97b5dad86
commit
499916b979
@ -49,9 +49,9 @@
|
||||
susp_height = 0.5
|
||||
susp_lower = -susp_height * susp_travel
|
||||
susp_upper = susp_lower + susp_travel
|
||||
susp_damping = 1.0
|
||||
susp_stiffness = 1.0
|
||||
susp_spring_center = 0.0
|
||||
susp_damping = 100
|
||||
susp_stiffness = 2500
|
||||
susp_spring_center = 0.05
|
||||
%>
|
||||
<sdf version="1.5">
|
||||
<model name="cart_soft_suspension">
|
||||
@ -133,7 +133,7 @@
|
||||
<parent>chassis</parent>
|
||||
<%= "<child>susp_" + k + "</child>" %>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<xyz>0 0 -1</xyz>
|
||||
<limit>
|
||||
<lower><%= susp_lower %></lower>
|
||||
<upper><%= susp_upper %></upper>
|
||||
|
||||
@ -38,105 +38,6 @@
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<link name="susp_rear_right">
|
||||
<pose>-0.5 -0.298 0.15 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.000208333333333333</ixx>
|
||||
<iyy>0.000208333333333333</iyy>
|
||||
<izz>0.000208333333333333</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="susp_rear_right_prismatic" type="prismatic">
|
||||
<parent>chassis</parent>
|
||||
<child>susp_rear_right</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.0375</lower>
|
||||
<upper>0.0375</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.0</damping>
|
||||
<spring_stiffness>1.0</spring_stiffness>
|
||||
<spring_reference>0.0</spring_reference>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<link name="wheel_rear_right">
|
||||
<pose>-0.5 -0.298 0.15 -1.5707963267949 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.00307916666666667</ixx>
|
||||
<iyy>0.00307916666666667</iyy>
|
||||
<izz>0.005625</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="wheel_rear_right_spin" type="revolute">
|
||||
<parent>susp_rear_right</parent>
|
||||
<child>wheel_rear_right</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name="susp_front_right">
|
||||
<pose>0.5 -0.298 0.15 0 0 0</pose>
|
||||
<inertial>
|
||||
@ -175,15 +76,15 @@
|
||||
<parent>chassis</parent>
|
||||
<child>susp_front_right</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<xyz>0 0 -1</xyz>
|
||||
<limit>
|
||||
<lower>-0.0375</lower>
|
||||
<upper>0.0375</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.0</damping>
|
||||
<spring_stiffness>1.0</spring_stiffness>
|
||||
<spring_reference>0.0</spring_reference>
|
||||
<damping>100</damping>
|
||||
<spring_stiffness>2500</spring_stiffness>
|
||||
<spring_reference>0.05</spring_reference>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
@ -236,105 +137,6 @@
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name="susp_rear_left">
|
||||
<pose>-0.5 0.298 0.15 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.000208333333333333</ixx>
|
||||
<iyy>0.000208333333333333</iyy>
|
||||
<izz>0.000208333333333333</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="susp_rear_left_prismatic" type="prismatic">
|
||||
<parent>chassis</parent>
|
||||
<child>susp_rear_left</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.0375</lower>
|
||||
<upper>0.0375</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.0</damping>
|
||||
<spring_stiffness>1.0</spring_stiffness>
|
||||
<spring_reference>0.0</spring_reference>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<link name="wheel_rear_left">
|
||||
<pose>-0.5 0.298 0.15 -1.5707963267949 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.00307916666666667</ixx>
|
||||
<iyy>0.00307916666666667</iyy>
|
||||
<izz>0.005625</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="wheel_rear_left_spin" type="revolute">
|
||||
<parent>susp_rear_left</parent>
|
||||
<child>wheel_rear_left</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name="susp_front_left">
|
||||
<pose>0.5 0.298 0.15 0 0 0</pose>
|
||||
<inertial>
|
||||
@ -373,15 +175,15 @@
|
||||
<parent>chassis</parent>
|
||||
<child>susp_front_left</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<xyz>0 0 -1</xyz>
|
||||
<limit>
|
||||
<lower>-0.0375</lower>
|
||||
<upper>0.0375</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.0</damping>
|
||||
<spring_stiffness>1.0</spring_stiffness>
|
||||
<spring_reference>0.0</spring_reference>
|
||||
<damping>100</damping>
|
||||
<spring_stiffness>2500</spring_stiffness>
|
||||
<spring_reference>0.05</spring_reference>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
@ -434,5 +236,203 @@
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name="susp_rear_right">
|
||||
<pose>-0.5 -0.298 0.15 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.000208333333333333</ixx>
|
||||
<iyy>0.000208333333333333</iyy>
|
||||
<izz>0.000208333333333333</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="susp_rear_right_prismatic" type="prismatic">
|
||||
<parent>chassis</parent>
|
||||
<child>susp_rear_right</child>
|
||||
<axis>
|
||||
<xyz>0 0 -1</xyz>
|
||||
<limit>
|
||||
<lower>-0.0375</lower>
|
||||
<upper>0.0375</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<spring_stiffness>2500</spring_stiffness>
|
||||
<spring_reference>0.05</spring_reference>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<link name="wheel_rear_right">
|
||||
<pose>-0.5 -0.298 0.15 -1.5707963267949 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.00307916666666667</ixx>
|
||||
<iyy>0.00307916666666667</iyy>
|
||||
<izz>0.005625</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="wheel_rear_right_spin" type="revolute">
|
||||
<parent>susp_rear_right</parent>
|
||||
<child>wheel_rear_right</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name="susp_rear_left">
|
||||
<pose>-0.5 0.298 0.15 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.000208333333333333</ixx>
|
||||
<iyy>0.000208333333333333</iyy>
|
||||
<izz>0.000208333333333333</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="susp_rear_left_prismatic" type="prismatic">
|
||||
<parent>chassis</parent>
|
||||
<child>susp_rear_left</child>
|
||||
<axis>
|
||||
<xyz>0 0 -1</xyz>
|
||||
<limit>
|
||||
<lower>-0.0375</lower>
|
||||
<upper>0.0375</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<spring_stiffness>2500</spring_stiffness>
|
||||
<spring_reference>0.05</spring_reference>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<link name="wheel_rear_left">
|
||||
<pose>-0.5 0.298 0.15 -1.5707963267949 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.5</mass>
|
||||
<inertia>
|
||||
<ixx>0.00307916666666667</ixx>
|
||||
<iyy>0.00307916666666667</iyy>
|
||||
<izz>0.005625</izz>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyz>0</iyz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.15</radius>
|
||||
<length>0.08</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Black</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="wheel_rear_left_spin" type="revolute">
|
||||
<parent>susp_rear_left</parent>
|
||||
<child>wheel_rear_left</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
</model>
|
||||
</sdf>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user