Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[cob4-5] new torso and sensorring configurations #192

Merged
merged 1 commit into from
Aug 4, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find cob_description)/urdf/cob4_sensorring/sensorring.gazebo.xacro" />
<xacro:include filename="$(find cob_description)/urdf/cob4_sensorring/sensorring.transmission.xacro" />
<xacro:include filename="$(find cob_description)/urdf/sensors/sick_3dcs.urdf.xacro" />
<xacro:include filename="$(find cob_description)/urdf/sensors/kinect.urdf.xacro" />

<xacro:macro name="sensorring" params="parent name *origin">

<joint name="${name}_base_joint" type="fixed">
<insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_base_link" />
</joint>

<link name="${name}_base_link">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<joint name="${name}_joint" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${name}_base_link"/>
<child link="${name}_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="6.28"/>
</joint>

<link name="${name}_link">
<xacro:default_inertial/>
<!--
<xacro:cylinder_inertial radius="0.250" length="0.1" mass="1.0">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
-->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<!-- camera -->
<xacro:sick_3dcs name="${name}_cam3d_front" ros_topic="${name}_cam3d_front" parent="${name}_link">
<origin xyz="${sensorring_cam3d_front_x} ${sensorring_cam3d_front_y} ${sensorring_cam3d_front_z}" rpy="${sensorring_cam3d_front_roll} ${sensorring_cam3d_front_pitch} ${sensorring_cam3d_front_yaw}" />
</xacro:sick_3dcs>

<xacro:cob_kinect_v0 name="${name}_cam3d_back" ros_topic="${name}_cam3d_back" parent="${name}_link">
<origin xyz="${sensorring_cam3d_back_x} ${sensorring_cam3d_back_y} ${sensorring_cam3d_back_z}" rpy="${sensorring_cam3d_back_roll} ${sensorring_cam3d_back_pitch} ${sensorring_cam3d_back_yaw}" />
</xacro:cob_kinect_v0>

<!-- extensions -->
<xacro:sensorring_gazebo name="${name}" />
<xacro:sensorring_transmission name="${name}" />

</xacro:macro>

</robot>
163 changes: 163 additions & 0 deletions cob_description/urdf/cob4_torso/torso_static_realsense.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,163 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find cob_description)/urdf/cob4_torso/torso.gazebo.xacro" />
<xacro:include filename="$(find cob_description)/urdf/cob4_torso/torso.transmission.xacro" />
<xacro:include filename="$(find cob_description)/urdf/sensors/realsense.urdf.xacro" />
<xacro:include filename="$(find cob_description)/urdf/sensors/kinect.urdf.xacro" />

<xacro:macro name="torso" params="parent name *origin">

<joint name="${name}_base_joint" type="fixed">
<insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_base_link" />
</joint>

<link name="${name}_base_link">
<xacro:default_inertial/>
<!--
<xacro:cylinder_inertial radius="0.300" length="0.046" mass="5.0">
<origin xyz="0.03 0.08 0.01" rpy="0 0 0" />
</xacro:cylinder_inertial>
-->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<joint name="${name}_1_joint" type="fixed">
<origin xyz="0 0 0.04642" rpy="0 0 0"/>
<parent link="${name}_base_link"/>
<child link="${name}_1_link" />
</joint>

<link name="${name}_1_link">
<xacro:default_inertial/>
<!--
<xacro:hollow_spherical_cap_inertial r="0.295" h="0.075" t="0.010" mass="6">
<origin xyz="0 0 ${0.075/2}" rpy="0 0 0"/>
</xacro:hollow_spherical_cap_inertial>
-->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<joint name="${name}_2_joint" type="fixed">
<origin xyz="0 0.14734 0.07547" rpy="0.5236 0 0" />
<parent link="${name}_1_link"/>
<child link="${name}_2_link" />
</joint>

<link name="${name}_2_link">
<xacro:default_inertial/>
<!--
<xacro:spherical_cap_inertial r="0.295" h="0.075" mass="19.5">
<origin xyz="0.034 0.102 0.092" rpy="0.5236 0 0"/>
</xacro:spherical_cap_inertial>
-->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<joint name="${name}_3_joint" type="fixed">
<origin xyz="0 -0.09228 0.13477" rpy="-0.5236 0 0" />
<parent link="${name}_2_link"/>
<child link="${name}_3_link" />
</joint>

<link name="${name}_3_link">
<xacro:default_inertial/>
<!--
<xacro:cylinder_inertial radius="0.250" length="0.610" mass="23.8">
<origin xyz="-0.028 0.005 0.233" rpy="0 0 0" />
</xacro:cylinder_inertial>
-->
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://cob_description/meshes/cob4_torso/torso_link.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://cob_description/meshes/cob4_torso/torso_link_collision.stl"/>
</geometry>
</collision>
</link>

<joint name="${name}_center_joint" type="fixed">
<origin xyz="0.0 0.0 0.18566" rpy="0 0 0" />
<parent link="${name}_3_link"/>
<child link="${name}_center_link" />
</joint>

<link name="${name}_center_link">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>


<!-- left camera -->
<xacro:cob_kinect_v0 name="${name}_cam3d_left" ros_topic="torso_cam3d_left" parent="${name}_3_link">
<origin xyz="${torso_cam3d_left_x} ${torso_cam3d_left_y} ${torso_cam3d_left_z}" rpy="${torso_cam3d_left_roll} ${torso_cam3d_left_pitch} ${torso_cam3d_left_yaw}" />
</xacro:cob_kinect_v0>

<!-- right camera -->
<xacro:cob_kinect_v0 name="${name}_cam3d_right" ros_topic="torso_cam3d_right" parent="${name}_3_link">
<origin xyz="${torso_cam3d_right_x} ${torso_cam3d_right_y} ${torso_cam3d_right_z}" rpy="${torso_cam3d_right_roll} ${torso_cam3d_right_pitch} ${torso_cam3d_right_yaw}" />
</xacro:cob_kinect_v0>

<!-- down camera -->
<xacro:realsense name="${name}_cam3d_down" ros_topic="torso_cam3d_down" parent="${name}_3_link">
<origin xyz="${torso_cam3d_down_x} ${torso_cam3d_down_y} ${torso_cam3d_down_z}" rpy="${torso_cam3d_down_roll} ${torso_cam3d_down_pitch} ${torso_cam3d_down_yaw}" />
</xacro:realsense>

<!-- extensions -->
<xacro:torso_gazebo name="torso" />
<xacro:torso_transmission name="torso" />

</xacro:macro>

</robot>