Unverified Commit 939ea223 authored by Guilhem Saurel's avatar Guilhem Saurel Committed by GitHub
Browse files

Merge pull request #94 from jviereck/jviereck/bolt

Adds the Bolt robot to the repo
parents 5d6f078d b4269048
Pipeline #14980 passed with stage
in 1 minute and 28 seconds
......@@ -258,6 +258,14 @@ def loadHyQ():
return HyQLoader().robot
class BoltLoader(RobotLoader):
path = 'bolt_description'
urdf_filename = "bolt.urdf"
srdf_filename = "bolt.srdf"
ref_posture = "standing"
free_flyer = True
class Solo8Loader(RobotLoader):
path = 'solo_description'
urdf_filename = "solo.urdf"
......@@ -504,6 +512,7 @@ ROBOTS = {
'romeo': RomeoLoader,
'simple_humanoid': SimpleHumanoidLoader,
'simple_humanoid_classical': SimpleHumanoidClassicalLoader,
'bolt': BoltLoader,
'solo': SoloLoader,
'solo8': Solo8Loader,
'solo12': Solo12Loader,
......
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /usr/local/lib/python3.9/site-packages/robot_properties_bolt/resources/xacro/bolt.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="bolt" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<!-- This file is based on: https://atlas.is.localnet/confluence/display/AMDW/Quadruped+URDF+Files -->
<link name="base_link">
<!-- BASE LINK INERTIAL -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.61436936"/>
<!-- The base is extremely symmetrical. -->
<inertia ixx="0.00578574" ixy="0.0" ixz="0.0" iyy="0.01938108" iyz="0.0" izz="0.02476124"/>
</inertial>
<!-- BASE LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_body.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- BASE LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_body.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END BASE LINK -->
<!--xacro:property name="base_2_HAA_x" value="${2.45656 * 0.001}" />
<xacro:property name="base_2_HAA_y" value="${63.6 * 0.001}" />
<xacro:property name="base_2_HAA_z" value="${33.0809 * 0.001}" /-->
<joint name="FL_HAA" type="revolute">
<parent link="base_link"/>
<child link="FL_SHOULDER"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.0 0.0636 0"/>
<!--xacro:unless value="${is_right}">
<origin xyz="${base_2_HAA_x} ${base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
</xacro:unless>
<xacro:if value="${is_right}">
<origin xyz="${base_2_HAA_x} ${-base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
</xacro:if-->
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FL_SHOULDER">
<!-- TODO: Update inertias and add visuals for link. -->
<!-- create a dummy shoulder link to join the two joints -->
<inertial>
<!-- Left upper leg inertia -->
<mass value="0.14004265"/>
<origin rpy="0 0 0" xyz="0.01708256 -0.00446892 -0.01095830"/>
<inertia ixx="0.00007443" ixy="0.00000148" ixz="0.00002154" iyy="0.00013847" iyz="-0.00001096" izz="0.00009002"/>
</inertial>
<!-- HIP LEG LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_hip_fe_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- UPPER LEG LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_hip_fe_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<joint name="FL_HFE" type="revolute">
<parent link="FL_SHOULDER"/>
<child link="FL_UPPER_LEG"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0 0.0145 -0.0386"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FL_UPPER_LEG">
<!-- Left upper leg inertia -->
<inertial>
<origin rpy="0 0 0" xyz="0.00001377 0.01935853 -0.11870700"/>
<mass value="0.14853845"/>
<inertia ixx="0.00041107" ixy="0.00000000" ixz="0.00000009" iyy="0.00041193" iyz="-0.00004671" izz="0.00003024"/>
</inertial>
<!-- UPPER LEG LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/upper_leg_200mm_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- UPPER LEG LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/upper_leg_200mm_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END UPPER LEG LINK -->
<!-- KFE: Joint between the upper leg and the lower leg -->
<joint name="FL_KFE" type="revolute">
<parent link="FL_UPPER_LEG"/>
<child link="FL_LOWER_LEG"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0 0.0374 -0.2"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FL_LOWER_LEG">
<!-- Left lower leg inertia -->
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.00836718 -0.11591877"/>
<mass value="0.03117243"/>
<inertia ixx="0.00011487" ixy="0.00000000" ixz="0.00000000" iyy="0.00011556" iyz="-0.00000190" izz="0.00000220"/>
</inertial>
<!-- LOWER LEG LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/lower_leg_200mm_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- LOWER LEG LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/lower_leg_200mm_left_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END LOWER LEG LINK -->
<!-- KFE: Joint between the upper leg and the lower leg -->
<joint name="FL_ANKLE" type="fixed">
<parent link="FL_LOWER_LEG"/>
<child link="FL_FOOT"/>
<origin rpy="0 0 0" xyz="0 0.008 -0.2"/>
<!-- Limits (usefull?) -->
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FL_FOOT">
<!-- FOOT INERTIAL -->
<!-- This link is symmetrical left or right -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.00035767"/>
<mass value="0.00000000"/>
<inertia ixx="0.00000057" ixy="0.0" ixz="0.0" iyy="0.00000084" iyz="0.0" izz="0.00000053"/>
</inertial>
<!-- FOOT VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- FOOT COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="4.0"/>
<restitution value="0.0"/>
</contact>
</link>
<!-- END LOWER LEG LINK -->
<joint name="FR_HAA" type="revolute">
<parent link="base_link"/>
<child link="FR_SHOULDER"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the x-axis -->
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0.0 -0.0636 0"/>
<!--xacro:unless value="${is_right}">
<origin xyz="${base_2_HAA_x} ${base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
</xacro:unless>
<xacro:if value="${is_right}">
<origin xyz="${base_2_HAA_x} ${-base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
</xacro:if-->
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FR_SHOULDER">
<!-- TODO: Update inertias and add visuals for link. -->
<!-- create a dummy shoulder link to join the two joints -->
<inertial>
<!-- Right upper leg inertia -->
<mass value="0.14004412"/>
<origin rpy="0 0 0" xyz="0.01708233 0.00447099 -0.01095846"/>
<inertia ixx="0.00007442" ixy="-0.00000148" ixz="0.00002154" iyy="0.00013848" iyz="0.00001095" izz="0.00009001"/>
</inertial>
<!-- HIP LEG LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_hip_fe_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- UPPER LEG LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_hip_fe_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<joint name="FR_HFE" type="revolute">
<parent link="FR_SHOULDER"/>
<child link="FR_UPPER_LEG"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0 -0.0145 -0.0386"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FR_UPPER_LEG">
<!-- Right upper leg inertia -->
<inertial>
<origin rpy="0 0 0" xyz="-0.00001377 -0.01935853 -0.11870700"/>
<mass value="0.14853845"/>
<inertia ixx="0.00041107" ixy="0.00000000" ixz="-0.00000009" iyy="0.00041193" iyz="0.00004671" izz="0.00003024"/>
</inertial>
<!-- UPPER LEG LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/upper_leg_200mm_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- UPPER LEG LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/upper_leg_200mm_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END UPPER LEG LINK -->
<!-- KFE: Joint between the upper leg and the lower leg -->
<joint name="FR_KFE" type="revolute">
<parent link="FR_UPPER_LEG"/>
<child link="FR_LOWER_LEG"/>
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- joints rotates around the y-axis -->
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0 -0.0374 -0.2"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FR_LOWER_LEG">
<!-- Right lower leg inertia -->
<inertial>
<origin rpy="0 0 0" xyz="0.0 -0.00836718 -0.11591877"/>
<mass value="0.03117243"/>
<inertia ixx="0.00011487" ixy="0.00000000" ixz="0.00000000" iyy="0.00011556" iyz="0.00000190" izz="0.00000220"/>
</inertial>
<!-- LOWER LEG LINK VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/lower_leg_200mm_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- LOWER LEG LINK COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/lower_leg_200mm_right_side.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="1.0"/>
<restitution value="0.5"/>
</contact>
</link>
<!-- END LOWER LEG LINK -->
<!-- KFE: Joint between the upper leg and the lower leg -->
<joint name="FR_ANKLE" type="fixed">
<parent link="FR_LOWER_LEG"/>
<child link="FR_FOOT"/>
<origin rpy="0 0 0" xyz="0 -0.008 -0.2"/>
<!-- Limits (usefull?) -->
<limit effort="1000" lower="-10" upper="10" velocity="1000"/>
<!-- pybullet simulation parameters -->
<dynamics damping="0.0" friction="0.0"/>
</joint>
<link name="FR_FOOT">
<!-- FOOT INERTIAL -->
<!-- This link is symmetrical left or right -->
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.00035767"/>
<mass value="0.00000000"/>
<inertia ixx="0.00000057" ixy="0.0" ixz="0.0" iyy="0.00000084" iyz="0.0" izz="0.00000053"/>
</inertial>
<!-- FOOT VISUAL -->
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</visual>
<!-- FOOT COLLISION -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bolt_description/meshes/stl/bolt_foot.stl"/>
</geometry>
<material name="grey">
<color rgba="0.8 0.8 0.8 1.0"/>
</material>
</collision>
<!-- Bullet specific paramters -->
<contact>
<lateral_friction value="4.0"/>
<restitution value="0.0"/>
</contact>
</link>
<!-- END LOWER LEG LINK -->
</robot>
<?xml version="1.0" ?>
<robot name="finger_edu">
<!-- left leg -->
<group name="left_leg">
<joint name="FL_HAA" />
<joint name="FL_HFE" />
<joint name="FL_KFE" />
<chain base_link="base_link" tip_link="FL_FOOT" />
</group>
<!-- right leg -->
<group name="right_leg">
<joint name="FR_HAA" />
<joint name="FR_HFE" />
<joint name="FR_KFE" />
<chain base_link="base_link" tip_link="FR_FOOT" />
</group>
<group name="all_legs">
<group name="left_leg" />
<group name="right_leg" />
</group>
<end_effector name="left_foot" parent_link="FL_FOOT" group="left_leg" />
<end_effector name="right_foot" parent_link="FR_FOOT" group="right_leg" />
<group_state name="standing" group="all_legs">
<joint name="root_joint" value="0. 0. 0.35487417 0. 0. 0. 1." />
<joint name="FL_HAA" value="-0.3" />
<joint name="FL_HFE" value="0.78539816" />
<joint name="FL_KFE" value="-1.57079633" />
<joint name="FR_HAA" value="0.3" />
<joint name="FR_HFE" value="0.78539816" />
<joint name="FR_KFE" value="-1.57079633" />
</group_state>
<disable_collisions link1="FL_SHOULDER" link2="base_link" reason="Adjacent" />
<disable_collisions link1="FR_SHOULDER" link2="base_link" reason="Adjacent" />
<disable_collisions link1="FL_UPPER_LEG" link2="FL_SHOULDER" reason="Adjacent" />
<disable_collisions link1="FR_UPPER_LEG" link2="FR_SHOULDER" reason="Adjacent" />
<disable_collisions link1="FL_LOWER_LEG" link2="FL_UPPER_LEG" reason="Adjacent" />
<disable_collisions link1="FR_LOWER_LEG" link2="FR_UPPER_LEG" reason="Adjacent" />
</robot>
......@@ -73,6 +73,9 @@ class RobotTestCase(unittest.TestCase):
def test_simple_humanoid_classical(self):
self.check('simple_humanoid_classical', 36, 35, one_kg_bodies=['LARM_LINK3', 'RARM_LINK3'])
def test_bolt(self):
self.check('bolt', 13, 12)
def test_solo8(self):
self.check('solo8', 15, 14)
......
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