Nao Helmet Added

>3D Printed helmet for accessories on top of Nao's head added
>Designed for adding cameras (in order to make stereo vision possible), but maybe can be used for other accessories too
This commit is contained in:
Konstantinos Chatzilygeroudis 2014-05-22 10:28:30 +03:00
parent ff5a60073b
commit f1b9c2e057
9 changed files with 475 additions and 36 deletions

View File

@ -89,50 +89,67 @@
<disable_collisions link1="LHip" link2="LKnee" reason="Never" />
<disable_collisions link1="LHip" link2="LShoulder" reason="Never" />
<disable_collisions link1="LHip" link2="LShoulderDummy" reason="Never" />
<disable_collisions link1="LHip" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LHip" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LHip" link2="RHip" reason="Never" />
<disable_collisions link1="LHip" link2="RHipDummy" reason="Never" />
<disable_collisions link1="LHip" link2="RHipYaw" reason="Never" />
<disable_collisions link1="LHip" link2="RKnee" reason="Never" />
<disable_collisions link1="LHip" link2="RShoulder" reason="Never" />
<disable_collisions link1="LHip" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LHip" link2="RightCamera" reason="Never" />
<disable_collisions link1="LHip" link2="gaze" reason="Never" />
<disable_collisions link1="LHip" link2="helmet" reason="Never" />
<disable_collisions link1="LHip" link2="l_ankle" reason="Never" />
<disable_collisions link1="LHip" link2="neck" reason="Never" />
<disable_collisions link1="LHip" link2="r_ankle" reason="Never" />
<disable_collisions link1="LHip" link2="torso" reason="Never" />
<disable_collisions link1="LHip" link2="r_sole" reason="Never" />
<disable_collisions link1="LHipDummy" link2="LHipYaw" reason="Default" />
<disable_collisions link1="LHipDummy" link2="LKnee" reason="Adjacent" />
<disable_collisions link1="LHipDummy" link2="LShoulder" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RHip" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RHipYaw" reason="Never" />
<disable_collisions link1="LHipDummy" link2="LShoulderDummy" reason="Never" />
<disable_collisions link1="LHipDummy" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RHip" reason="Default" />
<disable_collisions link1="LHipDummy" link2="RHipDummy" reason="Default" />
<disable_collisions link1="LHipDummy" link2="RHipYaw" reason="Default" />
<disable_collisions link1="LHipDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RightCamera" reason="Never" />
<disable_collisions link1="LHipDummy" link2="gaze" reason="Never" />
<disable_collisions link1="LHipDummy" link2="helmet" reason="Never" />
<disable_collisions link1="LHipDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="LHipDummy" link2="neck" reason="Never" />
<disable_collisions link1="LHipDummy" link2="torso" reason="Default" />
<disable_collisions link1="LHipYaw" link2="LKnee" reason="Never" />
<disable_collisions link1="LHipYaw" link2="LShoulder" reason="Never" />
<disable_collisions link1="LHipYaw" link2="LShoulderDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RHip" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RHipDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RHipYaw" reason="Adjacent" />
<disable_collisions link1="LHipYaw" link2="RKnee" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RShoulder" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RightCamera" reason="Never" />
<disable_collisions link1="LHipYaw" link2="gaze" reason="Never" />
<disable_collisions link1="LHipYaw" link2="helmet" reason="Never" />
<disable_collisions link1="LHipYaw" link2="l_ankle" reason="Never" />
<disable_collisions link1="LHipYaw" link2="neck" reason="Never" />
<disable_collisions link1="LHipYaw" link2="r_wrist" reason="Never" />
<disable_collisions link1="LHipYaw" link2="torso" reason="Adjacent" />
<disable_collisions link1="LKnee" link2="LShoulder" reason="Never" />
<disable_collisions link1="LKnee" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LKnee" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LKnee" link2="RKnee" reason="Default" />
<disable_collisions link1="LKnee" link2="RShoulder" reason="Never" />
<disable_collisions link1="LKnee" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LKnee" link2="RightCamera" reason="Never" />
<disable_collisions link1="LKnee" link2="gaze" reason="Never" />
<disable_collisions link1="LKnee" link2="helmet" reason="Never" />
<disable_collisions link1="LKnee" link2="l_ankle" reason="Adjacent" />
<disable_collisions link1="LKnee" link2="l_sole" reason="Default" />
<disable_collisions link1="LKnee" link2="neck" reason="Never" />
<disable_collisions link1="LKnee" link2="r_wrist" reason="Never" />
<disable_collisions link1="LKnee" link2="torso" reason="Never" />
<disable_collisions link1="LShoulder" link2="LShoulderDummy" reason="Adjacent" />
<disable_collisions link1="LShoulder" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LShoulder" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LShoulder" link2="RHip" reason="Never" />
<disable_collisions link1="LShoulder" link2="RHipDummy" reason="Never" />
@ -140,6 +157,9 @@
<disable_collisions link1="LShoulder" link2="RKnee" reason="Never" />
<disable_collisions link1="LShoulder" link2="RShoulder" reason="Never" />
<disable_collisions link1="LShoulder" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LShoulder" link2="RightCamera" reason="Never" />
<disable_collisions link1="LShoulder" link2="gaze" reason="Default" />
<disable_collisions link1="LShoulder" link2="helmet" reason="Never" />
<disable_collisions link1="LShoulder" link2="l_ankle" reason="Never" />
<disable_collisions link1="LShoulder" link2="l_sole" reason="Never" />
<disable_collisions link1="LShoulder" link2="l_wrist" reason="Never" />
@ -155,28 +175,42 @@
<disable_collisions link1="LShoulderDummy" link2="RKnee" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="gaze" reason="Default" />
<disable_collisions link1="LShoulderDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="l_sole" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="l_wrist" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="neck" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="r_sole" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="r_wrist" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="torso" reason="Default" />
<disable_collisions link1="LeftCamera" link2="RHip" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RHipDummy" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RHipYaw" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RKnee" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RShoulder" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RightCamera" reason="Never" />
<disable_collisions link1="LeftCamera" link2="gaze" reason="Never" />
<disable_collisions link1="LeftCamera" link2="helmet" reason="Adjacent" />
<disable_collisions link1="LeftCamera" link2="l_ankle" reason="Never" />
<disable_collisions link1="LeftCamera" link2="l_sole" reason="Never" />
<disable_collisions link1="LeftCamera" link2="neck" reason="Never" />
<disable_collisions link1="LeftCamera" link2="r_ankle" reason="Never" />
<disable_collisions link1="LeftCamera" link2="r_sole" reason="Never" />
<disable_collisions link1="LeftCamera" link2="torso" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="RShoulderDummy" reason="Adjacent" />
<disable_collisions link1="RElbowDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="l_sole" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="l_wrist" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="neck" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="r_wrist" reason="Adjacent" />
<disable_collisions link1="RHip" link2="RHipDummy" reason="Adjacent" />
<disable_collisions link1="RHip" link2="RHipYaw" reason="Adjacent" />
<disable_collisions link1="RHip" link2="RKnee" reason="Never" />
<disable_collisions link1="RHip" link2="RShoulder" reason="Never" />
<disable_collisions link1="RHip" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="RHip" link2="RightCamera" reason="Never" />
<disable_collisions link1="RHip" link2="gaze" reason="Never" />
<disable_collisions link1="RHip" link2="helmet" reason="Never" />
<disable_collisions link1="RHip" link2="l_ankle" reason="Never" />
<disable_collisions link1="RHip" link2="neck" reason="Never" />
<disable_collisions link1="RHip" link2="r_ankle" reason="Never" />
@ -184,22 +218,32 @@
<disable_collisions link1="RHipDummy" link2="RHipYaw" reason="Default" />
<disable_collisions link1="RHipDummy" link2="RKnee" reason="Adjacent" />
<disable_collisions link1="RHipDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="RHipDummy" link2="RightCamera" reason="Never" />
<disable_collisions link1="RHipDummy" link2="gaze" reason="Never" />
<disable_collisions link1="RHipDummy" link2="helmet" reason="Never" />
<disable_collisions link1="RHipDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="RHipDummy" link2="neck" reason="Never" />
<disable_collisions link1="RHipDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RKnee" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RShoulder" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RightCamera" reason="Never" />
<disable_collisions link1="RHipYaw" link2="gaze" reason="Never" />
<disable_collisions link1="RHipYaw" link2="helmet" reason="Never" />
<disable_collisions link1="RHipYaw" link2="l_ankle" reason="Never" />
<disable_collisions link1="RHipYaw" link2="neck" reason="Never" />
<disable_collisions link1="RHipYaw" link2="r_ankle" reason="Never" />
<disable_collisions link1="RHipYaw" link2="torso" reason="Adjacent" />
<disable_collisions link1="RKnee" link2="RShoulder" reason="Never" />
<disable_collisions link1="RKnee" link2="RightCamera" reason="Never" />
<disable_collisions link1="RKnee" link2="gaze" reason="Never" />
<disable_collisions link1="RKnee" link2="helmet" reason="Never" />
<disable_collisions link1="RKnee" link2="l_wrist" reason="Never" />
<disable_collisions link1="RKnee" link2="neck" reason="Never" />
<disable_collisions link1="RKnee" link2="r_ankle" reason="Adjacent" />
<disable_collisions link1="RKnee" link2="r_sole" reason="Default" />
<disable_collisions link1="RKnee" link2="torso" reason="Never" />
<disable_collisions link1="RShoulder" link2="RShoulderDummy" reason="Adjacent" />
<disable_collisions link1="RShoulder" link2="RightCamera" reason="Never" />
<disable_collisions link1="RShoulder" link2="helmet" reason="Never" />
<disable_collisions link1="RShoulder" link2="l_ankle" reason="Never" />
<disable_collisions link1="RShoulder" link2="l_sole" reason="Never" />
<disable_collisions link1="RShoulder" link2="l_wrist" reason="Never" />
@ -213,25 +257,36 @@
<disable_collisions link1="RShoulderDummy" link2="l_wrist" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="neck" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="r_sole" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="r_wrist" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="torso" reason="Default" />
<disable_collisions link1="RightCamera" link2="gaze" reason="Never" />
<disable_collisions link1="RightCamera" link2="helmet" reason="Adjacent" />
<disable_collisions link1="RightCamera" link2="l_ankle" reason="Never" />
<disable_collisions link1="RightCamera" link2="l_sole" reason="Never" />
<disable_collisions link1="RightCamera" link2="neck" reason="Never" />
<disable_collisions link1="RightCamera" link2="r_ankle" reason="Never" />
<disable_collisions link1="RightCamera" link2="r_sole" reason="Never" />
<disable_collisions link1="RightCamera" link2="torso" reason="Never" />
<disable_collisions link1="gaze" link2="helmet" reason="Adjacent" />
<disable_collisions link1="gaze" link2="l_ankle" reason="Never" />
<disable_collisions link1="gaze" link2="l_sole" reason="Never" />
<disable_collisions link1="gaze" link2="neck" reason="Adjacent" />
<disable_collisions link1="gaze" link2="r_ankle" reason="Never" />
<disable_collisions link1="gaze" link2="r_sole" reason="Never" />
<disable_collisions link1="gaze" link2="torso" reason="Default" />
<disable_collisions link1="helmet" link2="l_ankle" reason="Never" />
<disable_collisions link1="helmet" link2="l_sole" reason="Never" />
<disable_collisions link1="helmet" link2="neck" reason="Never" />
<disable_collisions link1="helmet" link2="r_ankle" reason="Never" />
<disable_collisions link1="helmet" link2="r_sole" reason="Never" />
<disable_collisions link1="helmet" link2="torso" reason="Never" />
<disable_collisions link1="l_ankle" link2="l_sole" reason="Adjacent" />
<disable_collisions link1="l_ankle" link2="neck" reason="Never" />
<disable_collisions link1="l_ankle" link2="r_wrist" reason="Never" />
<disable_collisions link1="l_ankle" link2="torso" reason="Never" />
<disable_collisions link1="l_sole" link2="neck" reason="Never" />
<disable_collisions link1="l_sole" link2="r_wrist" reason="Never" />
<disable_collisions link1="l_sole" link2="torso" reason="Never" />
<disable_collisions link1="l_wrist" link2="neck" reason="Never" />
<disable_collisions link1="l_wrist" link2="r_ankle" reason="Never" />
<disable_collisions link1="l_wrist" link2="r_sole" reason="Never" />
<disable_collisions link1="l_wrist" link2="r_wrist" reason="Default" />
<disable_collisions link1="neck" link2="r_ankle" reason="Never" />
<disable_collisions link1="neck" link2="r_sole" reason="Never" />
<disable_collisions link1="neck" link2="r_wrist" reason="Never" />

View File

@ -120,50 +120,67 @@
<disable_collisions link1="LHip" link2="LKnee" reason="Never" />
<disable_collisions link1="LHip" link2="LShoulder" reason="Never" />
<disable_collisions link1="LHip" link2="LShoulderDummy" reason="Never" />
<disable_collisions link1="LHip" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LHip" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LHip" link2="RHip" reason="Never" />
<disable_collisions link1="LHip" link2="RHipDummy" reason="Never" />
<disable_collisions link1="LHip" link2="RHipYaw" reason="Never" />
<disable_collisions link1="LHip" link2="RKnee" reason="Never" />
<disable_collisions link1="LHip" link2="RShoulder" reason="Never" />
<disable_collisions link1="LHip" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LHip" link2="RightCamera" reason="Never" />
<disable_collisions link1="LHip" link2="gaze" reason="Never" />
<disable_collisions link1="LHip" link2="helmet" reason="Never" />
<disable_collisions link1="LHip" link2="l_ankle" reason="Never" />
<disable_collisions link1="LHip" link2="neck" reason="Never" />
<disable_collisions link1="LHip" link2="r_ankle" reason="Never" />
<disable_collisions link1="LHip" link2="torso" reason="Never" />
<disable_collisions link1="LHip" link2="r_sole" reason="Never" />
<disable_collisions link1="LHipDummy" link2="LHipYaw" reason="Default" />
<disable_collisions link1="LHipDummy" link2="LKnee" reason="Adjacent" />
<disable_collisions link1="LHipDummy" link2="LShoulder" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RHip" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RHipYaw" reason="Never" />
<disable_collisions link1="LHipDummy" link2="LShoulderDummy" reason="Never" />
<disable_collisions link1="LHipDummy" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RHip" reason="Default" />
<disable_collisions link1="LHipDummy" link2="RHipDummy" reason="Default" />
<disable_collisions link1="LHipDummy" link2="RHipYaw" reason="Default" />
<disable_collisions link1="LHipDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LHipDummy" link2="RightCamera" reason="Never" />
<disable_collisions link1="LHipDummy" link2="gaze" reason="Never" />
<disable_collisions link1="LHipDummy" link2="helmet" reason="Never" />
<disable_collisions link1="LHipDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="LHipDummy" link2="neck" reason="Never" />
<disable_collisions link1="LHipDummy" link2="torso" reason="Default" />
<disable_collisions link1="LHipYaw" link2="LKnee" reason="Never" />
<disable_collisions link1="LHipYaw" link2="LShoulder" reason="Never" />
<disable_collisions link1="LHipYaw" link2="LShoulderDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RHip" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RHipDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RHipYaw" reason="Adjacent" />
<disable_collisions link1="LHipYaw" link2="RKnee" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RShoulder" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LHipYaw" link2="RightCamera" reason="Never" />
<disable_collisions link1="LHipYaw" link2="gaze" reason="Never" />
<disable_collisions link1="LHipYaw" link2="helmet" reason="Never" />
<disable_collisions link1="LHipYaw" link2="l_ankle" reason="Never" />
<disable_collisions link1="LHipYaw" link2="neck" reason="Never" />
<disable_collisions link1="LHipYaw" link2="r_wrist" reason="Never" />
<disable_collisions link1="LHipYaw" link2="torso" reason="Adjacent" />
<disable_collisions link1="LKnee" link2="LShoulder" reason="Never" />
<disable_collisions link1="LKnee" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LKnee" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LKnee" link2="RKnee" reason="Default" />
<disable_collisions link1="LKnee" link2="RShoulder" reason="Never" />
<disable_collisions link1="LKnee" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LKnee" link2="RightCamera" reason="Never" />
<disable_collisions link1="LKnee" link2="gaze" reason="Never" />
<disable_collisions link1="LKnee" link2="helmet" reason="Never" />
<disable_collisions link1="LKnee" link2="l_ankle" reason="Adjacent" />
<disable_collisions link1="LKnee" link2="l_sole" reason="Default" />
<disable_collisions link1="LKnee" link2="neck" reason="Never" />
<disable_collisions link1="LKnee" link2="r_wrist" reason="Never" />
<disable_collisions link1="LKnee" link2="torso" reason="Never" />
<disable_collisions link1="LShoulder" link2="LShoulderDummy" reason="Adjacent" />
<disable_collisions link1="LShoulder" link2="LeftCamera" reason="Never" />
<disable_collisions link1="LShoulder" link2="RElbowDummy" reason="Never" />
<disable_collisions link1="LShoulder" link2="RHip" reason="Never" />
<disable_collisions link1="LShoulder" link2="RHipDummy" reason="Never" />
@ -171,6 +188,9 @@
<disable_collisions link1="LShoulder" link2="RKnee" reason="Never" />
<disable_collisions link1="LShoulder" link2="RShoulder" reason="Never" />
<disable_collisions link1="LShoulder" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LShoulder" link2="RightCamera" reason="Never" />
<disable_collisions link1="LShoulder" link2="gaze" reason="Default" />
<disable_collisions link1="LShoulder" link2="helmet" reason="Never" />
<disable_collisions link1="LShoulder" link2="l_ankle" reason="Never" />
<disable_collisions link1="LShoulder" link2="l_sole" reason="Never" />
<disable_collisions link1="LShoulder" link2="l_wrist" reason="Never" />
@ -186,28 +206,42 @@
<disable_collisions link1="LShoulderDummy" link2="RKnee" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="gaze" reason="Default" />
<disable_collisions link1="LShoulderDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="l_sole" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="l_wrist" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="neck" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="r_sole" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="r_wrist" reason="Never" />
<disable_collisions link1="LShoulderDummy" link2="torso" reason="Default" />
<disable_collisions link1="LeftCamera" link2="RHip" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RHipDummy" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RHipYaw" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RKnee" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RShoulder" reason="Never" />
<disable_collisions link1="LeftCamera" link2="RightCamera" reason="Never" />
<disable_collisions link1="LeftCamera" link2="gaze" reason="Never" />
<disable_collisions link1="LeftCamera" link2="helmet" reason="Adjacent" />
<disable_collisions link1="LeftCamera" link2="l_ankle" reason="Never" />
<disable_collisions link1="LeftCamera" link2="l_sole" reason="Never" />
<disable_collisions link1="LeftCamera" link2="neck" reason="Never" />
<disable_collisions link1="LeftCamera" link2="r_ankle" reason="Never" />
<disable_collisions link1="LeftCamera" link2="r_sole" reason="Never" />
<disable_collisions link1="LeftCamera" link2="torso" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="RShoulderDummy" reason="Adjacent" />
<disable_collisions link1="RElbowDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="l_sole" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="l_wrist" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="neck" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="RElbowDummy" link2="r_wrist" reason="Adjacent" />
<disable_collisions link1="RHip" link2="RHipDummy" reason="Adjacent" />
<disable_collisions link1="RHip" link2="RHipYaw" reason="Adjacent" />
<disable_collisions link1="RHip" link2="RKnee" reason="Never" />
<disable_collisions link1="RHip" link2="RShoulder" reason="Never" />
<disable_collisions link1="RHip" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="RHip" link2="RightCamera" reason="Never" />
<disable_collisions link1="RHip" link2="gaze" reason="Never" />
<disable_collisions link1="RHip" link2="helmet" reason="Never" />
<disable_collisions link1="RHip" link2="l_ankle" reason="Never" />
<disable_collisions link1="RHip" link2="neck" reason="Never" />
<disable_collisions link1="RHip" link2="r_ankle" reason="Never" />
@ -215,22 +249,32 @@
<disable_collisions link1="RHipDummy" link2="RHipYaw" reason="Default" />
<disable_collisions link1="RHipDummy" link2="RKnee" reason="Adjacent" />
<disable_collisions link1="RHipDummy" link2="RShoulder" reason="Never" />
<disable_collisions link1="RHipDummy" link2="RightCamera" reason="Never" />
<disable_collisions link1="RHipDummy" link2="gaze" reason="Never" />
<disable_collisions link1="RHipDummy" link2="helmet" reason="Never" />
<disable_collisions link1="RHipDummy" link2="l_ankle" reason="Never" />
<disable_collisions link1="RHipDummy" link2="neck" reason="Never" />
<disable_collisions link1="RHipDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RKnee" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RShoulder" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RShoulderDummy" reason="Never" />
<disable_collisions link1="RHipYaw" link2="RightCamera" reason="Never" />
<disable_collisions link1="RHipYaw" link2="gaze" reason="Never" />
<disable_collisions link1="RHipYaw" link2="helmet" reason="Never" />
<disable_collisions link1="RHipYaw" link2="l_ankle" reason="Never" />
<disable_collisions link1="RHipYaw" link2="neck" reason="Never" />
<disable_collisions link1="RHipYaw" link2="r_ankle" reason="Never" />
<disable_collisions link1="RHipYaw" link2="torso" reason="Adjacent" />
<disable_collisions link1="RKnee" link2="RShoulder" reason="Never" />
<disable_collisions link1="RKnee" link2="RightCamera" reason="Never" />
<disable_collisions link1="RKnee" link2="gaze" reason="Never" />
<disable_collisions link1="RKnee" link2="helmet" reason="Never" />
<disable_collisions link1="RKnee" link2="l_wrist" reason="Never" />
<disable_collisions link1="RKnee" link2="neck" reason="Never" />
<disable_collisions link1="RKnee" link2="r_ankle" reason="Adjacent" />
<disable_collisions link1="RKnee" link2="r_sole" reason="Default" />
<disable_collisions link1="RKnee" link2="torso" reason="Never" />
<disable_collisions link1="RShoulder" link2="RShoulderDummy" reason="Adjacent" />
<disable_collisions link1="RShoulder" link2="RightCamera" reason="Never" />
<disable_collisions link1="RShoulder" link2="helmet" reason="Never" />
<disable_collisions link1="RShoulder" link2="l_ankle" reason="Never" />
<disable_collisions link1="RShoulder" link2="l_sole" reason="Never" />
<disable_collisions link1="RShoulder" link2="l_wrist" reason="Never" />
@ -244,25 +288,36 @@
<disable_collisions link1="RShoulderDummy" link2="l_wrist" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="neck" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="r_ankle" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="r_sole" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="r_wrist" reason="Never" />
<disable_collisions link1="RShoulderDummy" link2="torso" reason="Default" />
<disable_collisions link1="RightCamera" link2="gaze" reason="Never" />
<disable_collisions link1="RightCamera" link2="helmet" reason="Adjacent" />
<disable_collisions link1="RightCamera" link2="l_ankle" reason="Never" />
<disable_collisions link1="RightCamera" link2="l_sole" reason="Never" />
<disable_collisions link1="RightCamera" link2="neck" reason="Never" />
<disable_collisions link1="RightCamera" link2="r_ankle" reason="Never" />
<disable_collisions link1="RightCamera" link2="r_sole" reason="Never" />
<disable_collisions link1="RightCamera" link2="torso" reason="Never" />
<disable_collisions link1="gaze" link2="helmet" reason="Adjacent" />
<disable_collisions link1="gaze" link2="l_ankle" reason="Never" />
<disable_collisions link1="gaze" link2="l_sole" reason="Never" />
<disable_collisions link1="gaze" link2="neck" reason="Adjacent" />
<disable_collisions link1="gaze" link2="r_ankle" reason="Never" />
<disable_collisions link1="gaze" link2="r_sole" reason="Never" />
<disable_collisions link1="gaze" link2="torso" reason="Default" />
<disable_collisions link1="helmet" link2="l_ankle" reason="Never" />
<disable_collisions link1="helmet" link2="l_sole" reason="Never" />
<disable_collisions link1="helmet" link2="neck" reason="Never" />
<disable_collisions link1="helmet" link2="r_ankle" reason="Never" />
<disable_collisions link1="helmet" link2="r_sole" reason="Never" />
<disable_collisions link1="helmet" link2="torso" reason="Never" />
<disable_collisions link1="l_ankle" link2="l_sole" reason="Adjacent" />
<disable_collisions link1="l_ankle" link2="neck" reason="Never" />
<disable_collisions link1="l_ankle" link2="r_wrist" reason="Never" />
<disable_collisions link1="l_ankle" link2="torso" reason="Never" />
<disable_collisions link1="l_sole" link2="neck" reason="Never" />
<disable_collisions link1="l_sole" link2="r_wrist" reason="Never" />
<disable_collisions link1="l_sole" link2="torso" reason="Never" />
<disable_collisions link1="l_wrist" link2="neck" reason="Never" />
<disable_collisions link1="l_wrist" link2="r_ankle" reason="Never" />
<disable_collisions link1="l_wrist" link2="r_sole" reason="Never" />
<disable_collisions link1="l_wrist" link2="r_wrist" reason="Default" />
<disable_collisions link1="neck" link2="r_ankle" reason="Never" />
<disable_collisions link1="neck" link2="r_sole" reason="Never" />
<disable_collisions link1="neck" link2="r_wrist" reason="Never" />

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,11 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<joint name="head-helmet" type="fixed">
<parent link="gaze"/>
<child link="helmet"/>
<origin xyz="0 0 0.0975" rpy="0 0 0"/>
</joint>
<link name="helmet">
<xacro:visuals_collisions_helmet/>
</link>
</robot>

View File

@ -0,0 +1,68 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- XACRO MACROS FOR VISUALS AND COLLISIONS -->
<xacro:macro name="visuals_collisions_left_camera" params="">
<xacro:if value="${helmet_cameras_viz}">
<visual>
<origin xyz="0 0 0" rpy="${PI_2} 0 ${PI_2}"/>
<geometry>
<mesh filename="package://nao_dcm_description/meshes/camera.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${PI_2} 0 ${PI_2}"/>
<geometry>
<mesh filename="package://nao_dcm_description/meshes/camera.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
<material name="LightGrey"/>
</collision>
</xacro:if>
</xacro:macro>
<xacro:macro name="visuals_collisions_right_camera" params="">
<xacro:if value="${helmet_cameras_viz}">
<visual>
<origin xyz="0 0 0" rpy="${PI_2} 0 ${PI_2}"/>
<geometry>
<mesh filename="package://nao_dcm_description/meshes/camera.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${PI_2} 0 ${PI_2}"/>
<geometry>
<mesh filename="package://nao_dcm_description/meshes/camera.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
<material name="LightGrey"/>
</collision>
</xacro:if>
</xacro:macro>
<!-- HELMET CAMERAS JOINTS -->
<joint name="helmet-left-camera" type="fixed">
<parent link="helmet"/>
<child link="LeftCamera"/>
<origin xyz="0 ${0.10785/2} ${0.12496-0.0975}" rpy="0 0 0"/>
</joint>
<link name="LeftCamera">
<xacro:visuals_collisions_left_camera/>
<inertial> <!-- sample values for my cameras -->
<mass value="0.07" />
<origin xyz="0 0 0"/>
<inertia ixx="1e-9" ixy="0" ixz="0" iyy="1e-9" iyz="0" izz="1e-9" />
</inertial>
</link>
<joint name="helmet-right-camera" type="fixed">
<parent link="helmet"/>
<child link="RightCamera"/>
<origin xyz="0 -${0.10785/2} ${0.12496-0.0975}" rpy="0 0 0"/>
</joint>
<link name="RightCamera">
<xacro:visuals_collisions_right_camera/>
<inertial> <!-- sample values for my cameras -->
<mass value="0.07" />
<origin xyz="0 0 0"/>
<inertia ixx="1e-9" ixy="0" ixz="0" iyy="1e-9" iyz="0" izz="1e-9" />
</inertial>
</link>
</robot>

View File

@ -7,6 +7,8 @@
<xacro:property name="scale" value="0.001" />
<xacro:property name="H25" value="false" />
<xacro:property name="nao_meshes" value="true" />
<xacro:property name="use_helmet" value="true" />
<xacro:property name="helmet_cameras_viz" value="false" />
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_visuals_collisions.xacro" />
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_gazebo.xacro" />
@ -21,4 +23,9 @@
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/sonars.xacro" />
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/cameras.xacro" />
<xacro:if value="${use_helmet}">
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/helmet.xacro" />
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/helmet_cameras.xacro" />
</xacro:if>
</robot>

View File

@ -7,6 +7,7 @@
<xacro:property name="scale" value="0.001" />
<xacro:property name="H25" value="true" />
<xacro:property name="nao_meshes" value="true" />
<xacro:property name="use_helmet" value="true" />
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_visuals_collisions.xacro" />
<xacro:include filename="$(find nao_dcm_description)/urdf/nao_dcm_gazebo.xacro" />
@ -21,4 +22,9 @@
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/sonars.xacro" />
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/cameras.xacro" />
<xacro:if value="${use_helmet}">
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/helmet.xacro" />
<xacro:include filename="$(find nao_dcm_description)/urdf/modules/helmet_cameras.xacro" />
</xacro:if>
</robot>

View File

@ -27,6 +27,23 @@
<!-- XACRO MACROS FOR VISUALS AND COLLISIONS -->
<xacro:macro name="visuals_collisions_helmet" params="">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<mesh filename="package://nao_dcm_description/meshes/helmet.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
<material name="LightGrey"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<mesh filename="package://nao_dcm_description/meshes/helmet.dae" scale="${scale} ${scale} ${scale}"/>
</geometry>
<material name="LightGrey"/>
</collision>
</xacro:macro>
<xacro:macro name="visuals_collisions_torso" params="">
<xacro:unless value="${nao_meshes}">
<visual>