ardupilot/libraries/SITL/examples/JSON/pybullet/models/iris/iris.urdf

259 lines
9.6 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/tridge/project/UAV/pybullet/rotors_simulator/rotors_description/urdf/iris.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="iris">
<link name="iris/base_link"/>
<joint name="iris/base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="iris/base_link"/>
<child link="iris/base_link_inertia"/>
</joint>
<link name="iris/base_link_inertia">
<inertial>
<mass value="1.5"/>
<!-- [kg] -->
<origin xyz="0 0 0"/>
<inertia ixx="0.0347563" ixy="0.0" ixz="0.0" iyy="0.0458929" iyz="0.0" izz="0.0977"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/iris.dae" scale="1 1 1"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.47 0.47 0.11"/>
<!-- [m] [m] [m] -->
</geometry>
</collision>
</link>
<!-- attach multirotor_base_plugin to the base_link -->
<gazebo>
<plugin filename="librotors_gazebo_multirotor_base_plugin.so" name="multirotor_base_plugin">
<robotNamespace>iris</robotNamespace>
<linkName>iris/base_link</linkName>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
</gazebo>
<joint name="iris/rotor_0_joint" type="continuous">
<origin rpy="0 0 0" xyz="0.13 -0.22 0.023"/>
<axis xyz="0 0 1"/>
<!-- TODO(ff): not currently set because it's not yet supported -->
<!-- <limit effort="2000" velocity="${max_rot_velocity}" /> -->
<parent link="iris/base_link"/>
<child link="iris/rotor_0"/>
</joint>
<link name="iris/rotor_0">
<inertial>
<mass value="0.00005"/>
<!-- [kg] -->
<inertia ixx="9.7499961e-07" ixy="0.0" ixz="0.0" iyy="4.170414998500001e-05" iyz="0.0" izz="4.2604149625000006e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/propeller_ccw.dae" scale="0.1 0.1 0.1"/>
<!-- The propeller meshes have a radius of 1m -->
<!-- <box size="${2*radius_rotor} 0.01 0.005"/> -->
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.005" radius="0.1"/>
<!-- [m] -->
</geometry>
</collision>
</link>
<gazebo>
<plugin filename="librotors_gazebo_motor_model.so" name="iris_front_right_motor_model">
<robotNamespace>iris</robotNamespace>
<jointName>iris/rotor_0_joint</jointName>
<linkName>iris/rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>838</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
</gazebo>
<gazebo reference="iris/rotor_0">
<material>Gazebo/Blue</material>
</gazebo>
<joint name="iris/rotor_1_joint" type="continuous">
<origin rpy="0 0 0" xyz="-0.13 0.2 0.023"/>
<axis xyz="0 0 1"/>
<!-- TODO(ff): not currently set because it's not yet supported -->
<!-- <limit effort="2000" velocity="${max_rot_velocity}" /> -->
<parent link="iris/base_link"/>
<child link="iris/rotor_1"/>
</joint>
<link name="iris/rotor_1">
<inertial>
<mass value="0.00005"/>
<!-- [kg] -->
<inertia ixx="9.7499961e-07" ixy="0.0" ixz="0.0" iyy="4.170414998500001e-05" iyz="0.0" izz="4.2604149625000006e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/propeller_ccw.dae" scale="0.1 0.1 0.1"/>
<!-- The propeller meshes have a radius of 1m -->
<!-- <box size="${2*radius_rotor} 0.01 0.005"/> -->
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.005" radius="0.1"/>
<!-- [m] -->
</geometry>
</collision>
</link>
<gazebo>
<plugin filename="librotors_gazebo_motor_model.so" name="iris_back_left_motor_model">
<robotNamespace>iris</robotNamespace>
<jointName>iris/rotor_1_joint</jointName>
<linkName>iris/rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>838</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
</gazebo>
<gazebo reference="iris/rotor_1">
<material>Gazebo/Red</material>
</gazebo>
<joint name="iris/rotor_2_joint" type="continuous">
<origin rpy="0 0 0" xyz="0.13 0.22 0.023"/>
<axis xyz="0 0 1"/>
<!-- TODO(ff): not currently set because it's not yet supported -->
<!-- <limit effort="2000" velocity="${max_rot_velocity}" /> -->
<parent link="iris/base_link"/>
<child link="iris/rotor_2"/>
</joint>
<link name="iris/rotor_2">
<inertial>
<mass value="0.00005"/>
<!-- [kg] -->
<inertia ixx="9.7499961e-07" ixy="0.0" ixz="0.0" iyy="4.170414998500001e-05" iyz="0.0" izz="4.2604149625000006e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/propeller_cw.dae" scale="0.1 0.1 0.1"/>
<!-- The propeller meshes have a radius of 1m -->
<!-- <box size="${2*radius_rotor} 0.01 0.005"/> -->
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.005" radius="0.1"/>
<!-- [m] -->
</geometry>
</collision>
</link>
<gazebo>
<plugin filename="librotors_gazebo_motor_model.so" name="iris_front_left_motor_model">
<robotNamespace>iris</robotNamespace>
<jointName>iris/rotor_2_joint</jointName>
<linkName>iris/rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>838</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
</gazebo>
<gazebo reference="iris/rotor_2">
<material>Gazebo/Blue</material>
</gazebo>
<joint name="iris/rotor_3_joint" type="continuous">
<origin rpy="0 0 0" xyz="-0.13 -0.2 0.023"/>
<axis xyz="0 0 1"/>
<!-- TODO(ff): not currently set because it's not yet supported -->
<!-- <limit effort="2000" velocity="${max_rot_velocity}" /> -->
<parent link="iris/base_link"/>
<child link="iris/rotor_3"/>
</joint>
<link name="iris/rotor_3">
<inertial>
<mass value="0.00005"/>
<!-- [kg] -->
<inertia ixx="9.7499961e-07" ixy="0.0" ixz="0.0" iyy="4.170414998500001e-05" iyz="0.0" izz="4.2604149625000006e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/propeller_cw.dae" scale="0.1 0.1 0.1"/>
<!-- The propeller meshes have a radius of 1m -->
<!-- <box size="${2*radius_rotor} 0.01 0.005"/> -->
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.005" radius="0.1"/>
<!-- [m] -->
</geometry>
</collision>
</link>
<gazebo>
<plugin filename="librotors_gazebo_motor_model.so" name="iris_back_right_motor_model">
<robotNamespace>iris</robotNamespace>
<jointName>iris/rotor_3_joint</jointName>
<linkName>iris/rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>838</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
</gazebo>
<gazebo reference="iris/rotor_3">
<material>Gazebo/Red</material>
</gazebo>
</robot>