Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ur16e #270

Merged
merged 3 commits into from Sep 24, 2020
Merged

Ur16e #270

Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
13 changes: 11 additions & 2 deletions README.md
Expand Up @@ -3,7 +3,7 @@
# Universal_Robots_ROS_Driver
Universal Robots have become a dominant supplier of lightweight, robotic manipulators for industry, as well as for scientific research and education. The Robot Operating System (ROS) has developed from a community-centered movement to a mature framework and quasi standard, providing a rich set of powerful tools for robot engineers and researchers, working in many different domains.

<center><img src="ur_robot_driver/doc/initial_setup_images/e-Series.png" alt="Universal Robot e-Series family" style="width: 45%;"/></center>
<center><img src="ur_robot_driver/doc/initial_setup_images/e-Series.jpg" alt="Universal Robot e-Series family" style="width: 80%;"/></center>

With the release of UR’s new e-Series, the demand for a ROS driver that supports the new manipulators and the newest ROS releases and paradigms like ROS-control has increased further. The goal of this driver is to provide a stable and sustainable interface between UR robots and ROS that strongly benefit all parties.

Expand Down Expand Up @@ -91,6 +91,15 @@ To make sure that robot control isn't affected by system latencies, it is highly
a real-time kernel with the system. See the [real-time setup guide](ur_robot_driver/doc/real_time.md)
on information how to set this up.

## Preliminary UR16e support
This driver supports all UR variants including the UR16e. However, upstream support for the UR16e is
not finished, yet. When using the UR16e there is currently no support for gazebo or MoveIt!.

See [#97](https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/pull/97) for details on
using the latest upstream develop branch of
[ros_industrial/universal_robot](https://github.com/ros-industrial/universal_robot) which includes
gazebo support for the ur16e, but no working MoveIt! support at the time of writing.

## Building

```bash
Expand Down Expand Up @@ -166,7 +175,7 @@ To actually start the robot driver use one of the existing launch files

$ roslaunch ur_robot_driver <robot_type>_bringup.launch robot_ip:=192.168.56.101

where **<robot_type>** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e*. Note that in this example we
where **<robot_type>** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e, ur16e*. Note that in this example we
load the calibration parameters for the robot "ur10_example".

If you calibrated your robot before, pass that calibration to the launch file:
Expand Down
136 changes: 136 additions & 0 deletions ur_robot_driver/config/ur16e_controllers.yaml
@@ -0,0 +1,136 @@
# Settings for ros_control control loop
hardware_control_loop:
loop_hz: &loop_hz 500

# Settings for ros_control hardware interface
ur_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_joint_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: 20

pos_joint_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: 20

scaled_vel_joint_traj_controller:
type: velocity_controllers/ScaledJointTrajectoryController
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
gains:
#!!These values have not been optimized!!
shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
# Use a feedforward term to reduce the size of PID gains
velocity_ff:
shoulder_pan_joint: 1.0
shoulder_lift_joint: 1.0
elbow_joint: 1.0
wrist_1_joint: 1.0
wrist_2_joint: 1.0
wrist_3_joint: 1.0
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 20

vel_joint_traj_controller:
type: velocity_controllers/JointTrajectoryController
joints: *robot_joints
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
gains:
#!!These values have not been optimized!!
shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
# Use a feedforward term to reduce the size of PID gains
velocity_ff:
shoulder_pan_joint: 1.0
shoulder_lift_joint: 1.0
elbow_joint: 1.0
wrist_1_joint: 1.0
wrist_2_joint: 1.0
wrist_3_joint: 1.0
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 20

# Pass an array of joint velocities directly to the joints
joint_group_vel_controller:
type: velocity_controllers/JointGroupVelocityController
joints: *robot_joints

robot_status_controller:
type: industrial_robot_status_controller/IndustrialRobotStatusController
handle_name: industrial_robot_status_handle
publish_rate: 10
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file not shown.
27 changes: 27 additions & 0 deletions ur_robot_driver/launch/ur16e_bringup.launch
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<launch>

<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
<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."/>
<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."/>
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
<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."/>
<arg name="stopped_controllers" default="pos_joint_traj_controller joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur16e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
<arg name="robot_description_file" default="$(find ur_e_description)/launch/ur16e_upload.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur16e_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/>
<arg name="tool_voltage" default="0" doc="Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_stop_bits" default="1" doc="Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_rx_idle_chars" default="1.5" doc="Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>

<include file="$(find ur_robot_driver)/launch/ur_common.launch" pass_all_args="true"/>
</launch>