Skip to content

Commit d3af205

Browse files
committed
added dual arm demo draft (#189)
1 parent 218d723 commit d3af205

7 files changed

Lines changed: 308 additions & 0 deletions

File tree

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
cmake_minimum_required(VERSION 3.8)
2+
project(lbr_dual_arm_description)
3+
4+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5+
add_compile_options(-Wall -Wextra -Wpedantic)
6+
endif()
7+
8+
# find dependencies
9+
find_package(ament_cmake REQUIRED)
10+
find_package(lbr_description REQUIRED)
11+
12+
install(DIRECTORY ros2_control urdf
13+
DESTINATION share/${PROJECT_NAME}
14+
)
15+
16+
if(BUILD_TESTING)
17+
find_package(ament_lint_auto REQUIRED)
18+
# the following line skips the linter which checks for copyrights
19+
# comment the line when a copyright and license is added to all source files
20+
set(ament_cmake_copyright_FOUND TRUE)
21+
# the following line skips cpplint (only works in a git repo)
22+
# comment the line when this package is in a git repo and when
23+
# a copyright and license is added to all source files
24+
set(ament_cmake_cpplint_FOUND TRUE)
25+
ament_lint_auto_find_test_dependencies()
26+
endif()
27+
28+
ament_package()
Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
lbr_dual_arm_description
2+
========================
3+
This demo gives a walk through on using the ``lbr_description`` to generate a custom robot description. In this case, we will be investigating a dual-arm setup.
4+
5+
.. contents:: Table of Contents
6+
:depth: 2
7+
:local:
8+
:backlinks: none
9+
10+
Creating the Package
11+
--------------------
12+
#. Inside your workspace, create a package:
13+
14+
.. code-block:: bash
15+
16+
ros2 pkg create lbr_dual_arm_description \
17+
--build-type ament_cmake \
18+
--license Apache-2.0 \
19+
--maintainer-name mhubii \
20+
--maintainer-email "m.huber_1994@hotmail.de" \
21+
--description "A dual LBR description package using lbr_description." \
22+
--dependencies lbr_description
23+
24+
#. Remove unused folders and create a Universal Robot Description File (URDF) folder:
25+
26+
.. code-block:: bash
27+
28+
cd lbr_dual_arm_description && \
29+
rm -r lbr_dual_arm_description/include && \
30+
rm -r lbr_dual_arm_description/src && \
31+
mkdir urdf
32+
33+
Creating the Dual-arm Robot Description
34+
---------------------------------------
35+
#. Create a dual-arm robot description:
36+
37+
.. code-block:: bash
38+
39+
touch urdf/lbr_dual_arm.xacro
40+
41+
#. Fill it with the following contents (note that `xacro <https://github.com/ros/xacro/tree/ros2>`_:octicon:`link-external` is used):
42+
43+
.. code-block:: XML
44+
45+
<?xml version="1.0"?>
46+
47+
<robot name="lbr_dual_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
48+
<!-- include the lbr iiwa macro -->
49+
<xacro:include filename="$(find lbr_description)/urdf/iiwa7/iiwa7_description.xacro" />
50+
51+
<!-- add an arguent to allow for mock / hardware / gazebo -->
52+
<xacro:arg name="mode" default="mock" />
53+
54+
<!-- add a base / floating link -->
55+
<link name="base_link" />
56+
57+
<!-- add robot 1 via macro, note that different lbr_one_system_config.yaml are used (to
58+
configure port id) -->
59+
<xacro:iiwa7
60+
robot_name="lbr_one"
61+
mode="$(arg mode)"
62+
system_config_path="$(find lbr_dual_arm_description)/ros2_control/lbr_one_system_config.yaml" />
63+
64+
<!-- add robot 2 via macro -->
65+
<xacro:iiwa7
66+
robot_name="lbr_two"
67+
mode="$(arg mode)"
68+
system_config_path="$(find lbr_dual_arm_description)/ros2_control/lbr_two_system_config.yaml" />
69+
</robot>
70+
71+
#. Create the ROS 2 Control configuration files:
72+
73+
#. Create a configurations file for the controller manager and respective controllers:
74+
75+
76+
77+
#. FRI system configurations (only necessary when hardware is used):
78+
79+
.. code-block:: bash
80+
81+
cp `ros2 pkg prefix lbr_description`/share/lbr_description/ros2_control/lbr_system_config.yaml ros2_control/lbr_one_system_config.yaml && \
82+
cp `ros2 pkg prefix lbr_description`/share/lbr_description/ros2_control/lbr_system_config.yaml ros2_control/lbr_two_system_config.yaml
83+
84+
#. Open ``lbr_two_system_config.yaml``:
85+
86+
#. Change ``port_id`` to ``30201`` (or as desired, but different from ``lbr_one_system_config.yaml``)
87+
#. Update ``estimated_ft_sensor`` frames:
88+
89+
.. code-black:: yaml
90+
91+
chain_root: lbr_one_link_0 # and lbr_two_link_0 respectively
92+
chain_tip: lbr_one_link_ee # and lbr_two_link_0 respectively
93+
94+
#. Add the following to the ``CMakeLists.txt``:
95+
96+
.. code-block:: cmake
97+
98+
install(DIRECTORY ros2_control urdf
99+
DESTINATION share/${PROJECT_NAME}
100+
)
101+
102+
103+
104+
.. #. Build the package in your workspace:
105+
106+
.. .. code-block:: bash
107+
108+
.. colcon build --packages-select lbr_dual_arm_description --symlink-install
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>lbr_dual_arm_description</name>
5+
<version>2.1.2</version>
6+
<description>A dual LBR description package using lbr_description.</description>
7+
<maintainer email="m.huber_1994@hotmail.de">mhubii</maintainer>
8+
<license>Apache-2.0</license>
9+
10+
<buildtool_depend>ament_cmake</buildtool_depend>
11+
12+
<depend>lbr_description</depend>
13+
14+
<test_depend>ament_lint_auto</test_depend>
15+
<test_depend>ament_lint_common</test_depend>
16+
17+
<export>
18+
<build_type>ament_cmake</build_type>
19+
</export>
20+
</package>
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
# Use of /** so that the configurations hold for controller
2+
# managers regardless of their namespace. Usefull in multi-robot setups.
3+
/**/controller_manager:
4+
ros__parameters:
5+
update_rate: 100
6+
7+
# ROS 2 control broadcasters
8+
joint_state_broadcaster:
9+
type: joint_state_broadcaster/JointStateBroadcaster
10+
11+
# # LBR ROS 2 control broadcasters
12+
# lbr_state_broadcaster:
13+
# type: lbr_ros2_control/LBRStateBroadcaster
14+
15+
# ROS 2 control controllers
16+
joint_trajectory_controller:
17+
type: joint_trajectory_controller/JointTrajectoryController
18+
19+
# # LBR ROS 2 control broadcasters
20+
# /**/lbr_state_broadcaster:
21+
# ros__parameters:
22+
# robot_name: lbr
23+
24+
# ROS 2 control controllers
25+
/**/joint_trajectory_controller:
26+
ros__parameters:
27+
joints:
28+
# robot one
29+
- lbr_one_A1
30+
- lbr_one_A2
31+
- lbr_one_A3
32+
- lbr_one_A4
33+
- lbr_one_A5
34+
- lbr_one_A6
35+
- lbr_one_A7
36+
# robot two
37+
- lbr_two_A1
38+
- lbr_two_A2
39+
- lbr_two_A3
40+
- lbr_two_A4
41+
- lbr_two_A5
42+
- lbr_two_A6
43+
- lbr_two_A7
44+
command_interfaces:
45+
- position
46+
state_interfaces:
47+
- position
48+
- velocity
49+
state_publish_rate: 50.0
50+
action_monitor_rate: 20.0
Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
# these parameters are read by the lbr_system_interface.xacro and configure the lbr_ros2_control::SystemInterface
2+
hardware:
3+
fri_client_sdk: # the fri_client_sdk version is used to create the correct state interfaces lbr_system_interface.xacro
4+
major_version: 1
5+
minor_version: 15
6+
client_command_mode: position # the command mode specifies the user-sent commands. Available: [position, torque, wrench]
7+
port_id: 30200 # port id for the UDP communication. Useful in multi-robot setups
8+
remote_host: INADDR_ANY # the expected robot IP address. INADDR_ANY will accept any incoming connection
9+
rt_prio: 80 # real-time priority for the control loop
10+
pid_p: 0.1 # P gain for the joint position (useful for asynchronous control)
11+
pid_i: 0.0 # I gain for the joint position command
12+
pid_d: 0.0 # D gain for the joint position command
13+
pid_i_max: 0.0 # max integral value for the joint position command
14+
pid_i_min: 0.0 # min integral value for the joint position command
15+
pid_antiwindup: false # enable antiwindup for the joint position command
16+
command_guard_variant: default # if requested position / velocities beyond limits, CommandGuard will be triggered and shut the connection. Available: [default, safe_stop]
17+
external_torque_cutoff_frequency: 10 # low-pass filter for the external joint torque measurements [Hz]
18+
measured_torque_cutoff_frequency: 10 # low-pass filter for the joint torque measurements [Hz]
19+
open_loop: true # KUKA works the best in open_loop control mode
20+
21+
estimated_ft_sensor: # estimates the external force-torque from the external joint torque values
22+
enabled: true # whether to enable the force-torque estimation
23+
update_rate: 100 # update rate for the force-torque estimation [Hz] (less or equal to controller manager update rate)
24+
rt_prio: 30 # real-time priority for the force-torque estimation
25+
chain_root: lbr_one_link_0
26+
chain_tip: lbr_one_link_ee
27+
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
28+
force_x_th: 2.0 # x-force threshold. Only if the force exceeds this value, the force will be considered
29+
force_y_th: 2.0 # y-force threshold. Only if the force exceeds this value, the force will be considered
30+
force_z_th: 2.0 # z-force threshold. Only if the force exceeds this value, the force will be considered
31+
torque_x_th: 0.5 # x-torque threshold. Only if the torque exceeds this value, the torque will be considered
32+
torque_y_th: 0.5 # y-torque threshold. Only if the torque exceeds this value, the torque will be considered
33+
torque_z_th: 0.5 # z-torque threshold. Only if the torque exceeds this value, the torque will be considered
Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
# these parameters are read by the lbr_system_interface.xacro and configure the lbr_ros2_control::SystemInterface
2+
hardware:
3+
fri_client_sdk: # the fri_client_sdk version is used to create the correct state interfaces lbr_system_interface.xacro
4+
major_version: 1
5+
minor_version: 15
6+
client_command_mode: position # the command mode specifies the user-sent commands. Available: [position, torque, wrench]
7+
port_id: 30201 # port id for the UDP communication. Useful in multi-robot setups
8+
remote_host: INADDR_ANY # the expected robot IP address. INADDR_ANY will accept any incoming connection
9+
rt_prio: 80 # real-time priority for the control loop
10+
pid_p: 0.1 # P gain for the joint position (useful for asynchronous control)
11+
pid_i: 0.0 # I gain for the joint position command
12+
pid_d: 0.0 # D gain for the joint position command
13+
pid_i_max: 0.0 # max integral value for the joint position command
14+
pid_i_min: 0.0 # min integral value for the joint position command
15+
pid_antiwindup: false # enable antiwindup for the joint position command
16+
command_guard_variant: default # if requested position / velocities beyond limits, CommandGuard will be triggered and shut the connection. Available: [default, safe_stop]
17+
external_torque_cutoff_frequency: 10 # low-pass filter for the external joint torque measurements [Hz]
18+
measured_torque_cutoff_frequency: 10 # low-pass filter for the joint torque measurements [Hz]
19+
open_loop: true # KUKA works the best in open_loop control mode
20+
21+
estimated_ft_sensor: # estimates the external force-torque from the external joint torque values
22+
enabled: true # whether to enable the force-torque estimation
23+
update_rate: 100 # update rate for the force-torque estimation [Hz] (less or equal to controller manager update rate)
24+
rt_prio: 30 # real-time priority for the force-torque estimation
25+
chain_root: lbr_two_link_0
26+
chain_tip: lbr_two_link_ee
27+
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
28+
force_x_th: 2.0 # x-force threshold. Only if the force exceeds this value, the force will be considered
29+
force_y_th: 2.0 # y-force threshold. Only if the force exceeds this value, the force will be considered
30+
force_z_th: 2.0 # z-force threshold. Only if the force exceeds this value, the force will be considered
31+
torque_x_th: 0.5 # x-torque threshold. Only if the torque exceeds this value, the torque will be considered
32+
torque_y_th: 0.5 # y-torque threshold. Only if the torque exceeds this value, the torque will be considered
33+
torque_z_th: 0.5 # z-torque threshold. Only if the torque exceeds this value, the torque will be considered
Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
<?xml version="1.0"?>
2+
3+
<robot name="lbr_dual_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
4+
<!-- include the lbr iiwa macro -->
5+
<xacro:include filename="$(find lbr_description)/urdf/iiwa7/iiwa7_description.xacro" />
6+
7+
<!-- add an arguent to allow for mock / hardware / gazebo -->
8+
<xacro:arg name="mode" default="mock" />
9+
10+
<!-- add a base / floating link -->
11+
<link name="base_link" />
12+
13+
<!-- add joints that connect the robots -->
14+
<joint name="lbr_one_base_joint" type="fixed">
15+
<parent link="base_link" />
16+
<child link="lbr_one_link_0" />
17+
</joint>
18+
19+
<joint name="lbr_two_base_joint" type="fixed">
20+
<parent link="base_link" />
21+
<child link="lbr_two_link_0" />
22+
</joint>
23+
24+
<!-- add robot 1 via macro, note that different lbr_one_system_config.yaml are used (to
25+
configure port id) -->
26+
<xacro:iiwa7
27+
robot_name="lbr_one"
28+
mode="$(arg mode)"
29+
system_config_path="$(find lbr_dual_arm_description)/ros2_control/lbr_one_system_config.yaml" />
30+
31+
<!-- add robot 2 via macro -->
32+
<xacro:iiwa7
33+
robot_name="lbr_two"
34+
mode="$(arg mode)"
35+
system_config_path="$(find lbr_dual_arm_description)/ros2_control/lbr_two_system_config.yaml" />
36+
</robot>

0 commit comments

Comments
 (0)