diff --git a/ur_description/config/ur10/joints_limits_parameters.yaml b/ur_description/config/ur10/joints_limits_parameters.yaml
index bdaad3343..9330c7c98 100644
--- a/ur_description/config/ur10/joints_limits_parameters.yaml
+++ b/ur_description/config/ur10/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 2.0943951
+ lower: -360.0
+ upper: 360.0
+ velocity: 120.0
effort: 330.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 2.0943951
+ lower: -360.0
+ upper: 360.0
+ velocity: 120.0
effort: 330.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 150.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
diff --git a/ur_description/config/ur10e/joints_limits_parameters.yaml b/ur_description/config/ur10e/joints_limits_parameters.yaml
index 57a4dc43a..854a64410 100644
--- a/ur_description/config/ur10e/joints_limits_parameters.yaml
+++ b/ur_description/config/ur10e/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 2.0943951
+ lower: -360.0
+ upper: 360.0
+ velocity: 120.0
effort: 330.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 2.0943951
+ lower: -360.0
+ upper: 360.0
+ velocity: 120.0
effort: 330.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 150.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
diff --git a/ur_description/config/ur16e/joints_limits_parameters.yaml b/ur_description/config/ur16e/joints_limits_parameters.yaml
index 2a78995b6..cb0b4f8b4 100644
--- a/ur_description/config/ur16e/joints_limits_parameters.yaml
+++ b/ur_description/config/ur16e/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 2.0943951
+ lower: -360.0
+ upper: 360.0
+ velocity: 120.0
effort: 330.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 2.0943951
+ lower: -360.0
+ upper: 360.0
+ velocity: 120.0
effort: 330.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 150.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
diff --git a/ur_description/config/ur3/joints_limits_parameters.yaml b/ur_description/config/ur3/joints_limits_parameters.yaml
index 08c7dc4e5..7b969ca1c 100644
--- a/ur_description/config/ur3/joints_limits_parameters.yaml
+++ b/ur_description/config/ur3/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 28.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 6.28318530718
+ lower: -360.0
+ upper: 360.0
+ velocity: 360.0
effort: 12.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 6.28318530718
+ lower: -360.0
+ upper: 360.0
+ velocity: 360.0
effort: 12.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 6.28318530718
+ lower: -360.0
+ upper: 360.0
+ velocity: 360.0
effort: 12.0
diff --git a/ur_description/config/ur3e/joints_limits_parameters.yaml b/ur_description/config/ur3e/joints_limits_parameters.yaml
index 2b4564b59..c6bdac2c6 100644
--- a/ur_description/config/ur3e/joints_limits_parameters.yaml
+++ b/ur_description/config/ur3e/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 56.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 28.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 6.28318530718
+ lower: -360.0
+ upper: 360.0
+ velocity: 360.0
effort: 12.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 6.28318530718
+ lower: -360.0
+ upper: 360.0
+ velocity: 360.0
effort: 12.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 6.28318530718
+ lower: -360.0
+ upper: 360.0
+ velocity: 360.0
effort: 12.0
diff --git a/ur_description/config/ur5/joints_limits_parameters.yaml b/ur_description/config/ur5/joints_limits_parameters.yaml
index e420f5f11..b4105c7a3 100644
--- a/ur_description/config/ur5/joints_limits_parameters.yaml
+++ b/ur_description/config/ur5/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 150.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 150.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 150.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 28.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 28.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 28.0
diff --git a/ur_description/config/ur5e/joints_limits_parameters.yaml b/ur_description/config/ur5e/joints_limits_parameters.yaml
index 0f0e3f73d..335841e56 100644
--- a/ur_description/config/ur5e/joints_limits_parameters.yaml
+++ b/ur_description/config/ur5e/joints_limits_parameters.yaml
@@ -9,14 +9,14 @@
# retrieved: 2020-06-16, last modified: 2020-06-09
limits:
shoulder_pan:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 150.0
shoulder_lift:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 150.0
elbow_joint:
# we artificially limit this joint to half it's actual joint limit to avoid
@@ -29,22 +29,22 @@ limits:
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
- lower: -3.14159265359
- upper: 3.14159265359
- velocity: 3.14159265359
+ lower: -180.0
+ upper: 180.0
+ velocity: 180.0
effort: 150.0
wrist_1:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 28.0
wrist_2:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 28.0
wrist_3:
- lower: -6.28318530718
- upper: 6.28318530718
- velocity: 3.14159265359
+ lower: -360.0
+ upper: 360.0
+ velocity: 180.0
effort: 28.0
diff --git a/ur_description/urdf/ur_macro.xacro b/ur_description/urdf/ur_macro.xacro
index ca73488e9..fee5681d9 100644
--- a/ur_description/urdf/ur_macro.xacro
+++ b/ur_description/urdf/ur_macro.xacro
@@ -235,8 +235,8 @@
-
+
@@ -244,10 +244,10 @@
-
+
-
+
@@ -256,10 +256,10 @@
-
+
-
+
@@ -268,10 +268,10 @@
-
+
-
+
@@ -280,10 +280,10 @@
-
+
-
+
@@ -292,10 +292,10 @@
-
+
-
+