Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • nmansard/example-robot-data
  • jmarti/example-robot-data
  • wxmerkt/example-robot-data
  • pfernbac/example-robot-data
  • cmastall/example-robot-data
  • gsaurel/example-robot-data
  • gepetto/example-robot-data
7 results
Show changes
Showing
with 38975 additions and 326 deletions
SET(${PROJECT_NAME}_PYTHON_FILES
robots_loader.py
__main__.py
__init__.py
)
set(${PROJECT_NAME}_PYTHON_FILES robots_loader.py __main__.py __init__.py)
FOREACH(python ${${PROJECT_NAME}_PYTHON_FILES})
PYTHON_INSTALL_ON_SITE(${PY_NAME} ${python})
ENDFOREACH(python ${${PROJECT_NAME}_PYTHON_FILES})
foreach(python ${${PROJECT_NAME}_PYTHON_FILES})
python_install_on_site(${PY_NAME} ${python})
endforeach()
configure_file(${PY_NAME}/path.py.in ${PY_NAME}/path.py)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${PY_NAME}/path.py
DESTINATION "${PYTHON_SITELIB}/${PY_NAME}")
# flake8: noqa
from .robots_loader import (getModelPath, loadANYmal, loadHyQ, loadICub, loadKinova, loadRomeo, loadSolo, loadTalos,
loadTalosArm, loadTalosLegs, loadTiago, loadTiagoNoHand, loadUR, readParamsFromSrdf)
from .robots_loader import ROBOTS, getModelPath, load, load_full, readParamsFromSrdf
from argparse import ArgumentParser
from . import robots_loader
from .robots_loader import ROBOTS, load
ROBOTS = [
'anymal', 'anymal_kinova', 'hyq', 'solo', 'solo12', 'talos', 'talos_arm', 'talos_legs', 'kinova', 'tiago',
'tiago_no_hand', 'icub', 'ur5', 'romeo'
]
ROBOTS = sorted(ROBOTS.keys())
parser = ArgumentParser()
parser.add_argument('robot', nargs='?', default=ROBOTS[0], choices=ROBOTS)
parser = ArgumentParser(description=load.__doc__)
parser.add_argument("robot", nargs="?", default=ROBOTS[0], choices=ROBOTS)
parser.add_argument("--no-display", action="store_true")
args = parser.parse_args()
if args.robot == 'anymal':
anymal = robots_loader.loadANYmal()
anymal.initViewer(loadModel=True)
anymal.display(anymal.q0)
elif args.robot == 'anymal_kinova':
anymal = robots_loader.loadANYmal(withArm='kinova')
anymal.initViewer(loadModel=True)
anymal.display(anymal.q0)
elif args.robot == 'hyq':
hyq = robots_loader.loadHyQ()
hyq.initViewer(loadModel=True)
hyq.display(hyq.q0)
elif args.robot == 'solo':
solo = robots_loader.loadSolo()
solo.initViewer(loadModel=True)
solo.display(solo.q0)
elif args.robot == 'solo12':
solo = robots_loader.loadSolo(False)
solo.initViewer(loadModel=True)
solo.display(solo.q0)
elif args.robot == 'talos':
talos = robots_loader.loadTalos()
talos.initViewer(loadModel=True)
talos.display(talos.q0)
elif args.robot == 'talos_arm':
talos_arm = robots_loader.loadTalosArm()
talos_arm.initViewer(loadModel=True)
talos_arm.display(talos_arm.q0)
elif args.robot == 'talos_legs':
talos_legs = robots_loader.loadTalosLegs()
talos_legs.initViewer(loadModel=True)
talos_legs.display(talos_legs.q0)
elif args.robot == 'kinova':
kinova = robots_loader.loadKinova()
kinova.initViewer(loadModel=True)
kinova.display(kinova.q0)
elif args.robot == 'tiago':
tiago = robots_loader.loadTiago()
tiago.initViewer(loadModel=True)
tiago.display(tiago.q0)
elif args.robot == 'tiago_no_hand':
tiago_no_hand = robots_loader.loadTiagoNoHand()
tiago_no_hand.initViewer(loadModel=True)
tiago_no_hand.display(tiago_no_hand.q0)
elif args.robot == 'icub':
icub = robots_loader.loadICub()
icub.initViewer(loadModel=True)
icub.display(icub.q0)
elif args.robot == 'ur5':
ur5 = robots_loader.loadUR()
ur5.initViewer(loadModel=True)
ur5.display(ur5.q0)
elif args.robot == 'romeo':
romeo = robots_loader.loadRomeo()
romeo.initViewer(loadModel=True)
romeo.display(romeo.q0)
load(args.robot, display=not args.no_display)
EXAMPLE_ROBOT_DATA_MODEL_DIR = "${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/robots"
EXAMPLE_ROBOT_DATA_SOURCE_DIR = "${PROJECT_SOURCE_DIR}/robots"
# Unitree A1
upstream: https://github.com/unitreerobotics/unitree_ros/tree/master/robots/a1_description
license: MPL-2.0
### Modifications:
- Removed Gazebo and transmission tags
- Added SRDF
- Added colors in collada files and URDF
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
robots/a1_description/meshes/trunk_A1.png

70.2 KiB

<?xml version="1.0" ?>
<robot name="a1">
<group name="whole_body">
<joint name="root_joint"/>
<joint name="FL_hip_joint"/>
<joint name="FL_thigh_joint"/>
<joint name="FL_calf_joint"/>
<joint name="RL_hip_joint"/>
<joint name="RL_thigh_joint"/>
<joint name="RL_calf_joint"/>
<joint name="FR_hip_joint"/>
<joint name="FR_thigh_joint"/>
<joint name="FR_calf_joint"/>
<joint name="RR_hip_joint"/>
<joint name="RR_thigh_joint"/>
<joint name="RR_calf_joint"/>
</group>
<virtual_joint name="root_joint" type="floating" parent_frame="world_frame" child_link="base"/>
<group name="lf_leg">
<joint name="FL_hip_joint"/>
<joint name="FL_thigh_joint"/>
<joint name="FL_calf_joint"/>
<chain base_link="base" tip_link="FL_foot"/>
</group>
<group name="lh_leg">
<joint name="RL_hip_joint"/>
<joint name="RL_thigh_joint"/>
<joint name="RL_calf_joint"/>
<chain base_link="base" tip_link="RL_foot"/>
</group>
<group name="rf_leg">
<joint name="FR_hip_joint"/>
<joint name="FR_thigh_joint"/>
<joint name="FR_calf_joint"/>
<chain base_link="base" tip_link="FR_foot"/>
</group>
<group name="rh_leg">
<joint name="RR_hip_joint"/>
<joint name="RR_thigh_joint"/>
<joint name="RR_calf_joint"/>
<chain base_link="base" tip_link="RR_foot"/>
</group>
<group name="all_legs">
<group name="lf_leg"/>
<group name="rf_leg"/>
<group name="lh_leg"/>
<group name="rh_leg"/>
</group>
<group name="r_legs">
<group name="rf_leg"/>
<group name="rh_leg"/>
</group>
<group name="l_legs">
<group name="lf_leg"/>
<group name="lh_leg"/>
</group>
<group name="f_legs">
<group name="lf_leg"/>
<group name="rf_leg"/>
</group>
<group name="h_legs">
<group name="lh_leg"/>
<group name="rh_leg"/>
</group>
<group name="ld_legs">
<group name="lf_leg"/>
<group name="rh_leg"/>
</group>
<group name="rd_legs">
<group name="rf_leg"/>
<group name="lh_leg"/>
</group>
<end_effector name="lf_foot" parent_link="FL_foot" group="lf_leg"/>
<end_effector name="rf_foot" parent_link="FR_foot" group="rf_leg"/>
<end_effector name="lh_foot" parent_link="RL_foot" group="lh_leg"/>
<end_effector name="rh_foot" parent_link="RR_foot" group="rh_leg"/>
<group_state name="standing" group="whole_body">
<joint name="root_joint" value="0. 0. 0.26 0. 0. 0. 1."/>
<joint name="FL_hip_joint" value="0."/>
<joint name="FL_thigh_joint" value="0.8"/>
<joint name="FL_calf_joint" value="-1.81"/>
<joint name="FR_hip_joint" value="0."/>
<joint name="FR_thigh_joint" value="0.8"/>
<joint name="FR_calf_joint" value="-1.81"/>
<joint name="RL_hip_joint" value="0."/>
<joint name="RL_thigh_joint" value="0.8"/>
<joint name="RL_calf_joint" value="-1.81"/>
<joint name="RR_hip_joint" value="0."/>
<joint name="RR_thigh_joint" value="0.8"/>
<joint name="RR_calf_joint" value="-1.81"/>
</group_state>
<disable_collisions link1="FL_calf" link2="FL_foot" reason="Adjacent"/>
<disable_collisions link1="FL_calf" link2="FL_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="FL_thigh" reason="Adjacent"/>
<disable_collisions link1="FL_calf" link2="FL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_calf" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_calf" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FL_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FL_thigh" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_foot" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FL_thigh" reason="Adjacent"/>
<disable_collisions link1="FL_hip" link2="FL_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="FL_hip" link2="FR_calf" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_foot" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_thigh" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_foot" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_calf" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_foot" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="FL_thigh" link2="FL_thigh_shoulder" reason="Default"/>
<disable_collisions link1="FL_thigh" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_calf" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_foot" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_calf" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_foot" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="FR_calf" link2="FR_foot" reason="Adjacent"/>
<disable_collisions link1="FR_calf" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FR_calf" link2="FR_thigh" reason="Adjacent"/>
<disable_collisions link1="FR_calf" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_calf" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_calf" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="FR_foot" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FR_foot" link2="FR_thigh" reason="Never"/>
<disable_collisions link1="FR_foot" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_foot" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_foot" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_hip" link2="FR_thigh" reason="Adjacent"/>
<disable_collisions link1="FR_hip" link2="FR_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="FR_hip" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_foot" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_calf" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_foot" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="FR_thigh" link2="FR_thigh_shoulder" reason="Default"/>
<disable_collisions link1="FR_thigh" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_foot" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RL_foot" reason="Adjacent"/>
<disable_collisions link1="RL_calf" link2="RL_hip" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RL_thigh" reason="Adjacent"/>
<disable_collisions link1="RL_calf" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RL_hip" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RL_thigh" reason="Adjacent"/>
<disable_collisions link1="RL_hip" link2="RL_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="RL_hip" link2="RR_calf" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_foot" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="RL_thigh" link2="RL_thigh_shoulder" reason="Default"/>
<disable_collisions link1="RL_thigh" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_thigh" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_calf" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_foot" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="RR_calf" link2="RR_foot" reason="Adjacent"/>
<disable_collisions link1="RR_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RR_calf" link2="RR_thigh" reason="Adjacent"/>
<disable_collisions link1="RR_calf" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RR_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="RR_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RR_foot" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="RR_foot" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RR_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_hip" link2="RR_thigh" reason="Adjacent"/>
<disable_collisions link1="RR_hip" link2="RR_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="RR_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="RR_thigh" link2="RR_thigh_shoulder" reason="Default"/>
<disable_collisions link1="RR_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="imu_link" link2="trunk" reason="Adjacent"/>
</robot>
<?xml version="1.0" ?>
<!-- ==================================================================================================== -->
<!-- | This document was autogenerated by xacro, then had the Gazebo and transmission tags removed | -->
<!-- ==================================================================================================== -->
<robot name="a1">
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="silver">
<color rgba="0.6980 0.7529 0.8392 1"/>
</material>
<link name="base">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="floating_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base"/>
<child link="trunk"/>
</joint>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/trunk.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.267 0.194 0.114"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0041 -0.0005"/>
<mass value="6.0"/>
<inertia ixx="0.0158533" ixy="-3.66e-05" ixz="-6.11e-05" iyy="0.0377999" iyz="-2.75e-05" izz="0.0456542"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="trunk"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1805 -0.047 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-0.8028514559173915" upper="0.8028514559173915" velocity="21"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003311 -0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<joint name="FR_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="FR_thigh_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.032" radius="0.041"/>
</geometry>
</collision>
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0838 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-1.0471975511965976" upper="4.1887902047863905" velocity="21"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-2.6965336943312392" upper="-0.9162978572970231" velocity="21"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FR_calf"/>
<child link="FR_foot"/>
</joint>
<link name="FR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial>
</link>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1805 0.047 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-0.8028514559173915" upper="0.8028514559173915" velocity="21"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003311 0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<joint name="FL_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.081 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="FL_thigh_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.032" radius="0.041"/>
</geometry>
</collision>
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0838 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-1.0471975511965976" upper="4.1887902047863905" velocity="21"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-2.6965336943312392" upper="-0.9162978572970231" velocity="21"/>
</joint>
<link name="FL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="FL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FL_calf"/>
<child link="FL_foot"/>
</joint>
<link name="FL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial>
</link>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.1805 -0.047 0"/>
<parent link="trunk"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-0.8028514559173915" upper="0.8028514559173915" velocity="21"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.003311 -0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<joint name="RR_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="RR_thigh_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.032" radius="0.041"/>
</geometry>
</collision>
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="RR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0838 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-1.0471975511965976" upper="4.1887902047863905" velocity="21"/>
</joint>
<link name="RR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-2.6965336943312392" upper="-0.9162978572970231" velocity="21"/>
</joint>
<link name="RR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="RR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RR_calf"/>
<child link="RR_foot"/>
</joint>
<link name="RR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial>
</link>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.1805 0.047 0"/>
<parent link="trunk"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-0.8028514559173915" upper="0.8028514559173915" velocity="21"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.003311 0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<joint name="RL_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.081 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="RL_thigh_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.032" radius="0.041"/>
</geometry>
</collision>
<inertial>
<mass value="0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="RL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0838 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-1.0471975511965976" upper="4.1887902047863905" velocity="21"/>
</joint>
<link name="RL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-2.6965336943312392" upper="-0.9162978572970231" velocity="21"/>
</joint>
<link name="RL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="RL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="RL_calf"/>
<child link="RL_foot"/>
</joint>
<link name="RL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial>
</link>
</robot>
# Boarwalk Robotics - Alex Robot
upstream: [](https://github.com/boardwalkrobotics/alex-robot-models) license: CC BY-NC-ND 4.0
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.