From f880ca91ba8efd57d24fbb3ada7318a06bea654c Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 29 Jan 2020 11:05:17 +0100 Subject: [PATCH] Added ur16 support --- ur_robot_driver/config/ur16e_controllers.yaml | 62 +++++++++++++++++++ ur_robot_driver/launch/ur16e_bringup.launch | 48 ++++++++++++++ 2 files changed, 110 insertions(+) create mode 100644 ur_robot_driver/config/ur16e_controllers.yaml create mode 100644 ur_robot_driver/launch/ur16e_bringup.launch diff --git a/ur_robot_driver/config/ur16e_controllers.yaml b/ur_robot_driver/config/ur16e_controllers.yaml new file mode 100644 index 000000000..a1665d5cf --- /dev/null +++ b/ur_robot_driver/config/ur16e_controllers.yaml @@ -0,0 +1,62 @@ +# Settings for ros_control control loop +hardware_control_loop: + loop_hz: &loop_hz 500 + +# Settings for ros_control hardware interface +hardware_interface: + joints: &robot_joints + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + +# Publish all joint states ---------------------------------- +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: *loop_hz + +# Publish wrench ---------------------------------- +force_torque_sensor_controller: + type: force_torque_sensor_controller/ForceTorqueSensorController + publish_rate: *loop_hz + +# Publish speed_scaling factor +speed_scaling_state_controller: + type: ur_controllers/SpeedScalingStateController + publish_rate: *loop_hz + +# Joint Trajectory Controller - position based ------------------------------- +# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller +scaled_pos_traj_controller: + type: position_controllers/ScaledJointTrajectoryController + joints: *robot_joints + 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: *loop_hz + action_monitor_rate: 10 + +pos_traj_controller: + type: position_controllers/JointTrajectoryController + joints: *robot_joints + 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: *loop_hz + action_monitor_rate: 10 diff --git a/ur_robot_driver/launch/ur16e_bringup.launch b/ur_robot_driver/launch/ur16e_bringup.launch new file mode 100644 index 000000000..3d5949bd9 --- /dev/null +++ b/ur_robot_driver/launch/ur16e_bringup.launch @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +