Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
bigprint
universal_robot
Commits
87027887
Commit
87027887
authored
Apr 05, 2019
by
Miguel Prada
Committed by
G.A. vd. Hoorn
Apr 05, 2019
Browse files
Add transmission_hw_interface to UR xacro and expose everywhere (#392)
parent
d3d8f5ba
Changes
13
Hide whitespace changes
Inline
Side-by-side
ur_description/launch/ur10_upload.launch
View file @
87027887
<?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_description)/urdf/ur10_robot.urdf.xacro'"
/>
<param
if=
"$(arg limited)"
name=
"robot_description"
command=
"$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur10_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_description)/urdf/ur10_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)"
/>
<param
if=
"$(arg limited)"
name=
"robot_description"
command=
"$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur10_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)"
/>
</launch>
ur_description/launch/ur3_upload.launch
View file @
87027887
<?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_description)/urdf/ur3_robot.urdf.xacro'"
/>
<param
if=
"$(arg limited)"
name=
"robot_description"
command=
"$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_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_description)/urdf/ur3_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)"
/>
<param
if=
"$(arg limited)"
name=
"robot_description"
command=
"$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)"
/>
</launch>
ur_description/launch/ur5_upload.launch
View file @
87027887
<?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_description)/urdf/ur5_robot.urdf.xacro'"
/>
<param
if=
"$(arg limited)"
name=
"robot_description"
command=
"$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur5_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_description)/urdf/ur5_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)"
/>
<param
if=
"$(arg limited)"
name=
"robot_description"
command=
"$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)"
/>
</launch>
ur_description/urdf/ur.transmission.xacro
View file @
87027887
<?xml version="1.0"?>
<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>
...
...
@@ -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>
...
...
@@ -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>
...
...
@@ -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>
...
...
@@ -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>
...
...
@@ -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>
...
...
ur_description/urdf/ur10.urdf.xacro
View file @
87027887
...
...
@@ -20,12 +20,13 @@
</xacro:macro>
<xacro:macro
name=
"ur10_robot"
params=
"prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
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}"
>
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
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:=hardware_interface/PositionJointInterface"
>
<!-- Inertia parameters -->
<xacro:property
name=
"base_mass"
value=
"4.0"
/>
<!-- This mass might be incorrect -->
...
...
@@ -300,7 +301,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 -->
...
...
ur_description/urdf/ur10_joint_limited_robot.urdf.xacro
View file @
87027887
...
...
@@ -2,6 +2,8 @@
<robot
xmlns:xacro=
"http://wiki.ros.org/xacro"
name=
"ur10"
>
<xacro:arg
name=
"transmission_hw_interface"
default=
"hardware_interface/PositionJointInterface"
/>
<!-- common stuff -->
<xacro:include
filename=
"$(find ur_description)/urdf/common.gazebo.xacro"
/>
...
...
@@ -10,12 +12,13 @@
<!-- arm -->
<xacro:ur10_robot
prefix=
""
joint_limited=
"true"
shoulder_pan_lower_limit=
"${-pi}"
shoulder_pan_upper_limit=
"${pi}"
shoulder_lift_lower_limit=
"${-pi}"
shoulder_lift_upper_limit=
"${pi}"
elbow_joint_lower_limit=
"${-pi}"
elbow_joint_upper_limit=
"${pi}"
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}"
shoulder_pan_lower_limit=
"${-pi}"
shoulder_pan_upper_limit=
"${pi}"
shoulder_lift_lower_limit=
"${-pi}"
shoulder_lift_upper_limit=
"${pi}"
elbow_joint_lower_limit=
"${-pi}"
elbow_joint_upper_limit=
"${pi}"
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"
/>
...
...
ur_description/urdf/ur10_robot.urdf.xacro
View file @
87027887
...
...
@@ -2,6 +2,8 @@
<robot
xmlns:xacro=
"http://wiki.ros.org/xacro"
name=
"ur10"
>
<xacro:arg
name=
"transmission_hw_interface"
default=
"hardware_interface/PositionJointInterface"
/>
<!-- common stuff -->
<xacro:include
filename=
"$(find ur_description)/urdf/common.gazebo.xacro"
/>
...
...
@@ -9,7 +11,9 @@
<xacro:include
filename=
"$(find ur_description)/urdf/ur10.urdf.xacro"
/>
<!-- arm -->
<xacro:ur10_robot
prefix=
""
joint_limited=
"false"
/>
<xacro:ur10_robot
prefix=
""
joint_limited=
"false"
transmission_hw_interface=
"$(arg transmission_hw_interface)"
/>
<link
name=
"world"
/>
...
...
ur_description/urdf/ur3.urdf.xacro
View file @
87027887
...
...
@@ -19,12 +19,13 @@
</xacro:macro>
<xacro:macro
name=
"ur3_robot"
params=
"prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
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}"
>
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
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:=hardware_interface/PositionJointInterface"
>
<!-- Inertia parameters -->
<xacro:property
name=
"base_mass"
value=
"2.0"
/>
<!-- This mass might be incorrect -->
...
...
@@ -299,7 +300,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 -->
...
...
ur_description/urdf/ur3_joint_limited_robot.urdf.xacro
View file @
87027887
...
...
@@ -2,6 +2,8 @@
<robot
xmlns:xacro=
"http://wiki.ros.org/xacro"
name=
"ur3"
>
<xacro:arg
name=
"transmission_hw_interface"
default=
"hardware_interface/PositionJointInterface"
/>
<!-- common stuff -->
<xacro:include
filename=
"$(find ur_description)/urdf/common.gazebo.xacro"
/>
...
...
@@ -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"
/>
...
...
ur_description/urdf/ur3_robot.urdf.xacro
View file @
87027887
...
...
@@ -2,6 +2,8 @@
<robot
xmlns:xacro=
"http://wiki.ros.org/xacro"
name=
"ur3"
>
<xacro:arg
name=
"transmission_hw_interface"
default=
"hardware_interface/PositionJointInterface"
/>
<!-- common stuff -->
<xacro:include
filename=
"$(find ur_description)/urdf/common.gazebo.xacro"
/>
...
...
@@ -9,7 +11,9 @@
<xacro:include
filename=
"$(find ur_description)/urdf/ur3.urdf.xacro"
/>
<!-- arm -->
<xacro:ur3_robot
prefix=
""
joint_limited=
"false"
/>
<xacro:ur3_robot
prefix=
""
joint_limited=
"false"
transmission_hw_interface=
"$(arg transmission_hw_interface)"
/>
<link
name=
"world"
/>
...
...
ur_description/urdf/ur5.urdf.xacro
View file @
87027887
...
...
@@ -15,12 +15,13 @@
</xacro:macro>
<xacro:macro
name=
"ur5_robot"
params=
"prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
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}"
>
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi}
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:=hardware_interface/PositionJointInterface"
>
<!-- Inertia parameters -->
<xacro:property
name=
"base_mass"
value=
"4.0"
/>
<!-- This mass might be incorrect -->
...
...
@@ -316,7 +317,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 -->
...
...
ur_description/urdf/ur5_joint_limited_robot.urdf.xacro
View file @
87027887
...
...
@@ -2,6 +2,8 @@
<robot
xmlns:xacro=
"http://wiki.ros.org/xacro"
name=
"ur5"
>
<xacro:arg
name=
"transmission_hw_interface"
default=
"hardware_interface/PositionJointInterface"
/>
<!-- common stuff -->
<xacro:include
filename=
"$(find ur_description)/urdf/common.gazebo.xacro"
/>
...
...
@@ -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"
/>
...
...
ur_description/urdf/ur5_robot.urdf.xacro
View file @
87027887
...
...
@@ -2,6 +2,8 @@
<robot
xmlns:xacro=
"http://wiki.ros.org/xacro"
name=
"ur5"
>
<xacro:arg
name=
"transmission_hw_interface"
default=
"hardware_interface/PositionJointInterface"
/>
<!-- common stuff -->
<xacro:include
filename=
"$(find ur_description)/urdf/common.gazebo.xacro"
/>
...
...
@@ -9,7 +11,9 @@
<xacro:include
filename=
"$(find ur_description)/urdf/ur5.urdf.xacro"
/>
<!-- arm -->
<xacro:ur5_robot
prefix=
""
joint_limited=
"false"
/>
<xacro:ur5_robot
prefix=
""
joint_limited=
"false"
transmission_hw_interface=
"$(arg transmission_hw_interface)"
/>
<link
name=
"world"
/>
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment