XTDrone/sitl_config/models/rotors_description/urdf/iris.xacro

154 lines
6.4 KiB
XML

<?xml version="1.0"?>
<robot name="iris" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Properties -->
<xacro:property name="namespace" value="" />
<xacro:property name="rotor_velocity_slowdown_sim" value="10" />
<xacro:property name="mesh_file" value="iris.stl" />
<xacro:property name="mesh_scale" value="1 1 1"/>
<xacro:property name="mesh_scale_prop" value="1 1 1"/>
<xacro:property name="mass" value="1.5" /> <!-- [kg] -->
<xacro:property name="body_width" value="0.47" /> <!-- [m] -->
<xacro:property name="body_height" value="0.11" /> <!-- [m] -->
<xacro:property name="mass_rotor" value="0.005" /> <!-- [kg] -->
<xacro:property name="arm_length_front_x" value="0.13" /> <!-- [m] -->
<xacro:property name="arm_length_back_x" value="0.13" /> <!-- [m] -->
<xacro:property name="arm_length_front_y" value="0.22" /> <!-- [m] -->
<xacro:property name="arm_length_back_y" value="0.2" /> <!-- [m] -->
<xacro:property name="rotor_offset_top" value="0.023" /> <!-- [m] -->
<xacro:property name="radius_rotor" value="0.128" /> <!-- [m] -->
<xacro:property name="motor_constant" value="8.54858e-06" /> <!-- [kg.m/s^2] -->
<xacro:property name="moment_constant" value="0.06" /> <!-- [m] -->
<xacro:property name="time_constant_up" value="0.0125" /> <!-- [s] -->
<xacro:property name="time_constant_down" value="0.025" /> <!-- [s] -->
<xacro:property name="max_rot_velocity" value="1100" /> <!-- [rad/s] -->
<xacro:property name="sin30" value="0.5" />
<xacro:property name="cos30" value="0.866025403784" />
<xacro:property name="sqrt2" value="1.4142135623730951" />
<xacro:property name="rotor_drag_coefficient" value="1.75e-04" />
<xacro:property name="rolling_moment_coefficient" value="0.000001" />
<xacro:property name="color" value="$(arg visual_material)" />
<!-- Property Blocks -->
<xacro:property name="body_inertia">
<inertia
ixx="${1/12 * mass * (body_height * body_height + body_width * body_width)}"
iyy="${1/12 * mass * (body_height * body_height + body_width * body_width)}"
izz="${1/12 * mass * (body_width * body_width + body_width * body_width)}"
ixy="0.0" ixz="0.0" iyz="0.0" /> <!-- [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] -->
</xacro:property>
<!-- inertia of a single rotor, assuming it is a cuboid. Height=3mm, width=15mm -->
<xacro:property name="rotor_inertia">
<inertia
ixx="${1/12 * mass_rotor * (0.015 * 0.015 + 0.003 * 0.003) * rotor_velocity_slowdown_sim}"
iyy="${1/12 * mass_rotor * (4 * radius_rotor * radius_rotor + 0.003 * 0.003) * rotor_velocity_slowdown_sim}"
izz="${1/12 * mass_rotor * (4 * radius_rotor * radius_rotor + 0.015 * 0.015) * rotor_velocity_slowdown_sim}"
ixy="0.0" ixz="0.0" iyz="0.0" /> <!-- [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] -->
</xacro:property>
<!-- Included URDF Files -->
<xacro:include filename="$(arg rotors_description_dir)/urdf/multirotor_base.xacro" />
<!-- Instantiate multirotor_base_macro once -->
<xacro:multirotor_base_macro
robot_namespace="${namespace}"
mass="${mass}"
body_width="${body_width}"
body_height="${body_height}"
mesh_file="${mesh_file}"
mesh_scale="${mesh_scale}"
color="${color}"
>
<xacro:insert_block name="body_inertia" />
</xacro:multirotor_base_macro>
<!-- Instantiate rotors -->
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="front_right"
direction="ccw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="0"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh="iris_prop"
mesh_scale="${mesh_scale_prop}"
color="Blue">
<origin xyz="${arm_length_front_x} -${arm_length_front_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="back_left"
direction="ccw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="1"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh="iris_prop"
mesh_scale="${mesh_scale_prop}"
color="DarkGrey">
<origin xyz="-${arm_length_back_x} ${arm_length_back_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor robot_namespace="${namespace}"
suffix="front_left"
direction="cw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="2"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh="iris_prop"
mesh_scale="${mesh_scale_prop}"
color="Blue">
<origin xyz="${arm_length_front_x} ${arm_length_front_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor robot_namespace="${namespace}"
suffix="back_right"
direction="cw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="3"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh="iris_prop"
mesh_scale="${mesh_scale_prop}"
color="DarkGrey">
<origin xyz="-${arm_length_back_x} -${arm_length_back_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
</robot>