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

Add transmission_hw_interface to URe xacro and expose everywhere #528

Open
wants to merge 1 commit into
base: kinetic-devel
Choose a base branch
from
Open
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
7 changes: 4 additions & 3 deletions ur_e_description/launch/ur10e_upload.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur10e_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur10e_joint_limited_robot.urdf.xacro'" />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur10e_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur10e_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
</launch>
8 changes: 5 additions & 3 deletions ur_e_description/launch/ur3e_upload.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur3e_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur3e_joint_limited_robot.urdf.xacro'" />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />


<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur3e_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur3e_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
</launch>
7 changes: 4 additions & 3 deletions ur_e_description/launch/ur5e_upload.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur5e_robot.urdf.xacro'" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur5e_joint_limited_robot.urdf.xacro'" />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />

<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur5e_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_e_description)/urdf/ur5e_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
</launch>
14 changes: 7 additions & 7 deletions ur_e_description/urdf/ur.transmission.xacro
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="ur_arm_transmission" params="prefix">
<xacro:macro name="ur_arm_transmission" params="prefix hw_interface">

<transmission name="${prefix}shoulder_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}shoulder_pan_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}shoulder_pan_motor">
<mechanicalReduction>1</mechanicalReduction>
Expand All @@ -16,7 +16,7 @@
<transmission name="${prefix}shoulder_lift_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}shoulder_lift_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}shoulder_lift_motor">
<mechanicalReduction>1</mechanicalReduction>
Expand All @@ -26,7 +26,7 @@
<transmission name="${prefix}elbow_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}elbow_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}elbow_motor">
<mechanicalReduction>1</mechanicalReduction>
Expand All @@ -36,7 +36,7 @@
<transmission name="${prefix}wrist_1_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}wrist_1_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}wrist_1_motor">
<mechanicalReduction>1</mechanicalReduction>
Expand All @@ -46,7 +46,7 @@
<transmission name="${prefix}wrist_2_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}wrist_2_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}wrist_2_motor">
<mechanicalReduction>1</mechanicalReduction>
Expand All @@ -56,7 +56,7 @@
<transmission name="${prefix}wrist_3_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}wrist_3_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<hardwareInterface>${hw_interface}</hardwareInterface>
</joint>
<actuator name="${prefix}wrist_3_motor">
<mechanicalReduction>1</mechanicalReduction>
Expand Down
2 changes: 1 addition & 1 deletion ur_e_description/urdf/ur10e.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -339,7 +339,7 @@
</collision>
</link>

<xacro:ur_arm_transmission prefix="${prefix}" />
<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}"/>
<xacro:ur_arm_gazebo prefix="${prefix}" />

<!-- ROS base_link to UR 'Base' Coordinates transform -->
Expand Down
3 changes: 3 additions & 0 deletions ur_e_description/urdf/ur10e_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur10e" >

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- common stuff -->
<xacro:include filename="$(find ur_e_description)/urdf/common.gazebo.xacro" />

Expand All @@ -16,6 +18,7 @@
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>

<link name="world" />
Expand Down
6 changes: 5 additions & 1 deletion ur_e_description/urdf/ur10e_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,18 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur10e" >

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- common stuff -->
<xacro:include filename="$(find ur_e_description)/urdf/common.gazebo.xacro" />

<!-- ur10e -->
<xacro:include filename="$(find ur_e_description)/urdf/ur10e.urdf.xacro" />

<!-- arm -->
<xacro:ur10e_robot prefix="" joint_limited="false"/>
<xacro:ur10e_robot prefix="" joint_limited="false"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>

<link name="world" />

Expand Down
2 changes: 1 addition & 1 deletion ur_e_description/urdf/ur3e.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -338,7 +338,7 @@
</collision>
</link>

<xacro:ur_arm_transmission prefix="${prefix}" />
<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />
<xacro:ur_arm_gazebo prefix="${prefix}" />

<!-- ROS base_link to UR 'Base' Coordinates transform -->
Expand Down
3 changes: 3 additions & 0 deletions ur_e_description/urdf/ur3e_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur3e" >

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- common stuff -->
<xacro:include filename="$(find ur_e_description)/urdf/common.gazebo.xacro" />

Expand All @@ -16,6 +18,7 @@
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>

<link name="world" />
Expand Down
6 changes: 5 additions & 1 deletion ur_e_description/urdf/ur3e_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,18 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur3e" >

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- common stuff -->
<xacro:include filename="$(find ur_e_description)/urdf/common.gazebo.xacro" />

<!-- ur3e -->
<xacro:include filename="$(find ur_e_description)/urdf/ur3e.urdf.xacro" />

<!-- arm -->
<xacro:ur3e_robot prefix="" joint_limited="false"/>
<xacro:ur3e_robot prefix="" joint_limited="false"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>

<link name="world" />

Expand Down
2 changes: 1 addition & 1 deletion ur_e_description/urdf/ur5e.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,7 @@
</collision>
</link>

<xacro:ur_arm_transmission prefix="${prefix}" />
<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />
<xacro:ur_arm_gazebo prefix="${prefix}" />

<!-- ROS base_link to UR 'Base' Coordinates transform -->
Expand Down
3 changes: 3 additions & 0 deletions ur_e_description/urdf/ur5e_joint_limited_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur5e" >

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- common stuff -->
<xacro:include filename="$(find ur_e_description)/urdf/common.gazebo.xacro" />

Expand All @@ -16,6 +18,7 @@
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>

<link name="world" />
Expand Down
6 changes: 5 additions & 1 deletion ur_e_description/urdf/ur5e_robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,18 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="ur5e" >

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<!-- common stuff -->
<xacro:include filename="$(find ur_e_description)/urdf/common.gazebo.xacro" />

<!-- ur5e -->
<xacro:include filename="$(find ur_e_description)/urdf/ur5e.urdf.xacro" />

<!-- arm -->
<xacro:ur5e_robot prefix="" joint_limited="false"/>
<xacro:ur5e_robot prefix="" joint_limited="false"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>

<link name="world" />

Expand Down