Files
AMR_T800/Controllers/Packages/cititruck_description/urdf/include/common_properties.urdf.xacro
2026-02-26 09:48:16 +07:00

85 lines
2.9 KiB
XML
Executable File

<?xml version="1.0" ?>
<!--
Various useful properties such as constants and materials
-->
<robot name="xacro_properties" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- #################### RViz materials #################### -->
<xacro:property name="material_white">
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</xacro:property>
<xacro:property name="material_yellow">
<material name="yellow">
<color rgba="${255/255} ${226/255} ${0/255} 1"/>
</material>
</xacro:property>
<xacro:property name="material_almost_white">
<material name="almost_white">
<color rgba="0.9 0.9 0.9 1" />
</material>
</xacro:property>
<xacro:property name="material_grey">
<material name="grey">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</xacro:property>
<xacro:property name="material_light_grey">
<material name="light_grey">
<color rgba="0.6 0.6 0.6 1"/>
</material>
</xacro:property>
<xacro:property name="material_dark_grey">
<material name="dark_grey">
<color rgba="0.3 0.3 0.3 1"/>
</material>
</xacro:property>
<xacro:property name="material_black">
<material name="black">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</xacro:property>
<xacro:property name="material_aluminum">
<material name="aluminum">
<color rgba="0.8 0.8 0.8 1" />
</material>
</xacro:property>
<xacro:property name="material_silver">
<material name="silver">
<color rgba="0.79 0.82 0.93 1" />
</material>
</xacro:property>
<!-- #################### inertials with origin #################### -->
<!-- see https://secure.wikimedia.org/wikipedia/en/wiki/List_of_moment_of_inertia_tensors -->
<xacro:macro name="sphere_inertial" params="radius mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.4 * mass * radius * radius}" ixy="0.0" ixz="0.0"
iyy="${0.4 * mass * radius * radius}" iyz="0.0"
izz="${0.4 * mass * radius * radius}" />
</inertial>
</xacro:macro>
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
izz="${0.5 * mass * radius * radius}" />
</inertial>
</xacro:macro>
<xacro:macro name="box_inertial" params="x y z mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
<inertia ixx="${0.0833333 * mass * (y*y + z*z)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (x*x + z*z)}" iyz="0.0"
izz="${0.0833333 * mass * (x*x + y*y)}" />
</inertial>
</xacro:macro>
</robot>