Skip to content

Commit 42754ac

Browse files
author
Felix Exner
committed
updated ur16e controllers to changes on master branch
1 parent 4dfaee1 commit 42754ac

File tree

2 files changed

+79
-5
lines changed

2 files changed

+79
-5
lines changed

ur_robot_driver/config/ur16e_controllers.yaml

Lines changed: 77 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 500
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint
@@ -29,7 +29,7 @@ speed_scaling_state_controller:
2929

3030
# Joint Trajectory Controller - position based -------------------------------
3131
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
32-
scaled_pos_traj_controller:
32+
scaled_pos_joint_traj_controller:
3333
type: position_controllers/ScaledJointTrajectoryController
3434
joints: *robot_joints
3535
constraints:
@@ -45,7 +45,7 @@ scaled_pos_traj_controller:
4545
state_publish_rate: *loop_hz
4646
action_monitor_rate: 10
4747

48-
pos_traj_controller:
48+
pos_joint_traj_controller:
4949
type: position_controllers/JointTrajectoryController
5050
joints: *robot_joints
5151
constraints:
@@ -60,3 +60,77 @@ pos_traj_controller:
6060
stop_trajectory_duration: 0.5
6161
state_publish_rate: *loop_hz
6262
action_monitor_rate: 10
63+
64+
scaled_vel_joint_traj_controller:
65+
type: velocity_controllers/ScaledJointTrajectoryController
66+
joints: *robot_joints
67+
constraints:
68+
goal_time: 0.6
69+
stopped_velocity_tolerance: 0.05
70+
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
71+
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
72+
elbow_joint: {trajectory: 0.1, goal: 0.1}
73+
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
74+
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
75+
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
76+
gains:
77+
#!!These values have not been optimized!!
78+
shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
79+
shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
80+
elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
81+
wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
82+
wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
83+
wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
84+
# Use a feedforward term to reduce the size of PID gains
85+
velocity_ff:
86+
shoulder_pan_joint: 1.0
87+
shoulder_lift_joint: 1.0
88+
elbow_joint: 1.0
89+
wrist_1_joint: 1.0
90+
wrist_2_joint: 1.0
91+
wrist_3_joint: 1.0
92+
stop_trajectory_duration: 0.5
93+
state_publish_rate: *loop_hz
94+
action_monitor_rate: 20
95+
96+
vel_joint_traj_controller:
97+
type: velocity_controllers/JointTrajectoryController
98+
joints: *robot_joints
99+
constraints:
100+
goal_time: 0.6
101+
stopped_velocity_tolerance: 0.05
102+
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
103+
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
104+
elbow_joint: {trajectory: 0.1, goal: 0.1}
105+
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
106+
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
107+
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
108+
gains:
109+
#!!These values have not been optimized!!
110+
shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
111+
shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
112+
elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
113+
wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
114+
wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
115+
wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
116+
# Use a feedforward term to reduce the size of PID gains
117+
velocity_ff:
118+
shoulder_pan_joint: 1.0
119+
shoulder_lift_joint: 1.0
120+
elbow_joint: 1.0
121+
wrist_1_joint: 1.0
122+
wrist_2_joint: 1.0
123+
wrist_3_joint: 1.0
124+
stop_trajectory_duration: 0.5
125+
state_publish_rate: *loop_hz
126+
action_monitor_rate: 20
127+
128+
# Pass an array of joint velocities directly to the joints
129+
joint_group_vel_controller:
130+
type: velocity_controllers/JointGroupVelocityController
131+
joints: *robot_joints
132+
133+
robot_status_controller:
134+
type: industrial_robot_status_controller/IndustrialRobotStatusController
135+
handle_name: industrial_robot_status_handle
136+
publish_rate: 10

ur_robot_driver/launch/ur16e_bringup.launch

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
77
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
88
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
9-
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
10-
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
9+
<arg name="controllers" default="joint_state_controller scaled_pos_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
10+
<arg name="stopped_controllers" default="pos_joint_traj_controller" doc="Controllers that are initally loaded, but not started."/>
1111
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur16e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
1212
<arg name="robot_description_file" default="$(find ur_description)/launch/load_ur16e.launch" doc="Robot description launch file."/>
1313
<arg name="kinematics_config" default="$(find ur_description)/config/ur16e/default_kinematics.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>

0 commit comments

Comments
 (0)