diff --git a/ur_rtde_driver/config/ur10_controllers.yaml b/ur_rtde_driver/config/ur10_controllers.yaml
index 42bb62d..ebbd6be 100644
--- a/ur_rtde_driver/config/ur10_controllers.yaml
+++ b/ur_rtde_driver/config/ur10_controllers.yaml
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
-pos_based_pos_traj_controller:
+scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
+
+pos_traj_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - shoulder_pan_joint
+ - shoulder_lift_joint
+ - elbow_joint
+ - wrist_1_joint
+ - wrist_2_joint
+ - wrist_3_joint
+ constraints:
+ goal_time: 0.6
+ stopped_velocity_tolerance: 0.05
+ shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
+ shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
+ elbow_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_1_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_2_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_3_joint: {trajectory: 0.2, goal: 0.1}
+ stop_trajectory_duration: 0.5
+ state_publish_rate: 500
+ action_monitor_rate: 10
diff --git a/ur_rtde_driver/config/ur10e_controllers.yaml b/ur_rtde_driver/config/ur10e_controllers.yaml
index 345f4f5..c100dfc 100644
--- a/ur_rtde_driver/config/ur10e_controllers.yaml
+++ b/ur_rtde_driver/config/ur10e_controllers.yaml
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
-pos_based_pos_traj_controller:
+scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
+
+pos_traj_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - shoulder_pan_joint
+ - shoulder_lift_joint
+ - elbow_joint
+ - wrist_1_joint
+ - wrist_2_joint
+ - wrist_3_joint
+ constraints:
+ goal_time: 0.6
+ stopped_velocity_tolerance: 0.05
+ shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
+ shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
+ elbow_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_1_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_2_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_3_joint: {trajectory: 0.2, goal: 0.1}
+ stop_trajectory_duration: 0.5
+ state_publish_rate: 500
+ action_monitor_rate: 10
diff --git a/ur_rtde_driver/config/ur3_controllers.yaml b/ur_rtde_driver/config/ur3_controllers.yaml
index 42bb62d..ebbd6be 100644
--- a/ur_rtde_driver/config/ur3_controllers.yaml
+++ b/ur_rtde_driver/config/ur3_controllers.yaml
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
-pos_based_pos_traj_controller:
+scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
+
+pos_traj_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - shoulder_pan_joint
+ - shoulder_lift_joint
+ - elbow_joint
+ - wrist_1_joint
+ - wrist_2_joint
+ - wrist_3_joint
+ constraints:
+ goal_time: 0.6
+ stopped_velocity_tolerance: 0.05
+ shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
+ shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
+ elbow_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_1_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_2_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_3_joint: {trajectory: 0.2, goal: 0.1}
+ stop_trajectory_duration: 0.5
+ state_publish_rate: 500
+ action_monitor_rate: 10
diff --git a/ur_rtde_driver/config/ur3e_controllers.yaml b/ur_rtde_driver/config/ur3e_controllers.yaml
index 345f4f5..c100dfc 100644
--- a/ur_rtde_driver/config/ur3e_controllers.yaml
+++ b/ur_rtde_driver/config/ur3e_controllers.yaml
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
-pos_based_pos_traj_controller:
+scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
+
+pos_traj_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - shoulder_pan_joint
+ - shoulder_lift_joint
+ - elbow_joint
+ - wrist_1_joint
+ - wrist_2_joint
+ - wrist_3_joint
+ constraints:
+ goal_time: 0.6
+ stopped_velocity_tolerance: 0.05
+ shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
+ shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
+ elbow_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_1_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_2_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_3_joint: {trajectory: 0.2, goal: 0.1}
+ stop_trajectory_duration: 0.5
+ state_publish_rate: 500
+ action_monitor_rate: 10
diff --git a/ur_rtde_driver/config/ur5_controllers.yaml b/ur_rtde_driver/config/ur5_controllers.yaml
index 42bb62d..ebbd6be 100644
--- a/ur_rtde_driver/config/ur5_controllers.yaml
+++ b/ur_rtde_driver/config/ur5_controllers.yaml
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
-pos_based_pos_traj_controller:
+scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
+
+pos_traj_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - shoulder_pan_joint
+ - shoulder_lift_joint
+ - elbow_joint
+ - wrist_1_joint
+ - wrist_2_joint
+ - wrist_3_joint
+ constraints:
+ goal_time: 0.6
+ stopped_velocity_tolerance: 0.05
+ shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
+ shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
+ elbow_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_1_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_2_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_3_joint: {trajectory: 0.2, goal: 0.1}
+ stop_trajectory_duration: 0.5
+ state_publish_rate: 500
+ action_monitor_rate: 10
diff --git a/ur_rtde_driver/config/ur5e_controllers.yaml b/ur_rtde_driver/config/ur5e_controllers.yaml
index 345f4f5..c100dfc 100644
--- a/ur_rtde_driver/config/ur5e_controllers.yaml
+++ b/ur_rtde_driver/config/ur5e_controllers.yaml
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
-pos_based_pos_traj_controller:
+scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
+
+pos_traj_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - shoulder_pan_joint
+ - shoulder_lift_joint
+ - elbow_joint
+ - wrist_1_joint
+ - wrist_2_joint
+ - wrist_3_joint
+ constraints:
+ goal_time: 0.6
+ stopped_velocity_tolerance: 0.05
+ shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
+ shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
+ elbow_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_1_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_2_joint: {trajectory: 0.2, goal: 0.1}
+ wrist_3_joint: {trajectory: 0.2, goal: 0.1}
+ stop_trajectory_duration: 0.5
+ state_publish_rate: 500
+ action_monitor_rate: 10
diff --git a/ur_rtde_driver/launch/ur10_bringup.launch b/ur_rtde_driver/launch/ur10_bringup.launch
index b60464c..ef2d990 100644
--- a/ur_rtde_driver/launch/ur10_bringup.launch
+++ b/ur_rtde_driver/launch/ur10_bringup.launch
@@ -10,8 +10,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur10e_bringup.launch b/ur_rtde_driver/launch/ur10e_bringup.launch
index dadd662..317b44c 100644
--- a/ur_rtde_driver/launch/ur10e_bringup.launch
+++ b/ur_rtde_driver/launch/ur10e_bringup.launch
@@ -11,8 +11,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur3_bringup.launch b/ur_rtde_driver/launch/ur3_bringup.launch
index ea0ea84..3ecd9eb 100644
--- a/ur_rtde_driver/launch/ur3_bringup.launch
+++ b/ur_rtde_driver/launch/ur3_bringup.launch
@@ -10,8 +10,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur3e_bringup.launch b/ur_rtde_driver/launch/ur3e_bringup.launch
index aef3632..02ff890 100644
--- a/ur_rtde_driver/launch/ur3e_bringup.launch
+++ b/ur_rtde_driver/launch/ur3e_bringup.launch
@@ -11,8 +11,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur5_bringup.launch b/ur_rtde_driver/launch/ur5_bringup.launch
index a28b4ee..60a2363 100644
--- a/ur_rtde_driver/launch/ur5_bringup.launch
+++ b/ur_rtde_driver/launch/ur5_bringup.launch
@@ -10,8 +10,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur5e_bringup.launch b/ur_rtde_driver/launch/ur5e_bringup.launch
index 783f916..ad46d76 100644
--- a/ur_rtde_driver/launch/ur5e_bringup.launch
+++ b/ur_rtde_driver/launch/ur5e_bringup.launch
@@ -11,8 +11,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur_common.launch b/ur_rtde_driver/launch/ur_common.launch
index d591941..646d378 100644
--- a/ur_rtde_driver/launch/ur_common.launch
+++ b/ur_rtde_driver/launch/ur_common.launch
@@ -8,8 +8,8 @@
-
-
+
+
diff --git a/ur_rtde_driver/launch/ur_control.launch b/ur_rtde_driver/launch/ur_control.launch
index 7c98798..e2a6d40 100644
--- a/ur_rtde_driver/launch/ur_control.launch
+++ b/ur_rtde_driver/launch/ur_control.launch
@@ -11,8 +11,8 @@
-
-
+
+