Skip to content
Snippets Groups Projects
Commit 7f12d15b authored by Pep Marti Saumell's avatar Pep Marti Saumell
Browse files

2DOF description: added files and loader

parent 4698aa3c
No related branches found
No related tags found
1 merge request!21New descriptions
File added
File added
File added
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="2dof_planar">
<link
name="base_link">
<inertial>
<origin
xyz="0.0030299 2.6279E-13 0.02912"
rpy="0 0 0" />
<mass
value="0.10159" />
<inertia
ixx="2.636E-05"
ixy="-1.007E-16"
ixz="-2.3835E-06"
iyy="1.8042E-05"
iyz="-4.6617E-09"
izz="1.8795E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://2dof_description/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.96078 1 0 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://2dof_description/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="0.0086107 2.1727E-06 0.036012"
rpy="0 0 0" />
<mass
value="0.26703" />
<inertia
ixx="0.00040827"
ixy="1.2675E-09"
ixz="1.8738E-05"
iyy="0.00038791"
iyz="3.5443E-08"
izz="3.6421E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://2dof_description/meshes/link1.STL" />
</geometry>
<material
name="">
<color
rgba="0.64706 0.61961 0.58824 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://2dof_description/meshes/link1.STL" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0.0060872 0 0.035"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="1 0 0" />
<limit
lower="0"
upper="0"
effort="0"
velocity="0" />
<dynamics
damping="0.05" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="-0.0050107 1.9371E-10 0.10088"
rpy="0 0 0" />
<mass
value="0.33238" />
<inertia
ixx="0.0011753"
ixy="-3.854E-13"
ixz="-2.9304E-08"
iyy="0.0011666"
iyz="-5.2365E-12"
izz="1.4553E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://2dof_description/meshes/link2.STL" />
</geometry>
<material
name="">
<color
rgba="0.64706 0.61961 0.58824 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://2dof_description/meshes/link2.STL" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0.023 0 0.1"
rpy="0 0 0" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="1 0 0" />
<limit
lower="0"
upper="0"
effort="0"
velocity="0" />
<dynamics
damping="0.05" />
</joint>
</robot>
...@@ -46,6 +46,7 @@ IF(NOT INSTALL_PYTHON_INTERFACE_ONLY) ...@@ -46,6 +46,7 @@ IF(NOT INSTALL_PYTHON_INTERFACE_ONLY)
INSTALL(DIRECTORY tiago_description DESTINATION share/${PROJECT_NAME}) INSTALL(DIRECTORY tiago_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY ur_description DESTINATION share/${PROJECT_NAME}) INSTALL(DIRECTORY ur_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY hector_description DESTINATION share/${PROJECT_NAME}) INSTALL(DIRECTORY hector_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY 2dof_description DESTINATION share/${PROJECT_NAME})
ENDIF(NOT INSTALL_PYTHON_INTERFACE_ONLY) ENDIF(NOT INSTALL_PYTHON_INTERFACE_ONLY)
SETUP_PROJECT_FINALIZE() SETUP_PROJECT_FINALIZE()
# flake8: noqa # flake8: noqa
from .robots_loader import (getModelPath, loadANYmal, loadHyQ, loadICub, loadSolo, loadTalos, loadTalosArm, from .robots_loader import (getModelPath, loadANYmal, loadHyQ, loadICub, loadSolo, loadTalos, loadTalosArm,
loadTalosLegs, loadTiago, loadTiagoNoHand, loadUR, loadHector, readParamsFromSrdf) loadTalosLegs, loadTiago, loadTiagoNoHand, loadUR, loadHector, load2dof, readParamsFromSrdf)
...@@ -3,7 +3,7 @@ from argparse import ArgumentParser ...@@ -3,7 +3,7 @@ from argparse import ArgumentParser
from . import robots_loader from . import robots_loader
ROBOTS = [ ROBOTS = [
'anymal', 'hyq', 'solo', 'solo12', 'talos', 'talos_arm', 'talos_legs', 'tiago', 'tiago_no_hand', 'icub', 'ur5' 'anymal', 'hyq', 'solo', 'solo12', 'talos', 'talos_arm', 'talos_legs', 'tiago', 'tiago_no_hand', 'icub', 'ur5', 'hector', '2dof'
] ]
parser = ArgumentParser() parser = ArgumentParser()
...@@ -65,3 +65,14 @@ elif args.robot == 'ur5': ...@@ -65,3 +65,14 @@ elif args.robot == 'ur5':
ur5 = robots_loader.loadUR() ur5 = robots_loader.loadUR()
ur5.initViewer(loadModel=True) ur5.initViewer(loadModel=True)
ur5.display(ur5.q0) ur5.display(ur5.q0)
if args.robot == 'hector':
hector = robots_loader.loadHector()
hector.initViewer(loadModel=True)
hector.display(hector.q0)
if args.robot == '2dof':
planar2dof = robots_loader.load2dof()
planar2dof.initViewer(loadModel=True)
planar2dof.display(planar2dof.q0)
...@@ -236,3 +236,11 @@ def loadHector(): ...@@ -236,3 +236,11 @@ def loadHector():
modelPath = getModelPath(URDF_SUBPATH) modelPath = getModelPath(URDF_SUBPATH)
robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer()) robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath], pinocchio.JointModelFreeFlyer())
return robot return robot
def load2dof():
URDF_FILENAME = "2dof_planar.urdf"
URDF_SUBPATH = "/2dof_description/urdf/" + URDF_FILENAME
modelPath = getModelPath(URDF_SUBPATH)
robot = RobotWrapper.BuildFromURDF(modelPath + URDF_SUBPATH, [modelPath])
return robot
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment