diff --git a/.github/workflows/iron-binary-main.yml b/.github/workflows/iron-binary-main.yml index 43c8df5ec..d089e1dc6 100644 --- a/.github/workflows/iron-binary-main.yml +++ b/.github/workflows/iron-binary-main.yml @@ -6,7 +6,6 @@ on: pull_request: branches: - iron - - main # as long as rolling and iron should be compatible push: branches: - iron diff --git a/.github/workflows/iron-binary-testing.yml b/.github/workflows/iron-binary-testing.yml index a59f1daa3..ba8918604 100644 --- a/.github/workflows/iron-binary-testing.yml +++ b/.github/workflows/iron-binary-testing.yml @@ -6,7 +6,6 @@ on: pull_request: branches: - iron - - main # as long as rolling and iron should be compatible push: branches: - iron diff --git a/.github/workflows/iron-semi-binary-main.yml b/.github/workflows/iron-semi-binary-main.yml index 60d0e3412..01340fd50 100644 --- a/.github/workflows/iron-semi-binary-main.yml +++ b/.github/workflows/iron-semi-binary-main.yml @@ -6,7 +6,6 @@ on: pull_request: branches: - iron - - main # as long as rolling and iron should be compatible push: branches: - iron diff --git a/.github/workflows/iron-semi-binary-testing.yml b/.github/workflows/iron-semi-binary-testing.yml index d9a172075..809cea567 100644 --- a/.github/workflows/iron-semi-binary-testing.yml +++ b/.github/workflows/iron-semi-binary-testing.yml @@ -6,7 +6,6 @@ on: pull_request: branches: - iron - - main # as long as rolling and iron should be compatible push: branches: - iron diff --git a/README.md b/README.md index ed7d45d21..d24d01bca 100644 --- a/README.md +++ b/README.md @@ -85,12 +85,19 @@ users an overview of the current released state. - `ur_moveit_config` - example MoveIt configuration for UR robots. - `ur_robot_driver` - driver / hardware interface for communication with UR robots. +## System Requirements + +Please see the [requirements for the Universal_Robots_Client_Library](https://github.com/UniversalRobots/Universal_Robots_Client_Library#requirements), as this driver is build on top of Universal_Robots_Client_Library. + ## Getting Started For getting started, you'll basically need three steps: -1. **Install the driver** (see below). You can either install this driver from binary packages or build it from source. We recommend a -binary package installation unless you want to join development and submit changes. +1. **Install the driver** + ```bash + sudo apt-get install ros-rolling-ur + ``` + See the [installation instructions](https://docs.ros.org/en/ros2_packages/rolling/api/ur_robot_driver/installation/installation.html) for more details and source-build instructions. 2. **Start & Setup the robot**. Once you've installed the driver, [setup the robot](https://docs.ros.org/en/ros2_packages/rolling/api/ur_robot_driver/installation/robot_setup.html) @@ -110,65 +117,14 @@ binary package installation unless you want to join development and submit chang documentation](https://docs.ros.org/en/ros2_packages/rolling/api/ur_robot_driver/usage.html) for details. -4. Unless started in [headless mode](https://docs.ros.org/en/ros2_packages/rolling/api/ur_robot_driver/ROS_INTERFACE.html#headless-mode): Run the external_control program by **pressing `play` on the teach pendant**. - -### Install from binary packages -1. [Install ROS2](https://docs.ros.org/en/rolling/Installation/Ubuntu-Install-Debians.html). This - branch supports only ROS2 Rolling. For other ROS2 versions, please see the respective - branches. -2. Install the driver using - ``` - sudo apt-get install ros-${ROS_DISTRO}-ur + ```bash + # Replace ur5e with one of ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20, ur30 + # Replace the IP address with the IP address of your actual robot / URSim + ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.56.101 ``` -### Build from source -Before building from source please make sure that you actually need to do that. Building from source -might require some special treatment, especially when it comes to dependency management. -Dependencies might change from time to time. Upstream packages (such as the library) might change -their features / API which require changes in this repo. Therefore, this repo's source builds might -require upstream repositories to be present in a certain version as otherwise builds might fail. -Starting from scratch following exactly the steps below should always work, but simply pulling and -building might fail occasionally. - -1. [Install ROS2](https://docs.ros.org/en/rolling/Installation/Ubuntu-Install-Debians.html). This - branch supports only ROS2 Rolling. For other ROS2 versions, please see the respective - branches. - - Once installed, please make sure to actually [source ROS2](https://docs.ros.org/en/rolling/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html#source-the-setup-files) before proceeding. - -3. Make sure that `colcon`, its extensions and `vcs` are installed: - ``` - sudo apt install python3-colcon-common-extensions python3-vcstool - ``` - -4. Create a new ROS2 workspace: - ``` - export COLCON_WS=~/workspace/ros_ur_driver - mkdir -p $COLCON_WS/src - ``` - -5. Clone relevant packages, install dependencies, compile, and source the workspace by using: - ``` - cd $COLCON_WS - git clone https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git src/Universal_Robots_ROS2_Driver - vcs import src --skip-existing --input src/Universal_Robots_ROS2_Driver/Universal_Robots_ROS2_Driver-not-released.${ROS_DISTRO}.repos - rosdep update - rosdep install --ignore-src --from-paths src -y - colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release - source install/setup.bash - ``` - -6. When consecutive pulls lead to build errors it is possible that you'll have to build an upstream - package from source, as well. See the [detailed build status](ci_status.md). When the binary builds are red, but - the semi-binary builds are green, you need to build the upstream dependencies from source. The - easiest way to achieve this, is using the repos file: +4. Unless started in [headless mode](https://docs.ros.org/en/ros2_packages/rolling/api/ur_robot_driver/ROS_INTERFACE.html#headless-mode): Run the external_control program by **pressing `play` on the teach pendant**. - ``` - cd $COLCON_WS - vcs import src --skip-existing --input src/Universal_Robots_ROS2_Driver/Universal_Robots_ROS2_Driver.${ROS_DISTRO}.repos - rosdep update - rosdep install --ignore-src --from-paths src -y - ``` ## MoveIt! support diff --git a/ur/CHANGELOG.rst b/ur/CHANGELOG.rst index f46209fb1..1c1a15d5c 100644 --- a/ur/CHANGELOG.rst +++ b/ur/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ur ^^^^^^^^^^^^^^^^^^^^^^^^ +2.4.2 (2023-11-23) +------------------ + 2.4.1 (2023-09-21) ------------------ diff --git a/ur/package.xml b/ur/package.xml index a1abed791..2561105d6 100644 --- a/ur/package.xml +++ b/ur/package.xml @@ -2,7 +2,7 @@ ur - 2.4.1 + 2.4.2 Metapackage for universal robots Felix Exner Robert Wilbrandt diff --git a/ur_calibration/CHANGELOG.rst b/ur_calibration/CHANGELOG.rst index 38a0a25e0..c0d4b2dcb 100644 --- a/ur_calibration/CHANGELOG.rst +++ b/ur_calibration/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ur_calibration ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.4.2 (2023-11-23) +------------------ + 2.4.1 (2023-09-21) ------------------ diff --git a/ur_calibration/package.xml b/ur_calibration/package.xml index b85f4f58e..6baaa18d8 100644 --- a/ur_calibration/package.xml +++ b/ur_calibration/package.xml @@ -1,7 +1,7 @@ ur_calibration - 2.4.1 + 2.4.2 Package for extracting the factory calibration from a UR robot and change it such that it can be used by ur_description to gain a correct URDF Felix Exner diff --git a/ur_controllers/CHANGELOG.rst b/ur_controllers/CHANGELOG.rst index 0f5bb74a5..19d1440d0 100644 --- a/ur_controllers/CHANGELOG.rst +++ b/ur_controllers/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package ur_controllers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.4.2 (2023-11-23) +------------------ +* Update read_state_from_hardware +* Renamed normalize_joint_error to joints_angle_wraparound +* Remove noisy controller log message +* Contributors: Felix Exner, Robert Wilbrandt + 2.4.1 (2023-09-21) ------------------ * Update sjtc to newest upstream API (`#810 `_) diff --git a/ur_controllers/package.xml b/ur_controllers/package.xml index e8a492e3f..b92732d7f 100644 --- a/ur_controllers/package.xml +++ b/ur_controllers/package.xml @@ -2,7 +2,7 @@ ur_controllers - 2.4.1 + 2.4.2 Provides controllers that use the speed scaling interface of Universal Robots. Denis Stogl diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index e9e78d336..93ffa0a94 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -90,7 +90,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const auto compute_error_for_joint = [&](JointTrajectoryPoint& error, size_t index, const JointTrajectoryPoint& current, const JointTrajectoryPoint& desired) { // error defined as the difference between current and desired - if (normalize_joint_error_[index]) { + if (joints_angle_wraparound_[index]) { // if desired, the shortest_angular_distance is calculated, i.e., the error is // normalized between -pi ur_dashboard_msgs - 2.4.1 + 2.4.2 Messages around the UR Dashboard server. Felix Exner diff --git a/ur_moveit_config/CHANGELOG.rst b/ur_moveit_config/CHANGELOG.rst index 9d7791ce8..afc30cff1 100644 --- a/ur_moveit_config/CHANGELOG.rst +++ b/ur_moveit_config/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package ur_moveit_config ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.4.2 (2023-11-23) +------------------ +* moveit_servo package executable name has changed (`#854 `_) +* Contributors: Felix Durchdewald + 2.4.1 (2023-09-21) ------------------ * Added support for UR20 (`#797 `_) diff --git a/ur_moveit_config/launch/ur_moveit.launch.py b/ur_moveit_config/launch/ur_moveit.launch.py index af8b0d8c5..cd7436054 100644 --- a/ur_moveit_config/launch/ur_moveit.launch.py +++ b/ur_moveit_config/launch/ur_moveit.launch.py @@ -263,7 +263,7 @@ def generate_launch_description(): DeclareLaunchArgument( "ur_type", description="Type/series of used UR robot.", - choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"], + choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"], ) ) declared_arguments.append( diff --git a/ur_moveit_config/package.xml b/ur_moveit_config/package.xml index 477e82a58..d0ae92982 100644 --- a/ur_moveit_config/package.xml +++ b/ur_moveit_config/package.xml @@ -2,7 +2,7 @@ ur_moveit_config - 2.4.1 + 2.4.2 An example package with MoveIt2 configurations for UR robots. diff --git a/ur_robot_driver/CHANGELOG.rst b/ur_robot_driver/CHANGELOG.rst index 21b5ca06d..2ae004d0e 100644 --- a/ur_robot_driver/CHANGELOG.rst +++ b/ur_robot_driver/CHANGELOG.rst @@ -1,3 +1,14 @@ +2.4.2 (2023-11-23) +------------------ +* [README] Move installation instructions to subpage (`#870 `_) +* Add backward_ros to driver (`#872 `_) +* Simplify tests (`#849 `_) +* Port configuration (`#835 `_) + Added possibility to change the reverse_port, script_sender_port and trajectory_port +* [README] Update link to MoveIt! documentation +* Do not start urscipt_interface when using mock hardware +* Contributors: Felix Durchdewald, Felix Exner, RobertWilbrandt + 2.4.1 (2023-09-21) ------------------ * Added a test that sjtc correctly aborts on violation of constraints (`#810 `_) diff --git a/ur_robot_driver/CMakeLists.txt b/ur_robot_driver/CMakeLists.txt index c2eed8a8e..a45dd3e61 100644 --- a/ur_robot_driver/CMakeLists.txt +++ b/ur_robot_driver/CMakeLists.txt @@ -167,7 +167,7 @@ install(PROGRAMS scripts/start_ursim.sh DESTINATION lib/${PROJECT_NAME} ) -install(DIRECTORY config launch +install(DIRECTORY config launch urdf DESTINATION share/${PROJECT_NAME} ) diff --git a/ur_robot_driver/config/ur30_update_rate.yaml b/ur_robot_driver/config/ur30_update_rate.yaml new file mode 100644 index 000000000..66ef3d736 --- /dev/null +++ b/ur_robot_driver/config/ur30_update_rate.yaml @@ -0,0 +1,3 @@ +controller_manager: + ros__parameters: + update_rate: 500 # Hz diff --git a/ur_robot_driver/doc/installation/installation.rst b/ur_robot_driver/doc/installation/installation.rst new file mode 100644 index 000000000..eed955798 --- /dev/null +++ b/ur_robot_driver/doc/installation/installation.rst @@ -0,0 +1,71 @@ +Installation of the ur_robot_driver +=================================== + +You can either install this driver from binary packages as shown above or build it from source. We +recommend a binary package installation unless you want to join development and submit changes. + +Install from binary packages +---------------------------- + +1. `Install ROS2 `_. This + branch supports only ROS2 Rolling. For other ROS2 versions, please see the respective branches. +2. Install the driver using + + .. code-block:: bash + + sudo apt-get install ros-${ROS_DISTRO}-ur + + +Build from source +----------------- + +Before building from source please make sure that you actually need to do that. Building from source +might require some special treatment, especially when it comes to dependency management. +Dependencies might change from time to time. Upstream packages (such as the library) might change +their features / API which require changes in this repo. Therefore, this repo's source builds might +require upstream repositories to be present in a certain version as otherwise builds might fail. +Starting from scratch following exactly the steps below should always work, but simply pulling and +building might fail occasionally. + +1. `Install ROS2 `_. This + branch supports only ROS2 Rolling. For other ROS2 versions, please see the respective branches. + + Once installed, please make sure to actually `source ROS2 `_ before proceeding. + +3. Make sure that ``colcon``, its extensions and ``vcs`` are installed: + + .. code-block:: bash + + sudo apt install python3-colcon-common-extensions python3-vcstool + + +4. Create a new ROS2 workspace: + + .. code-block:: bash + + export COLCON_WS=~/workspace/ros_ur_driver + mkdir -p $COLCON_WS/src + +5. Clone relevant packages, install dependencies, compile, and source the workspace by using: + + .. code-block:: bash + + cd $COLCON_WS + git clone https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver.git src/Universal_Robots_ROS2_Driver + vcs import src --skip-existing --input src/Universal_Robots_ROS2_Driver/Universal_Robots_ROS2_Driver-not-released.${ROS_DISTRO}.repos + rosdep update + rosdep install --ignore-src --from-paths src -y + colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release + source install/setup.bash + +6. When consecutive pulls lead to build errors it is possible that you'll have to build an upstream + package from source, as well. See the [detailed build status](ci_status.md). When the binary builds are red, but + the semi-binary builds are green, you need to build the upstream dependencies from source. The + easiest way to achieve this, is using the repos file: + + .. code-block:: bash + + cd $COLCON_WS + vcs import src --skip-existing --input src/Universal_Robots_ROS2_Driver/Universal_Robots_ROS2_Driver.${ROS_DISTRO}.repos + rosdep update + rosdep install --ignore-src --from-paths src -y diff --git a/ur_robot_driver/doc/installation/toc.rst b/ur_robot_driver/doc/installation/toc.rst index 926be1acd..2ee60aae8 100644 --- a/ur_robot_driver/doc/installation/toc.rst +++ b/ur_robot_driver/doc/installation/toc.rst @@ -9,6 +9,7 @@ This chapter explains how to install the ``ur_robot_driver`` :maxdepth: 4 :caption: Contents: + installation real_time robot_setup install_urcap_cb3 diff --git a/ur_robot_driver/doc/usage.rst b/ur_robot_driver/doc/usage.rst index 039ab305a..1a3acd329 100644 --- a/ur_robot_driver/doc/usage.rst +++ b/ur_robot_driver/doc/usage.rst @@ -20,7 +20,7 @@ The arguments for launch files can be listed using ``ros2 launch ur_robot_driver The most relevant arguments are the following: -* ``ur_type`` (\ *mandatory* ) - a type of used UR robot (\ *ur3*\ , *ur3e*\ , *ur5*\ , *ur5e*\ , *ur10*\ , *ur10e*\ , or *ur16e*\ , *ur20*\ ). +* ``ur_type`` (\ *mandatory* ) - a type of used UR robot (\ *ur3*\ , *ur3e*\ , *ur5*\ , *ur5e*\ , *ur10*\ , *ur10e*\ , or *ur16e*\ , *ur20*\ , *ur30*\ ). * ``robot_ip`` (\ *mandatory* ) - IP address by which the root can be reached. * ``use_mock_hardware`` (default: *false* ) - use simple hardware emulator from ros2_control. Useful for testing launch files, descriptions, etc. See explanation below. @@ -106,7 +106,7 @@ For details on the Docker image, please see the more detailed guide :ref:`here < Example Commands for Testing the Driver --------------------------------------- -Allowed UR - Type strings: ``ur3``\ , ``ur3e``\ , ``ur5``\ , ``ur5e``\ , ``ur10``\ , ``ur10e``\ , ``ur16e``\ , ``ur20``. +Allowed UR - Type strings: ``ur3``\ , ``ur3e``\ , ``ur5``\ , ``ur5e``\ , ``ur10``\ , ``ur10e``\ , ``ur16e``\ , ``ur20``, ``ur30``. 1. Start hardware, simulator or mockup ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/ur_robot_driver/launch/ur30.launch.py b/ur_robot_driver/launch/ur30.launch.py new file mode 100644 index 000000000..2ac76eb65 --- /dev/null +++ b/ur_robot_driver/launch/ur30.launch.py @@ -0,0 +1,102 @@ +# Copyright (c) 2021 PickNik, Inc. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the {copyright_holder} nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +# +# Author: Denis Stogl + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir + + +def generate_launch_description(): + # Declare arguments + declared_arguments = [] + declared_arguments.append( + DeclareLaunchArgument( + "robot_ip", + description="IP address by which the robot can be reached.", + ) + ) + declared_arguments.append( + DeclareLaunchArgument( + "use_mock_hardware", + default_value="false", + description="Start robot with mock hardware mirroring command to its states.", + ) + ) + declared_arguments.append( + DeclareLaunchArgument( + "mock_sensor_commands", + default_value="false", + description="Enable mock command interfaces for sensors used for simple simulations. \ + Used only if 'use_mock_hardware' parameter is true.", + ) + ) + declared_arguments.append( + DeclareLaunchArgument( + "initial_joint_controller", + default_value="scaled_joint_trajectory_controller", + description="Initially loaded robot controller.", + choices=[ + "scaled_joint_trajectory_controller", + "joint_trajectory_controller", + "forward_velocity_controller", + "forward_position_controller", + ], + ) + ) + declared_arguments.append( + DeclareLaunchArgument( + "activate_joint_controller", + default_value="true", + description="Activate loaded joint controller.", + ) + ) + + # Initialize Arguments + robot_ip = LaunchConfiguration("robot_ip") + use_mock_hardware = LaunchConfiguration("use_mock_hardware") + mock_sensor_commands = LaunchConfiguration("mock_sensor_commands") + initial_joint_controller = LaunchConfiguration("initial_joint_controller") + activate_joint_controller = LaunchConfiguration("activate_joint_controller") + + base_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource([ThisLaunchFileDir(), "/ur_control.launch.py"]), + launch_arguments={ + "ur_type": "ur30", + "robot_ip": robot_ip, + "use_mock_hardware": use_mock_hardware, + "mock_sensor_commands": mock_sensor_commands, + "initial_joint_controller": initial_joint_controller, + "activate_joint_controller": activate_joint_controller, + }.items(), + ) + + return LaunchDescription(declared_arguments + [base_launch]) diff --git a/ur_robot_driver/launch/ur_control.launch.py b/ur_robot_driver/launch/ur_control.launch.py index 3ac85dbbf..18ad4afa1 100644 --- a/ur_robot_driver/launch/ur_control.launch.py +++ b/ur_robot_driver/launch/ur_control.launch.py @@ -101,7 +101,7 @@ def launch_setup(context, *args, **kwargs): [ PathJoinSubstitution([FindExecutable(name="xacro")]), " ", - PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]), + PathJoinSubstitution([FindPackageShare("ur_robot_driver"), "urdf", description_file]), " ", "robot_ip:=", robot_ip, @@ -386,7 +386,7 @@ def generate_launch_description(): DeclareLaunchArgument( "ur_type", description="Type/series of used UR robot.", - choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"], + choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"], ) ) declared_arguments.append( diff --git a/ur_robot_driver/package.xml b/ur_robot_driver/package.xml index f31ea4b62..c4d06d1d1 100644 --- a/ur_robot_driver/package.xml +++ b/ur_robot_driver/package.xml @@ -2,7 +2,7 @@ ur_robot_driver - 2.4.1 + 2.4.2 The new driver for Universal Robots UR3, UR5 and UR10 robots with CB3 controllers and the e-series. Denis Stogl diff --git a/ur_robot_driver/test/test_common.py b/ur_robot_driver/test/test_common.py index b8d7c08b1..5b6033cea 100644 --- a/ur_robot_driver/test/test_common.py +++ b/ur_robot_driver/test/test_common.py @@ -253,7 +253,7 @@ def _declare_launch_arguments(): "ur_type", default_value="ur5e", description="Type/series of used UR robot.", - choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"], + choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"], ) ) diff --git a/ur_robot_driver/urdf/ur.ros2_control.xacro b/ur_robot_driver/urdf/ur.ros2_control.xacro new file mode 100644 index 000000000..074f94221 --- /dev/null +++ b/ur_robot_driver/urdf/ur.ros2_control.xacro @@ -0,0 +1,230 @@ + + + + + + + + + + + + + + + + + + + + mock_components/GenericSystem + ${mock_sensor_commands} + 0.0 + + + ur_robot_driver/URPositionHardwareInterface + ${robot_ip} + ${script_filename} + ${output_recipe_filename} + ${input_recipe_filename} + ${headless_mode} + ${reverse_port} + ${script_sender_port} + ${reverse_ip} + ${script_command_port} + ${trajectory_port} + ${tf_prefix} + ${non_blocking_read} + 2000 + 0.03 + ${use_tool_communication} + ${kinematics_hash} + ${tool_voltage} + ${tool_parity} + ${tool_baud_rate} + ${tool_stop_bits} + ${tool_rx_idle_chars} + ${tool_tx_idle_chars} + ${tool_device_name} + ${tool_tcp_port} + ${keep_alive_count} + + + + + + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur_robot_driver/urdf/ur.urdf.xacro b/ur_robot_driver/urdf/ur.urdf.xacro new file mode 100644 index 000000000..d72a573e4 --- /dev/null +++ b/ur_robot_driver/urdf/ur.urdf.xacro @@ -0,0 +1,106 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +