diff --git a/README.md b/README.md index e8a2b8d..c4d5601 100644 --- a/README.md +++ b/README.md @@ -21,6 +21,7 @@ The most relevant files are: - `urdf/ur_macro.xacro` - macro file with UR-manipulator description. This file is usually included into external projects to visualize and configure UR manipulators properly. An example how to use this macro is in `urdf/ur.urdf.xacro` file. - `urdf/ur.ros2_control.xacro` - definition of manipulator's joints and interfaces for `ros2_control` framework. + ## Testing description of a manipulator To visualize the robot install this repository to you workspace and execute the following: @@ -62,6 +63,7 @@ Arguments that have to be passed to the main `ur.urdf.xacro` file are: The launchfile `launch/view_ur.launch.py` abstracts these four parameters to one `ur_type` argument which will basically replace the `urXX` part of the paths as shown in the picture above. +How to use multiple UR - robots with this package is documented in a [separate document](doc/multiarm.md) ## Creating your own description including this description In real-world applications you will most probably have a more complex description consisting of more objects than just the robot. It is recommended to create a separate ROS package containing this diff --git a/doc/multiarm.md b/doc/multiarm.md new file mode 100644 index 0000000..0d02237 --- /dev/null +++ b/doc/multiarm.md @@ -0,0 +1,269 @@ +# Multiarm support + +We support creating and handling multiple robot arms with this package. Adapting your `xacro` definition is fairly straight forward. Just create a second ur instance and name it differently and set a different `tf_prefix`. + + +## Example + +Lets assume you want to control two UR16e which are left - `ur_left` and right - `ur_right`. Both arms are connected to the same network as your PC. + +A possible example config which lists all the parameters that need to be different for for both arms could look like this. + +| Parameter | left | right | Explanation | +| --- | --- | --- | ----- | +| robot_ip | 192.168.1.10 | 192.168.1.11 | IP address of the robot arm| +| tf_prefix | ur_left | ur_right | Prefix which is added to each joint etc. of the arm| +| reverse_port | 50001 | 50006 | The port on your local PC which the `ur_cap` on the robot will connect to| +| script_sender_port | 50002 | 50007 | See [ur_driver.h](https://github.com/UniversalRobots/Universal_Robots_Client_Library/blob/master/include/ur_client_library/ur/ur_driver.h) | +| trajectory_port | 50004 | 50009 | See [ur_driver.h](https://github.com/UniversalRobots/Universal_Robots_Client_Library/blob/master/include/ur_client_library/ur/ur_driver.h) | +| script_command_port | 50005 | 50010 | See [ur_driver.h](https://github.com/UniversalRobots/Universal_Robots_Client_Library/blob/master/include/ur_client_library/ur/ur_driver.h) | +| kinematics_param_file | kinematics_params_left.yaml | kinematics_params_right.yaml | Kinematics calibration data. See [calibration manual](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/tree/main/ur_calibration) | +| non_blocking_read | true | true | Has to be `true` otherwise the readout will hang and the connection of the other arm will drop | + +__The major__ differences to a single robot config are that you need to specify different ports for the reverse connections, you __need__ to set `non_blocking_read = true` and you __need__ to set a different `tf_prefix`. +You might want to increase the `keep_alive_count` as with more robot arms your PC will have more troubles to keep up with the exact 500Hz update rate required by the `ur_cap` running on the robot arm. +Ofcourse you can change all other parameters seperately for both arms if necessary. + +For environments using the ros2control mock interface setting only the `tf_prefix` is enough. + +__Hint__: Choose your `tf_prefix` wisely at the beginning. It will be a lot of work changing it afterwards. + + + +### Xacro example file + +An example xacro file could then look like this: + +Please note that we explicitly leave out the arguments part from the `ur.urdf.xacro` example file as this does not contribute to the example. Only the common parameters are declared as properties. From my experience the most easy to use approach is to write a yaml file with the parameters for both arms and load these parameters when initiating the `xacro:ur_robot` macro. + + +``` + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +``` + +# Some tips and tricks + + +## Configuration and xarco setup + +From my experience you often want to have different end effectors and tools for both (or even more arms). Therefore it makes sense to put each robot arm (+ everything that is connected to it) into its own `xacro macro` and initiate that macro in your main file. For configurating the arm (something you will play around a lot at the beginning) I decided to create a yaml file which contains the configuration for both arms, load that configuration in the main xacro file and pass the subsection of each arm to the corresponding xacro file. + +The yaml file looks in my case like this: + +Note: I do not use the tool communication. Remember to select different device names if you want to use it! + +robot_arms.yaml +``` +ur_arms: + ur_left: + use_fake_hardware: "true" + prefix: "ur_left/" + robot_ip: "192.168.1.102" + script_filename: "resources/ros_control.urscript" + output_recipe_filename: "resources/rtde_output_recipe.txt" + input_recipe_filename: "resources/rtde_input_recipe.txt" + headless_mode : true + reverse_port: 50001 + script_sender_port: 50002 + servoj_gain: 2000 + servoj_lookahead_time: 0.03 + non_blocking_read: true + use_tool_communication: false + trajectory_port: 50004 + script_command_port: 50005 + reverse_ip: "192.168.1.1" + kinematics_file: "config/ur_16e_left_kinematics.yaml" + tool: + tool_tcp_port: 54321 + tool_device_name: "/tmp/ttyUR" + tool_parity: 0 + tool_baud_rate: 115200 + tool_stop_bits: 1 + tool_rx_idle_chars: 1.5 + tool_tx_idle_chars: 3.5 + tool_voltage: 24.0 + + + + ur_right: + use_fake_hardware: "true" + prefix: "ur_right/" + robot_ip: "192.168.1.101" + script_filename: "resources/ros_control.urscript" + output_recipe_filename: "resources/rtde_output_recipe.txt" + input_recipe_filename: "resources/rtde_input_recipe.txt" + headless_mode : true + reverse_port: 50006 + script_sender_port: 50007 + servoj_gain: 2000 + servoj_lookahead_time: 0.03 + non_blocking_read: true + use_tool_communication: false + trajectory_port: 50009 + script_command_port: 50010 + reverse_ip: "192.168.1.1" + kinematics_file: "config/ur_16e_right_kinematics.yaml" + tool: + tool_tcp_port: 54321 + tool_device_name: "/tmp/ttyUR" + tool_parity: 0 + tool_baud_rate: 115200 + tool_stop_bits: 1 + tool_rx_idle_chars: 1.5 + tool_tx_idle_chars: 3.5 + tool_voltage: 24.0 + + + +``` + + +In the main xacro I then do: + + +``` + + + + + + + + + + + + + +``` + + +## Futher tips + +1. Start with one arm after the other. (At least have the second arm set to `use_fake_hardware=true`) +2. As said above: Choose the `tf_prefix` wisely. +3. I had to use `headless_mode=true` otherwise I had issues starting the program on both arms +4. Consider setting the `reverse_ip` I had issues with the automatic detection of the right interface. +5. Remember that you can run `xacro` from the command line. This can help debugging issues quite a lot. Just run: + > xacro my_main.urdf.xacro > test.xml + + And open it in an editor of your choice + +6. When using with moveit you need to adapt / create the `joint_limits.yaml` by hand. Otherwise you won't get the right limits. \ No newline at end of file