Skip to content

Humble #11

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

Merged
merged 17 commits into from
Mar 19, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ repos:
- id: check-merge-conflict
- id: check-symlinks
- id: check-yaml
args: ['--unsafe']
- id: end-of-file-fixer
- id: mixed-line-ending
- id: trailing-whitespace
Expand Down
6 changes: 3 additions & 3 deletions my_robot_cell/doc/assemble_urdf.rst
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ The workcell macro is defined in the following manner:
.. literalinclude:: ../my_robot_cell_description/urdf/my_robot_cell_macro.xacro
:language: xml
:linenos:
:caption: my_robot_cell_description/urdf/my_robot_cell_macro.urdf.xacro
:caption: my_robot_cell_description/urdf/my_robot_cell_macro.xacro

This macro provides an example of what a custom workcell could resemble. Your workspace will likely
vary from this one. Please feel free to modify this portion of the URDF to match your own setup. In
Expand All @@ -72,7 +72,7 @@ macro. In this example, we chose to create a link named **robot_mount**.
:start-at: <link name="robot_mount"/>
:end-at: </joint>
:linenos:
:caption: my_robot_cell_description/urdf/my_robot_cell.urdf.xacro
:caption: my_robot_cell_description/urdf/my_robot_cell.xacro

After that we are finally able to actually **create the robot arm** by calling the macro.

Expand All @@ -81,7 +81,7 @@ After that we are finally able to actually **create the robot arm** by calling t
:start-at: <xacro:ur_robot
:end-at: </xacro:ur_robot>
:linenos:
:caption: my_robot_cell_description/urdf/my_robot_cell.urdf.xacro
:caption: my_robot_cell_description/urdf/my_robot_cell.xacro

Note that the **origin** argument is transmitted in a different manner than the other arguments.

Expand Down
2 changes: 1 addition & 1 deletion my_robot_cell/doc/build_moveit_config.rst
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ First, we need to start a robot, simulated or real. If you start a real robot, m
.. code-block:: bash

# You can switch to real hardware if you prefer
ros2 launch my_robot_cell_control start_robot.launch.py use_mock_hardware:=true
ros2 launch my_robot_cell_control start_robot.launch.py use_fake_hardware:=true


Second, we can start the move_group node by running the launch file the setup assistant created for us:
Expand Down
43 changes: 8 additions & 35 deletions my_robot_cell/doc/start_ur_driver.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ This URDF is very similar to the one we have already assembled. We simply need t

.. literalinclude:: ../my_robot_cell_control/urdf/my_robot_cell_controlled.urdf.xacro
:language: xml
:start-at: <xacro:include filename="$(find ur_robot_driver)/urdf/ur.ros2_control.xacro"/>
:end-at: <xacro:include filename="$(find ur_robot_driver)/urdf/ur.ros2_control.xacro"/>
:start-at: <xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro"/>
:end-at: <xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro"/>
:caption: my_robot_cell_control/urdf/my_robot_cell_controlled.urdf.xacro


Expand All @@ -33,7 +33,7 @@ define the necessary arguments that need to be passed to the macro,
.. literalinclude:: ../my_robot_cell_control/urdf/my_robot_cell_controlled.urdf.xacro
:language: xml
:start-at: <xacro:arg name="robot_ip" default="0.0.0.0"/>
:end-at: <xacro:arg name="mock_sensor_commands" default="false" />
:end-at: <xacro:arg name="fake_sensor_commands" default="false" />
:caption: my_robot_cell_control/urdf/my_robot_cell_controlled.urdf.xacro


Expand All @@ -57,39 +57,12 @@ For now, we just copy the default one for the ur20.
cp $(ros2 pkg prefix ur_description)/share/ur_description/config/ur20/default_kinematics.yaml \
my_robot_cell_control/config/my_robot_calibration.yaml


Create robot_state_publisher launchfile
---------------------------------------

To use the custom controlled description, we need to generate a launchfile loading that description
(Since it contains less / potentially different) arguments than the "default" one. In that
launchfile we need to start a ``robot_state_publisher`` (RSP) node that will get the description as a
parameter and redistribute it via the ``robot_description`` topic:

.. literalinclude:: ../my_robot_cell_control/launch/rsp.launch.py
:language: py
:start-after: # Author: Felix Exner
:linenos:
:caption: my_robot_cell_control/launch/rsp.launch.py

With this we could start our workcell using

.. code-block:: bash

ros2 launch ur_robot_driver ur_control.launch.py \
description_launchfile:=$(ros2 pkg prefix my_robot_cell_control)/share/my_robot_cell_control/launch/rsp.launch.py \
use_mock_hardware:=true \
robot_ip:=123 \
ur_type:=ur20 \
rviz_config_file:=$(ros2 pkg prefix my_robot_cell_description)/share/my_robot_cell_description/rviz/urdf.rviz \
tf_prefix:=ur20_

Create start_robot launchfile
-----------------------------

Since the command above is obviously not very convenient to start our robot, we wrap that into another
launchfile that includes the ``ur_control.launch.py`` launchfile with the correct description
launchfile and prefix:
To launch a controlled robot with our custom description, we need to generate a launchfile. We
include the ``ur_control.launch.py`` file from the driver and set its parameters to match our
custom workcell.

.. literalinclude:: ../my_robot_cell_control/launch/start_robot.launch.py
:language: py
Expand All @@ -100,7 +73,7 @@ With that we can start the robot using

.. code-block:: bash

ros2 launch my_robot_cell_control start_robot.launch.py use_mock_hardware:=true
ros2 launch my_robot_cell_control start_robot.launch.py use_fake_hardware:=true

Testing everything
------------------
Expand All @@ -121,7 +94,7 @@ We can start the system in a mocked simulation
.. code-block:: bash

#start the driver with mocked hardware
ros2 launch my_robot_cell_control start_robot.launch.py use_mock_hardware:=true
ros2 launch my_robot_cell_control start_robot.launch.py use_fake_hardware:=true

Or to use it with a real robot:

Expand Down
2 changes: 1 addition & 1 deletion my_robot_cell/my_robot_cell_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(my_robot_cell_control)
find_package(ament_cmake REQUIRED)

install(
DIRECTORY launch config urdf
DIRECTORY launch config urdf rviz
DESTINATION share/${PROJECT_NAME}
)

Expand Down
94 changes: 0 additions & 94 deletions my_robot_cell/my_robot_cell_control/config/ros2_controllers.yaml

This file was deleted.

3 changes: 0 additions & 3 deletions my_robot_cell/my_robot_cell_control/config/update_rate.yaml

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
kinematics:
shoulder:
x: 0
y: 0
z: 0.23630000000000001
roll: -0
pitch: 0
yaw: -0
upper_arm:
x: 0
y: 0
z: 0
roll: 1.570796327
pitch: 0
yaw: -0
forearm:
x: -0.86199999999999999
y: 0
z: 0
roll: -0
pitch: 0
yaw: -0
wrist_1:
x: -0.72870000000000001
y: 0
z: 0.20100000000000001
roll: -0
pitch: 0
yaw: -0
wrist_2:
x: 0
y: -0.1593
z: -3.2672976162492252e-11
roll: 1.570796327
pitch: 0
yaw: -0
wrist_3:
x: 0
y: 0.15429999999999999
z: -3.1647459019915597e-11
roll: 1.5707963265897931
pitch: 3.1415926535897931
yaw: 3.1415926535897931
hash: calib_4890363623803256388
77 changes: 77 additions & 0 deletions my_robot_cell/my_robot_cell_control/config/ur20/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
# Joints limits
#
# Sources:
#
# - Universal Robots e-Series, User Manual, UR20, Version 5.14
# https://s3-eu-west-1.amazonaws.com/ur-support-site/203281/706-276-00_UR20_User_Manual_en_Global.pdf
joint_limits:
shoulder_pan_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 738.0
max_position: !degrees 360.0
max_velocity: !degrees 120.0
min_position: !degrees -360.0
shoulder_lift_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 738.0
max_position: !degrees 360.0
max_velocity: !degrees 120.0
min_position: !degrees -360.0
elbow_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 433.0
# we artificially limit this joint to half its actual joint position limit
# to avoid (MoveIt/OMPL) planning problems, as due to the physical
# construction of the robot, it's impossible to rotate the 'elbow_joint'
# over more than approx +- 1 pi (the shoulder lift joint gets in the way).
#
# This leads to planning problems as the search space will be divided into
# two sections, with no connections from one to the other.
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
max_position: !degrees 180.0
max_velocity: !degrees 150.0
min_position: !degrees -180.0
wrist_1_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 107.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
wrist_2_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 107.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
wrist_3_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 107.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
Loading