diff --git a/ur10_moveit_config/config/joint_limits.yaml b/ur10_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index 633b7bbce..000000000
--- a/ur10_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 2.0943951023931953
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 2.0943951023931953
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
\ No newline at end of file
diff --git a/ur10_moveit_config/launch/planning_context.launch b/ur10_moveit_config/launch/planning_context.launch
index b3bd21211..92e56f397 100644
--- a/ur10_moveit_config/launch/planning_context.launch
+++ b/ur10_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+
diff --git a/ur10e_moveit_config/config/joint_limits.yaml b/ur10e_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index 633b7bbce..000000000
--- a/ur10e_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 2.0943951023931953
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 2.0943951023931953
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
\ No newline at end of file
diff --git a/ur10e_moveit_config/launch/planning_context.launch b/ur10e_moveit_config/launch/planning_context.launch
index a0121a8de..499f40dab 100644
--- a/ur10e_moveit_config/launch/planning_context.launch
+++ b/ur10e_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+
diff --git a/ur16e_moveit_config/config/joint_limits.yaml b/ur16e_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index 633b7bbce..000000000
--- a/ur16e_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 2.0943951023931953
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 2.0943951023931953
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
\ No newline at end of file
diff --git a/ur16e_moveit_config/launch/planning_context.launch b/ur16e_moveit_config/launch/planning_context.launch
index 2c61f888c..6beb426f6 100644
--- a/ur16e_moveit_config/launch/planning_context.launch
+++ b/ur16e_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+
diff --git a/ur3_moveit_config/config/joint_limits.yaml b/ur3_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index 45694aa56..000000000
--- a/ur3_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 6.283185307179586
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 6.283185307179586
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 6.283185307179586
- has_acceleration_limits: false
- max_acceleration: 0
diff --git a/ur3_moveit_config/launch/planning_context.launch b/ur3_moveit_config/launch/planning_context.launch
index 8356b2332..1f8a24eb2 100644
--- a/ur3_moveit_config/launch/planning_context.launch
+++ b/ur3_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+
diff --git a/ur3e_moveit_config/config/joint_limits.yaml b/ur3e_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index 45694aa56..000000000
--- a/ur3e_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 6.283185307179586
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 6.283185307179586
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 6.283185307179586
- has_acceleration_limits: false
- max_acceleration: 0
diff --git a/ur3e_moveit_config/launch/planning_context.launch b/ur3e_moveit_config/launch/planning_context.launch
index 49ef7dfeb..3fb484b35 100644
--- a/ur3e_moveit_config/launch/planning_context.launch
+++ b/ur3e_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+
diff --git a/ur5_moveit_config/config/joint_limits.yaml b/ur5_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index bdc914f89..000000000
--- a/ur5_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
diff --git a/ur5_moveit_config/launch/planning_context.launch b/ur5_moveit_config/launch/planning_context.launch
index a2a3ebff4..f599a8710 100644
--- a/ur5_moveit_config/launch/planning_context.launch
+++ b/ur5_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+
diff --git a/ur5e_moveit_config/config/joint_limits.yaml b/ur5e_moveit_config/config/joint_limits.yaml
deleted file mode 100644
index bdc914f89..000000000
--- a/ur5e_moveit_config/config/joint_limits.yaml
+++ /dev/null
@@ -1,34 +0,0 @@
-# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
-# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
-# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
-joint_limits:
- elbow_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_lift_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- shoulder_pan_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_1_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_2_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
- wrist_3_joint:
- has_velocity_limits: true
- max_velocity: 3.1415926535897931
- has_acceleration_limits: false
- max_acceleration: 0
diff --git a/ur5e_moveit_config/launch/planning_context.launch b/ur5e_moveit_config/launch/planning_context.launch
index 9052fd96f..e6221b79f 100644
--- a/ur5e_moveit_config/launch/planning_context.launch
+++ b/ur5e_moveit_config/launch/planning_context.launch
@@ -13,7 +13,7 @@
-
+