Created
July 12, 2013 23:56
-
-
Save exrhizo/5988718 to your computer and use it in GitHub Desktop.
SDF for an ackermann type vehicle
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<sdf version='1.3'> | |
<model name='ackermann'> | |
<!--base link and front link--> | |
<link name='base_link'> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.400000 0.000000 -0.125000 0.000000 0.000000 0.000000</pose> | |
<mass>2.000000</mass> | |
<inertia> | |
<ixx>2.062500</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.200000</ixz> | |
<iyy>2.702500</iyy> | |
<iyz>0.000000</iyz> | |
<izz>2.640000</izz> | |
</inertia> | |
</inertial> | |
<collision name='base_link_geom'> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>2.000000 1.000000 0.100000</size> | |
</box> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<collision name='base_link_geom_front_link'> | |
<pose>0.800000 0.000000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.100000 1.000000 0.010000</size> | |
</box> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='base_link_visual'> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>2.000000 1.000000 0.100000</size> | |
</box> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Grey</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<visual name='base_link_visualfront_link'> | |
<pose>0.800000 0.000000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.100000 1.000000 0.010000</size> | |
</box> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Gold</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
<material> | |
<script> | |
<name>Gazebo/WhiteGlow</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<!--back left wheel --> | |
<link name='back_left_wheel_link'> | |
<pose>-0.800000 0.550000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='back_left_wheel_link_geom'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='back_left_wheel_link_visual'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Green</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='back_left_wheel_joint' type='revolute'> | |
<child>back_left_wheel_link</child> | |
<parent>base_link</parent> | |
<axis> | |
<xyz>0.000000 1.000000 0.000000</xyz> | |
<limit> | |
<lower>-10000000000000000.000000</lower> | |
<upper>10000000000000000.000000</upper> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<!--back right wheel --> | |
<link name='back_right_wheel_link'> | |
<pose>-0.800000 -0.550000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='back_right_wheel_link_geom'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='back_right_wheel_link_visual'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Green</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='back_right_wheel_joint' type='revolute'> | |
<child>back_right_wheel_link</child> | |
<parent>base_link</parent> | |
<axis> | |
<xyz>0.000000 1.000000 0.000000</xyz> | |
<limit> | |
<lower>-10000000000000000.000000</lower> | |
<upper>10000000000000000.000000</upper> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<!--front left bar link --> | |
<link name='front_left_bar_link'> | |
<pose>0.800000 0.450000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='front_left_bar_link_geom'> | |
<pose>-0.150000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.400000 0.100000 0.010000</size> | |
</box> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='front_left_bar_link_visual'> | |
<pose>-0.150000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.400000 0.100000 0.010000</size> | |
</box> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Green</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='front_left_bar_joint' type='revolute'> | |
<child>front_left_bar_link</child> | |
<parent>base_link</parent> | |
<axis> | |
<xyz>0.000000 0.000000 1.000000</xyz> | |
<limit> | |
<lower>-0.500000</lower> | |
<upper>0.500000</upper> | |
<effort>100.000000</effort> | |
<velocity>10.000000</velocity> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<link name='front_left_wheel_link'> | |
<pose>0.800000 0.550000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='front_left_wheel_link_geom'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='front_left_wheel_link_visual'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Green</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='front_left_wheel_joint' type='revolute'> | |
<child>front_left_wheel_link</child> | |
<parent>front_left_bar_link</parent> | |
<axis> | |
<xyz>0.000000 1.000000 0.000000</xyz> | |
<limit> | |
<lower>-10000000000000000.000000</lower> | |
<upper>10000000000000000.000000</upper> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<link name='front_right_bar_link'> | |
<pose>0.800000 -0.450000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='front_right_bar_link_geom'> | |
<pose>-0.150000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.400000 0.100000 0.010000</size> | |
</box> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='front_right_bar_link_visual'> | |
<pose>-0.150000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.400000 0.100000 0.010000</size> | |
</box> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Red</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='front_right_bar_joint' type='revolute'> | |
<child>front_right_bar_link</child> | |
<parent>base_link</parent> | |
<axis> | |
<xyz>0.000000 0.000000 1.000000</xyz> | |
<limit> | |
<lower>-0.500000</lower> | |
<upper>0.500000</upper> | |
<effort>100.000000</effort> | |
<velocity>10.000000</velocity> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<link name='front_right_wheel_link'> | |
<pose>0.800000 -0.550000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='front_right_wheel_link_geom'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='front_right_wheel_link_visual'> | |
<pose>0.000000 0.000000 0.000000 1.570800 0.000000 0.000000</pose> | |
<geometry> | |
<cylinder> | |
<length>0.010000</length> | |
<radius>0.200000</radius> | |
</cylinder> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Green</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='front_right_wheel_joint' type='revolute'> | |
<child>front_right_wheel_link</child> | |
<parent>front_right_bar_link</parent> | |
<axis> | |
<xyz>0.000000 1.000000 0.000000</xyz> | |
<limit> | |
<lower>-10000000000000000.000000</lower> | |
<upper>10000000000000000.000000</upper> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<link name='steer_link'> | |
<pose>0.800000 0.000000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='steer_link_geom'> | |
<pose>-0.150000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.400000 0.100000 0.010000</size> | |
</box> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='steer_link_visual'> | |
<pose>-0.150000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.400000 0.100000 0.010000</size> | |
</box> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/PurpleGlow</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='steer_joint' type='revolute'> | |
<child>steer_link</child> | |
<parent>base_link</parent> | |
<axis> | |
<xyz>0.000000 0.000000 1.000000</xyz> | |
<limit> | |
<lower>-0.500000</lower> | |
<upper>0.500000</upper> | |
<effort>100.000000</effort> | |
<velocity>10.000000</velocity> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<link name='ackermann_bar_link'> | |
<pose>0.500000 0.000000 -0.250000 0.000000 0.000000 0.000000</pose> | |
<inertial> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<mass>1.000000</mass> | |
<inertia> | |
<ixx>1.000000</ixx> | |
<ixy>0.000000</ixy> | |
<ixz>0.000000</ixz> | |
<iyy>1.000000</iyy> | |
<iyz>0.000000</iyz> | |
<izz>1.000000</izz> | |
</inertia> | |
</inertial> | |
<collision name='ackermann_bar_link_geom'> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.100000 1.000000 0.010000</size> | |
</box> | |
</geometry> | |
<surface> | |
<contact> | |
<ode/> | |
</contact> | |
<friction> | |
<ode/> | |
</friction> | |
</surface> | |
</collision> | |
<visual name='ackermann_bar_link_visual'> | |
<pose>0.000000 0.000000 0.000000 0.000000 0.000000 0.000000</pose> | |
<geometry> | |
<box> | |
<size>0.100000 1.000000 0.010000</size> | |
</box> | |
</geometry> | |
<material> | |
<script> | |
<name>Gazebo/Yellow</name> | |
<uri>__default__</uri> | |
</script> | |
</material> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0.000000</linear> | |
<angular>0.000000</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
</link> | |
<joint name='ackermann_joint' type='revolute'> | |
<child>ackermann_bar_link</child> | |
<parent>steer_link</parent> | |
<axis> | |
<xyz>0.000000 0.000000 1.000000</xyz> | |
<limit> | |
<lower>-0.500000</lower> | |
<upper>0.500000</upper> | |
<effort>100.000000</effort> | |
<velocity>10.000000</velocity> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<!-- Adding loop joints --> | |
<joint name='ackermann_left_bar_joint' type='revolute'> | |
<parent>ackermann_bar_link</parent> | |
<child>front_left_bar_link</child> | |
<axis> | |
<xyz>0.000000 0.000000 1.000000</xyz> | |
<limit> | |
<lower>-0.500000</lower> | |
<upper>0.500000</upper> | |
<effort>100.000000</effort> | |
<velocity>10.000000</velocity> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<joint name='ackermann_right_bar_joint' type='revolute'> | |
<parent>ackermann_bar_link</parent> | |
<child>front_right_bar_link</child> | |
<axis> | |
<xyz>0.000000 0.000000 1.000000</xyz> | |
<limit> | |
<lower>-0.500000</lower> | |
<upper>0.500000</upper> | |
<effort>100.000000</effort> | |
<velocity>10.000000</velocity> | |
</limit> | |
<dynamics/> | |
</axis> | |
</joint> | |
<pose>0.000000 0.000000 1.000000 0.000000 0.000000 0.000000</pose> | |
</model> | |
</sdf> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment