-
Notifications
You must be signed in to change notification settings - Fork 185
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
7 changed files
with
378 additions
and
105 deletions.
There are no files selected for viewing
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
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
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
214 changes: 214 additions & 0 deletions
214
example_11/description/urdf/carlikebot_ackermann_description.urdf.xacro
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,214 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
|
||
<xacro:macro name="carlikebot" params="prefix"> | ||
|
||
<!-- Constants for robot dimensions --> | ||
<xacro:property name="PI" value="3.1415926535897931"/> | ||
<xacro:property name="base_mass" value="4.0" /> <!-- arbitrary value for base mass --> | ||
<xacro:property name="base_width" value="0.260" /> | ||
<xacro:property name="base_length" value="0.525" /> | ||
<xacro:property name="base_height" value="0.060" /> | ||
<xacro:property name="wheelbase" value="0.325" /> | ||
<xacro:property name="wheel_mass" value="0.34055" /> <!-- arbitrary value for wheel mass --> | ||
<xacro:property name="wheel_len" value="0.045" /> | ||
<xacro:property name="wheel_radius" value="0.05" /> | ||
|
||
<!-- Base Link --> | ||
<link name="${prefix}base_link" /> | ||
|
||
<!-- Chassis --> | ||
|
||
<link name="${prefix}chassis_link"> | ||
<collision> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<geometry> | ||
<box size="${base_width} ${base_length} ${base_height}"/> | ||
</geometry> | ||
</collision> | ||
|
||
<visual> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<geometry> | ||
<box size="${base_width} ${base_length} ${base_height}"/> | ||
</geometry> | ||
<material name="orange"/> | ||
</visual> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<mass value="${base_mass}"/> | ||
<inertia | ||
ixx="${base_mass / 12.0 * (base_length*base_length + base_height*base_height)}" ixy="0.0" ixz="0.0" | ||
iyy="${base_mass / 12.0 * (base_height*base_height + base_width*base_width)}" iyz="0.0" | ||
izz="${base_mass / 12.0 * (base_width*base_width + base_length*base_length)}"/> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="${prefix}chassis_joint" type="fixed"> | ||
<parent link="${prefix}base_link"/> | ||
<child link="${prefix}chassis_link"/> | ||
<origin xyz="0 0 ${base_height/2 + wheel_radius}" rpy="0 0 0"/> | ||
<axis xyz="0 0 1"/> | ||
<dynamics damping="0.2"/> | ||
</joint> | ||
|
||
|
||
<!-- rear wheels --> | ||
|
||
<!-- rear right wheel --> | ||
|
||
<link name="${prefix}rear_right_wheel"> | ||
|
||
<collision> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
</collision> | ||
|
||
<visual> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
<material name="black"/> | ||
</visual> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<mass value="${wheel_mass}"/> | ||
<inertia | ||
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0" | ||
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0" | ||
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/> | ||
</inertial> | ||
|
||
</link> | ||
|
||
<joint name="${prefix}rear_right_wheel_joint" type="continuous"> | ||
<parent link="${prefix}chassis_link"/> | ||
<child link="${prefix}rear_right_wheel"/> | ||
<origin xyz="${base_width/2} -${wheelbase/2} -${base_height/2}" rpy="0 0 0"/> | ||
<axis xyz="-1 0 0"/> | ||
<dynamics damping="0.2"/> | ||
</joint> | ||
|
||
<!-- rear left wheel --> | ||
<link name="${prefix}rear_left_wheel"> | ||
|
||
<collision> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
</collision> | ||
|
||
<visual> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
<material name="black"/> | ||
</visual> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<mass value="${wheel_mass}"/> | ||
<inertia | ||
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0" | ||
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0" | ||
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/> | ||
</inertial> | ||
|
||
</link> | ||
|
||
<joint name="${prefix}rear_left_wheel_joint" type="continuous"> | ||
<parent link="${prefix}chassis_link"/> | ||
<child link="${prefix}rear_left_wheel"/> | ||
<origin xyz="-${base_width/2} -${wheelbase/2} -${base_height/2}" rpy="0 0 0"/> | ||
<axis xyz="-1 0 0"/> | ||
<dynamics damping="0.2"/> | ||
|
||
</joint> | ||
|
||
<!-- front wheels --> | ||
|
||
<!-- front right wheel --> | ||
|
||
<link name="${prefix}right_steering_hinge"> | ||
|
||
<collision> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
</collision> | ||
|
||
<visual> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
<material name="black"/> | ||
</visual> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<mass value="${wheel_mass}"/> | ||
<inertia | ||
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0" | ||
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0" | ||
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="${prefix}right_steering_hinge_joint" type="revolute"> | ||
<parent link="${prefix}chassis_link"/> | ||
<child link="${prefix}right_steering_hinge"/> | ||
<origin xyz="${base_width/2} ${wheelbase/2} -${base_height/2}" rpy="0 0 0"/> | ||
<axis xyz="0 0 -1"/> | ||
<limit lower="-0.4" upper="0.4" effort="0.0" velocity="0.0"/> | ||
<dynamics damping="0.2"/> | ||
</joint> | ||
|
||
|
||
<link name="${prefix}left_steering_hinge"> | ||
<collision> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
</collision> | ||
|
||
<visual> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<geometry> | ||
<cylinder length="${wheel_len}" radius="${wheel_radius}"/> | ||
</geometry> | ||
<material name="black"/> | ||
</visual> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/> | ||
<mass value="${wheel_mass}"/> | ||
<inertia | ||
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0" | ||
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0" | ||
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/> | ||
</inertial> | ||
|
||
</link> | ||
|
||
<joint name="${prefix}left_steering_hinge_joint" type="revolute"> | ||
<parent link="${prefix}chassis_link"/> | ||
<child link="${prefix}left_steering_hinge"/> | ||
<origin xyz="-${base_width/2} ${wheelbase/2} -${base_height/2}" rpy="0 0 0"/> | ||
<axis xyz="0 0 -1"/> | ||
<limit lower="-0.4" upper="0.4" effort="0.0" velocity="0.0"/> | ||
<dynamics damping="0.2"/> | ||
</joint> | ||
|
||
</xacro:macro> | ||
|
||
</robot> |
File renamed without changes.
Oops, something went wrong.