Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Gepetto
example-robot-data
Commits
7fe3792e
Unverified
Commit
7fe3792e
authored
Jun 20, 2020
by
Guilhem Saurel
Committed by
GitHub
Jun 20, 2020
Browse files
Merge pull request #32 from jcarpent/master
Add Panda robot
parents
ea2d6af2
6a180774
Pipeline
#9878
passed with stage
in 4 minutes and 58 seconds
Changes
26
Pipelines
1
Expand all
Hide whitespace changes
Inline
Side-by-side
robots/panda_description/meshes/visual/link4.dae
0 → 100644
View file @
7fe3792e
This diff is collapsed.
Click to expand it.
robots/panda_description/meshes/visual/link5.dae
0 → 100644
View file @
7fe3792e
This diff is collapsed.
Click to expand it.
robots/panda_description/meshes/visual/link6.dae
0 → 100644
View file @
7fe3792e
This diff is collapsed.
Click to expand it.
robots/panda_description/meshes/visual/link7.dae
0 → 100644
View file @
7fe3792e
This diff is collapsed.
Click to expand it.
robots/panda_description/urdf/panda.urdf
0 → 100644
View file @
7fe3792e
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /opt/ros/kinetic/share/moveit_resources/panda_description/urdf/panda.urdf | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot
name=
"panda"
xmlns:xacro=
"http://www.ros.org/wiki/xacro"
>
<link
name=
"panda_link0"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link0.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link0.stl"
/>
</geometry>
</collision>
</link>
<link
name=
"panda_link1"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link1.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link1.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint1"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-2.8973"
soft_upper_limit=
"2.8973"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.333"
/>
<parent
link=
"panda_link0"
/>
<child
link=
"panda_link1"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"87"
lower=
"-2.9671"
upper=
"2.9671"
velocity=
"2.3925"
/>
</joint>
<link
name=
"panda_link2"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link2.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link2.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint2"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-1.7628"
soft_upper_limit=
"1.7628"
/>
<origin
rpy=
"-1.57079632679 0 0"
xyz=
"0 0 0"
/>
<parent
link=
"panda_link1"
/>
<child
link=
"panda_link2"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"87"
lower=
"-1.8326"
upper=
"1.8326"
velocity=
"2.3925"
/>
</joint>
<link
name=
"panda_link3"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link3.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link3.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint3"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-2.8973"
soft_upper_limit=
"2.8973"
/>
<origin
rpy=
"1.57079632679 0 0"
xyz=
"0 -0.316 0"
/>
<parent
link=
"panda_link2"
/>
<child
link=
"panda_link3"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"87"
lower=
"-2.9671"
upper=
"2.9671"
velocity=
"2.3925"
/>
</joint>
<link
name=
"panda_link4"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link4.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link4.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint4"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-3.0718"
soft_upper_limit=
"0.0175"
/>
<origin
rpy=
"1.57079632679 0 0"
xyz=
"0.0825 0 0"
/>
<parent
link=
"panda_link3"
/>
<child
link=
"panda_link4"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"87"
lower=
"-3.1416"
upper=
"0.0873"
velocity=
"2.3925"
/>
</joint>
<link
name=
"panda_link5"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link5.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link5.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint5"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-2.8973"
soft_upper_limit=
"2.8973"
/>
<origin
rpy=
"-1.57079632679 0 0"
xyz=
"-0.0825 0.384 0"
/>
<parent
link=
"panda_link4"
/>
<child
link=
"panda_link5"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"12"
lower=
"-2.9671"
upper=
"2.9671"
velocity=
"2.8710"
/>
</joint>
<link
name=
"panda_link6"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link6.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link6.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint6"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-0.0175"
soft_upper_limit=
"3.7525"
/>
<origin
rpy=
"1.57079632679 0 0"
xyz=
"0 0 0"
/>
<parent
link=
"panda_link5"
/>
<child
link=
"panda_link6"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"12"
lower=
"-0.0873"
upper=
"3.8223"
velocity=
"2.8710"
/>
</joint>
<link
name=
"panda_link7"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/link7.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/link7.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_joint7"
type=
"revolute"
>
<safety_controller
k_position=
"100.0"
k_velocity=
"40.0"
soft_lower_limit=
"-2.8973"
soft_upper_limit=
"2.8973"
/>
<origin
rpy=
"1.57079632679 0 0"
xyz=
"0.088 0 0"
/>
<parent
link=
"panda_link6"
/>
<child
link=
"panda_link7"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"12"
lower=
"-2.9671"
upper=
"2.9671"
velocity=
"2.8710"
/>
</joint>
<link
name=
"panda_link8"
/>
<joint
name=
"panda_joint8"
type=
"fixed"
>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.107"
/>
<parent
link=
"panda_link7"
/>
<child
link=
"panda_link8"
/>
<axis
xyz=
"0 0 0"
/>
</joint>
<joint
name=
"panda_hand_joint"
type=
"fixed"
>
<parent
link=
"panda_link8"
/>
<child
link=
"panda_hand"
/>
<origin
rpy=
"0 0 -0.785398163397"
xyz=
"0 0 0"
/>
</joint>
<link
name=
"panda_hand"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/hand.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/hand.stl"
/>
</geometry>
</collision>
</link>
<link
name=
"panda_leftfinger"
>
<visual>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/finger.dae"
/>
</geometry>
</visual>
<collision>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/finger.stl"
/>
</geometry>
</collision>
</link>
<link
name=
"panda_rightfinger"
>
<visual>
<origin
rpy=
"0 0 3.14159265359"
xyz=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/visual/finger.dae"
/>
</geometry>
</visual>
<collision>
<origin
rpy=
"0 0 3.14159265359"
xyz=
"0 0 0"
/>
<geometry>
<mesh
filename=
"package://example-robot-data/robots/panda_description/meshes/collision/finger.stl"
/>
</geometry>
</collision>
</link>
<joint
name=
"panda_finger_joint1"
type=
"prismatic"
>
<parent
link=
"panda_hand"
/>
<child
link=
"panda_leftfinger"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0584"
/>
<axis
xyz=
"0 1 0"
/>
<limit
effort=
"20"
lower=
"0.0"
upper=
"0.04"
velocity=
"0.2"
/>
</joint>
<joint
name=
"panda_finger_joint2"
type=
"prismatic"
>
<parent
link=
"panda_hand"
/>
<child
link=
"panda_rightfinger"
/>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0.0584"
/>
<axis
xyz=
"0 -1 0"
/>
<limit
effort=
"20"
lower=
"0.0"
upper=
"0.04"
velocity=
"0.2"
/>
<mimic
joint=
"panda_finger_joint1"
/>
</joint>
</robot>
unittest/test_load.py
View file @
7fe3792e
...
...
@@ -125,11 +125,17 @@ class RomeoTest(RobotTestCase):
RobotTestCase
.
NV
=
61
class
PandaTest
(
RobotTestCase
):
RobotTestCase
.
ROBOT
=
example_robot_data
.
loadPanda
()
RobotTestCase
.
NQ
=
9
RobotTestCase
.
NV
=
9
if
__name__
==
'__main__'
:
test_classes_to_run
=
[
ANYmalTest
,
ANYmalKinovaTest
,
HyQTest
,
TalosTest
,
TalosArmTest
,
TalosArmFloatingTest
,
TalosLegsTest
,
ICubTest
,
SoloTest
,
Solo12Test
,
TiagoTest
,
TiagoNoHandTest
,
UR5Test
,
UR5LimitedTest
,
UR5GripperTest
,
KinovaTest
,
RomeoTest
RomeoTest
,
PandaTest
]
loader
=
unittest
.
TestLoader
()
suites_list
=
[]
...
...
Prev
1
2
Next
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment