Skip to content

Commit

Permalink
Merge pull request UniversalRobots#6 from shadow-robot/fix_ur10e_hard…
Browse files Browse the repository at this point in the history
…ware_interface

Add a parameter to choose the hardware interface for the e-series
  • Loading branch information
fmauch authored May 28, 2020
2 parents ae91d44 + a8e8b59 commit 3ebf807
Show file tree
Hide file tree
Showing 10 changed files with 29 additions and 11 deletions.
3 changes: 3 additions & 0 deletions ur_e_description/launch/ur10e_upload.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur10e_default.yaml"/>

<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)
kinematics_config:=$(arg kinematics_config)"
/>
<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)
kinematics_config:=$(arg kinematics_config)"
/>
</launch>
3 changes: 3 additions & 0 deletions ur_e_description/launch/ur3e_upload.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur3e_default.yaml"/>

<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)
kinematics_config:=$(arg kinematics_config)"
/>
<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)
kinematics_config:=$(arg kinematics_config)"
/>
</launch>
3 changes: 3 additions & 0 deletions ur_e_description/launch/ur5e_upload.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur5e_default.yaml"/>

<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)
kinematics_config:=$(arg kinematics_config)"
/>
<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)
kinematics_config:=$(arg kinematics_config)"
/>
</launch>
16 changes: 8 additions & 8 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">
<robot xmlns:xacro="http://wiki.ros.org/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 @@ -344,7 +344,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 @@ -17,6 +19,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)"
kinematics_file="${load_yaml('$(arg kinematics_config)')}"
/>

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 @@ -342,7 +342,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 @@ -17,6 +19,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)"
kinematics_file="${load_yaml('$(arg kinematics_config)')}"
/>

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 @@ -342,7 +342,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 @@ -17,6 +19,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)"
kinematics_file="${load_yaml('$(arg kinematics_config)')}"
/>

Expand Down

0 comments on commit 3ebf807

Please sign in to comment.