<?xml version="1.0" ?> <sdf version="1.5"> <model name="cart_soft_suspension"> <link name="chassis"> <pose>0 0 0.15 0 0 0</pose> <inertial> <pose>0.1 0 0 0 0 0</pose> <mass>10</mass> <inertia> <ixx>0.216666666666667</ixx> <iyy>0.841666666666667</iyy> <izz>1.04166666666667</izz> <ixy>0</ixy> <ixz>0</ixz> <iyz>0</iyz> </inertia> </inertial> <collision name="collision"> <geometry> <box> <size>1.0 0.5 0.1</size> </box> </geometry> </collision> <visual name="visual"> <geometry> <box> <size>1.0 0.5 0.1</size> </box> </geometry> <material> <script> <uri>file://media/materials/scripts/gazebo.material</uri> <name>Gazebo/Grey</name> </script> </material> </visual> </link> <link name="susp_front_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_front_right_prismatic" type="prismatic"> <parent>chassis</parent> <child>susp_front_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_front_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_front_right_spin" type="revolute"> <parent>susp_front_right</parent> <child>wheel_front_right</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> <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_front_left_prismatic" type="prismatic"> <parent>chassis</parent> <child>susp_front_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_front_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_front_left_spin" type="revolute"> <parent>susp_front_left</parent> <child>wheel_front_left</child> <axis> <xyz>0 0 1</xyz> </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>