Unverified Commit b2e1bfcc authored by Carlos Mastalli's avatar Carlos Mastalli Committed by GitHub
Browse files

Add the IRIS quadcopter model



* Added quadcopter Iris from 3DRobotics

* [readme] add hector and iris to the launch command

* [iris] Added reduced version of the STL file
Co-authored-by: Pep Marti Saumell's avatarPepMS <jmarti@iri.upc.edu>
parent f0d2380d
Pipeline #8921 failed with stage
in 2 minutes and 49 seconds
......@@ -46,7 +46,7 @@ If you have never added robotpkg as a softwares repository, please follow first
(you will need pinocchio and its Python bindings)
`python -m example_robot_data [anymal,anymal_kinova,hyq,solo,solo12,talos,talos_arm,talos_legs,tiago,tiago_no_hand,icub,ur5]`
`python -m example_robot_data [anymal,anymal_kinova,hyq,solo,solo12,talos,talos_arm,talos_legs,tiago,tiago_no_hand,icub,ur5,hector,iris]`
This will work from the `python` subdirectory inside this repository, or if this package has been installed on your
system.
# flake8: noqa
from .robots_loader import (getModelPath, loadANYmal, loadHyQ, loadICub, loadKinova, loadRomeo, loadSolo, loadTalos,
loadTalosArm, loadTalosLegs, loadTiago, loadTiagoNoHand, loadUR, readParamsFromSrdf,
loadHector, loadDoublePendulum)
loadHector, loadDoublePendulum, loadIris)
......@@ -8,7 +8,7 @@ eigenpy.switchToNumpyMatrix()
ROBOTS = [
'anymal', 'anymal_kinova', 'hyq', 'solo', 'solo12', 'talos', 'talos_arm', 'talos_legs', 'kinova', 'tiago',
'tiago_no_hand', 'icub', 'ur5', 'romeo', 'hector', 'double_pendulum'
'tiago_no_hand', 'icub', 'ur5', 'romeo', 'hector', 'double_pendulum', 'iris'
]
parser = ArgumentParser()
......@@ -95,3 +95,8 @@ if args.robot == 'double_pendulum':
pendulum = robots_loader.loadDoublePendulum()
pendulum.initViewer(loadModel=True)
pendulum.display(pendulum.q0)
if args.robot == 'iris':
iris = robots_loader.loadIris()
iris.initViewer(loadModel=True)
iris.display(iris.q0)
......@@ -287,3 +287,10 @@ def loadRomeo():
URDF_SUBPATH = "/romeo_description/urdf/" + URDF_FILENAME
modelPath = getModelPath(URDF_SUBPATH)
return RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
def loadIris():
URDF_FILENAME = "iris_simple.urdf"
URDF_SUBPATH = "/iris_description/robots/" + URDF_FILENAME
modelPath = getModelPath(URDF_SUBPATH)
robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
return robot
\ No newline at end of file
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
<?xml version="1.0" ?>
<robot name="iris">
<joint name="iris__/imu_joint" type="fixed">
<parent link="iris__base_link"/>
<child link="iris__/imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="1 0 0"/>
<limit effort="0.0" lower="0.0" upper="0.0" velocity="0.0"/>
</joint>
<joint name="iris__rotor_0_joint" type="revolute">
<parent link="iris__base_link"/>
<child link="iris__rotor_0"/>
<origin rpy="0 0 0" xyz="0.13 -0.22 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<joint name="iris__rotor_1_joint" type="revolute">
<parent link="iris__base_link"/>
<child link="iris__rotor_1"/>
<origin rpy="0 0 0" xyz="-0.13 0.2 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<joint name="iris__rotor_2_joint" type="revolute">
<parent link="iris__base_link"/>
<child link="iris__rotor_2"/>
<origin rpy="0 0 0" xyz="0.13 0.22 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<joint name="iris__rotor_3_joint" type="revolute">
<parent link="iris__base_link"/>
<child link="iris__rotor_3"/>
<origin rpy="0 0 0" xyz="-0.13 -0.2 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<link name="iris__base_link">
<inertial>
<mass value="1.5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.029125" ixy="0" ixz="0" iyy="0.029125" iyz="0" izz="0.055225"/>
</inertial>
<collision name="iris__base_link_inertia_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.47 0.47 0.11"/>
</geometry>
</collision>
<visual name="iris__base_link_inertia_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris.stl" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__/imu_link">
<inertial>
<mass value="0.015"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-05" ixy="0" ixz="0" iyy="1e-05" iyz="0" izz="1e-05"/>
</inertial>
</link>
<link name="iris__rotor_0">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_0_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_0_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__rotor_1">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_1_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_1_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__rotor_2">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_2_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_2_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_cw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__rotor_3">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_3_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_3_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_cw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
</robot>
<?xml version="1.0" ?>
<robot name="iris">
<joint name="iris__/imu_joint" type="fixed">
<parent link="iris__base_link"/>
<child link="iris__/imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="1 0 0"/>
<limit effort="0.0" lower="0.0" upper="0.0" velocity="0.0"/>
</joint>
<joint name="iris__rotor_0_joint" type="fixed">
<parent link="iris__base_link"/>
<child link="iris__rotor_0"/>
<origin rpy="0 0 0" xyz="0.13 -0.22 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<joint name="iris__rotor_1_joint" type="fixed">
<parent link="iris__base_link"/>
<child link="iris__rotor_1"/>
<origin rpy="0 0 0" xyz="-0.13 0.2 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<joint name="iris__rotor_2_joint" type="fixed">
<parent link="iris__base_link"/>
<child link="iris__rotor_2"/>
<origin rpy="0 0 0" xyz="0.13 0.22 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<joint name="iris__rotor_3_joint" type="fixed">
<parent link="iris__base_link"/>
<child link="iris__rotor_3"/>
<origin rpy="0 0 0" xyz="-0.13 -0.2 0.023"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
</joint>
<link name="iris__base_link">
<inertial>
<mass value="1.5"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.029125" ixy="0" ixz="0" iyy="0.029125" iyz="0" izz="0.055225"/>
</inertial>
<collision name="iris__base_link_inertia_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.47 0.47 0.11"/>
</geometry>
</collision>
<visual name="iris__base_link_inertia_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris.stl" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__/imu_link">
<inertial>
<mass value="0.015"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-05" ixy="0" ixz="0" iyy="1e-05" iyz="0" izz="1e-05"/>
</inertial>
</link>
<link name="iris__rotor_0">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_0_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_0_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__rotor_1">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_1_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_1_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__rotor_2">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_2_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_2_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_cw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="iris__rotor_3">
<inertial>
<mass value="0.005"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
</inertial>
<collision name="iris__rotor_3_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.128"/>
</geometry>
</collision>
<visual name="iris__rotor_3_visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iris_description/meshes/iris_prop_cw.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
</robot>
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment