Skip to content

Commit

Permalink
Merge pull request #198 from ipa-fxm/separate_sensors_actors
Browse files Browse the repository at this point in the history
Separate sensors actors
  • Loading branch information
fmessmer authored Jan 11, 2017
2 parents 26b7690 + 55674dc commit 2c70667
Show file tree
Hide file tree
Showing 12 changed files with 139 additions and 811 deletions.
43 changes: 11 additions & 32 deletions cob_description/urdf/cob4_head/head.transmission.xacro
Original file line number Diff line number Diff line change
@@ -1,40 +1,19 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="head_transmission" params="name">
<xacro:include filename="$(find cob_description)/urdf/common.xacro" />

<transmission name="${name}_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_1_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_1_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<xacro:macro name="head_transmission" params="name dof1 dof2 dof3">

<transmission name="${name}_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_2_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_2_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="${name}_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_3_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_3_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<xacro:if value="${dof1}">
<xacro:default_transmission jname="${name}_1"/>
</xacro:if>
<xacro:if value="${dof2}">
<xacro:default_transmission jname="${name}_2"/>
</xacro:if>
<xacro:if value="${dof3}">
<xacro:default_transmission jname="${name}_3"/>
</xacro:if>

</xacro:macro>

Expand Down
78 changes: 50 additions & 28 deletions cob_description/urdf/cob4_head/head.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,8 @@

<xacro:include filename="$(find cob_description)/urdf/cob4_head/head.gazebo.xacro" />
<xacro:include filename="$(find cob_description)/urdf/cob4_head/head.transmission.xacro" />
<xacro:include filename="$(find cob_description)/urdf/sensors/usb_cam.urdf.xacro" />

<xacro:macro name="head" params="parent name *origin">
<xacro:macro name="head" params="parent name *origin dof1:=false dof2:=false dof3:=false">

<joint name="${name}_base_joint" type="fixed">
<insert_block name="origin" />
Expand All @@ -29,13 +28,22 @@
</collision>
</link>

<joint name="${name}_1_joint" type="revolute">
<origin xyz="0 0 0.0305" rpy="0 0 0"/>
<parent link="${name}_base_link"/>
<child link="${name}_1_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="1.4"/>
</joint>
<xacro:unless value="${dof1}">
<joint name="${name}_1_joint" type="fixed">
<origin xyz="0 0 0.0305" rpy="0 0 0"/>
<parent link="${name}_base_link"/>
<child link="${name}_1_link" />
</joint>
</xacro:unless>
<xacro:if value="${dof1}">
<joint name="${name}_1_joint" type="revolute">
<origin xyz="0 0 0.0305" rpy="0 0 0"/>
<parent link="${name}_base_link"/>
<child link="${name}_1_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="1.4"/>
</joint>
</xacro:if>

<link name="${name}_1_link">
<xacro:default_inertial/>
Expand All @@ -53,13 +61,22 @@
</collision>
</link>

<joint name="${name}_2_joint" type="revolute">
<origin xyz="0 -0.07725 0.00439" rpy="0.349 0 0" />
<parent link="${name}_1_link"/>
<child link="${name}_2_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="1.4"/>
</joint>
<xacro:unless value="${dof2}">
<joint name="${name}_2_joint" type="fixed">
<origin xyz="0 -0.07725 0.00439" rpy="0.349 0 0" />
<parent link="${name}_1_link"/>
<child link="${name}_2_link" />
</joint>
</xacro:unless>
<xacro:if value="${dof2}">
<joint name="${name}_2_joint" type="revolute">
<origin xyz="0 -0.07725 0.00439" rpy="0.349 0 0" />
<parent link="${name}_1_link"/>
<child link="${name}_2_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="1.4"/>
</joint>
</xacro:if>

<link name="${name}_2_link">
<xacro:default_inertial/>
Expand All @@ -77,13 +94,22 @@
</collision>
</link>

<joint name="${name}_3_joint" type="revolute">
<origin xyz="0 0.09849 0.04476" rpy="-0.349 0 0" />
<parent link="${name}_2_link"/>
<child link="${name}_3_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="1.4"/>
</joint>
<xacro:unless value="${dof3}">
<joint name="${name}_3_joint" type="fixed">
<origin xyz="0 0.09849 0.04476" rpy="-0.349 0 0" />
<parent link="${name}_2_link"/>
<child link="${name}_3_link" />
</joint>
</xacro:unless>
<xacro:if value="${dof3}">
<joint name="${name}_3_joint" type="revolute">
<origin xyz="0 0.09849 0.04476" rpy="-0.349 0 0" />
<parent link="${name}_2_link"/>
<child link="${name}_3_link" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="1.4"/>
</joint>
</xacro:if>

<link name="${name}_3_link">
<xacro:default_inertial/>
Expand Down Expand Up @@ -111,13 +137,9 @@

<link name="${name}_center_link"/>

<xacro:usb_cam name="${name}_cam" parent="${name}_3_link" ros_topic="${name}_cam">
<origin xyz="${head_cam_x} ${head_cam_y} ${head_cam_z}" rpy="${head_cam_roll} ${head_cam_pitch} ${head_cam_yaw}" />
</xacro:usb_cam>

<!-- extensions -->
<xacro:head_gazebo name="${name}" />
<xacro:head_transmission name="${name}" />
<xacro:head_transmission name="${name}" dof1="${dof1}" dof2="${dof2}" dof3="${dof3}" />

</xacro:macro>

Expand Down
118 changes: 0 additions & 118 deletions cob_description/urdf/cob4_head/head_static.urdf.xacro

This file was deleted.

13 changes: 3 additions & 10 deletions cob_description/urdf/cob4_sensorring/sensorring.transmission.xacro
Original file line number Diff line number Diff line change
@@ -1,18 +1,11 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find cob_description)/urdf/common.xacro" />

<xacro:macro name="sensorring_transmission" params="name">

<transmission name="${name}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_joint">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<xacro:default_transmission jname="${name}"/>

</xacro:macro>

Expand Down
72 changes: 0 additions & 72 deletions cob_description/urdf/cob4_sensorring/sensorring_3dcs.urdf.xacro

This file was deleted.

Loading

0 comments on commit 2c70667

Please sign in to comment.