Converted nao_meshes to collada for Gazebo compatibility..
This commit is contained in:
parent
b92842f3ce
commit
ff5a60073b
@ -19,6 +19,10 @@
|
||||
<color rgba="1 1 0 1"/>
|
||||
</material>
|
||||
|
||||
<material name="LightGrey">
|
||||
<color rgba="0.8 0.8 0.8 1.0"/>
|
||||
</material>
|
||||
|
||||
<!-- END OF MATERIALS -->
|
||||
|
||||
<!-- XACRO MACROS FOR VISUALS AND COLLISIONS -->
|
||||
@ -41,16 +45,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/Torso.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/Torso.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_meshes/meshes/V40/collision/Torso.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/Torso.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -60,16 +64,16 @@
|
||||
<xacro:macro name="visuals_collisions_head_yaw" params="">
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/HeadYaw.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/HeadYaw.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_meshes/meshes/V40/collision/HeadYaw.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/HeadYaw.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -94,16 +98,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/HeadPitch.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/HeadPitch.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_meshes/meshes/V40/collision/HeadPitch.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/HeadPitch.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -113,16 +117,16 @@
|
||||
<xacro:macro name="visuals_collisions_shoulder_pitch" params="side">
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}ShoulderPitch.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}ShoulderPitch.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_meshes/meshes/V40/collision/${side}ShoulderPitch.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}ShoulderPitch.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -147,16 +151,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}ShoulderRoll.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}ShoulderRoll.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_meshes/meshes/V40/collision/${side}ShoulderRoll.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}ShoulderRoll.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -181,16 +185,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}ElbowRoll.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}ElbowRoll.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_meshes/meshes/V40/collision/${side}ElbowRoll.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}ElbowRoll.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -215,16 +219,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/WristYaw.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/WristYaw.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_meshes/meshes/V40/collision/WristYaw.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/WristYaw.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -234,16 +238,16 @@
|
||||
<xacro:macro name="visuals_collisions_hip_yaw_pitch" params="side reflect">
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}HipYawPitch.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}HipYawPitch.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_meshes/meshes/V40/collision/${side}HipYawPitch.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}HipYawPitch.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -253,16 +257,16 @@
|
||||
<xacro:macro name="visuals_collisions_hip_roll" params="side">
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}HipRoll.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}HipRoll.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_meshes/meshes/V40/collision/${side}HipRoll.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}HipRoll.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -287,16 +291,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}HipPitch.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}HipPitch.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_meshes/meshes/V40/collision/${side}HipPitch.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}HipPitch.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -321,16 +325,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}KneePitch.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}KneePitch.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_meshes/meshes/V40/collision/${side}KneePitch.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}KneePitch.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -355,16 +359,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}AnklePitch.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}AnklePitch.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_meshes/meshes/V40/collision/${side}AnklePitch.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}AnklePitch.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
@ -389,16 +393,16 @@
|
||||
</xacro:unless>
|
||||
<xacro:if value="${nao_meshes}">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0"/>
|
||||
<origin xyz="0 0 0" rpy="-${PI_2} -0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}AnkleRoll.obj" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/visual/${side}AnkleRoll.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_meshes/meshes/V40/collision/${side}AnkleRoll.ply" scale="${scale} ${scale} ${scale}"/>
|
||||
<mesh filename="package://nao_meshes/meshes/V40/collision/${side}AnkleRoll.dae" scale="${scale} ${scale} ${scale}"/>
|
||||
</geometry>
|
||||
<material name="LightGrey"/>
|
||||
</collision>
|
||||
|
Loading…
x
Reference in New Issue
Block a user