Skip to content

Commit f8fccc4

Browse files
authored
add basic CI tests (#26)
* add example configs * test load * rename test src files * refractor existing tests * fix jazzy-specific problem when instanciating th ctrl manager * add ft_sensor in URDF * fix ft_sensor frame * update mandatory parameters list * make vic plugin desc. param mandatory * fix tests (basic tests only...) * linting * fix "ft_sensor:is_enabled" param issues * source in CI before test * add dynamics_interface_kdl to pkg XML
1 parent cfa6bee commit f8fccc4

11 files changed

+339
-175
lines changed

.github/workflows/ci.yml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@ jobs:
5050
vcs import src < src/cartesian_controllers_ros2/cartesian_controllers_ros2.repos
5151
rosdep install --ignore-src --from-paths . -y -r
5252
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --symlink-install
53+
source install/setup.bash
5354
colcon test --event-handlers console_direct+
5455
colcon test-result
5556

cartesian_vic_controller/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,14 +69,15 @@ target_compile_definitions(cartesian_vic_controller PRIVATE "CARTESIAN_VIC_CONTR
6969
pluginlib_export_plugin_description_file(controller_interface cartesian_vic_controller.xml)
7070
pluginlib_export_plugin_description_file(cartesian_vic_controller cartesian_vic_rules.xml)
7171

72-
if(0) # (BUILD_TESTING)
72+
if(BUILD_TESTING)
7373
find_package(ament_cmake_gmock REQUIRED)
7474
find_package(controller_manager REQUIRED)
7575
find_package(ros2_control_test_assets REQUIRED)
7676

7777
# Dynamically loaded during test
7878
find_package(kinematics_interface_kdl REQUIRED)
7979

80+
#[[
8081
# test controller (loading only)
8182
add_rostest_with_parameters_gmock(test_load_controller
8283
test/test_load_controller.cpp
@@ -87,6 +88,7 @@ if(0) # (BUILD_TESTING)
8788
hardware_interface
8889
ros2_control_test_assets
8990
)
91+
#]]
9092

9193
# test controller
9294
add_rostest_with_parameters_gmock(test_controller

cartesian_vic_controller/config/example_admittance_controller_config.yaml

Lines changed: 29 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,7 @@
1-
cartesian_vic_controller:
1+
cartesian_impedance_controller:
22
ros__parameters:
33
command_interfaces:
4-
- position
5-
# - velocity
4+
- velocity
65
state_interfaces:
76
- position
87
- velocity
@@ -13,17 +12,21 @@ cartesian_vic_controller:
1312
- joint_a4
1413
- joint_a5
1514
- joint_a6
15+
- joint_a7
16+
17+
# Parameters for the controller
18+
# Note: having ".0" at the end of float is a MUST, otherwise there is a loading error
1619

1720
filters:
18-
state_position_filter_cuttoff_freq: 100.0
21+
state_position_filter_cuttoff_freq: -1.0
1922
state_velocity_filter_cuttoff_freq: 100.0
2023
command_filter_cuttoff_freq: -1.0
2124
ft_sensor_filter_cuttoff_freq: 30.0
2225

2326
dynamics:
24-
plugin_name: kinematics_interface_kdl/KinematicsInterfaceKDL
25-
plugin_package: kinematics_interface
26-
base: base_link # Assumed to be stationary
27+
plugin_name: dynamics_interface_kdl/DynamicsInterfaceKDL
28+
plugin_package: dynamics_interface
29+
base: iiwa_base # Assumed to be stationary
2730
tip: interaction_point
2831
alpha: 0.0005
2932
gravity: [0.0, 0.0, -9.81]
@@ -41,33 +44,37 @@ cartesian_vic_controller:
4144

4245
control:
4346
frame:
44-
id: interaction_point # Vic calcs (displacement etc) are done in this frame. Usually the tool or end-effector
47+
id: interaction_point # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
4548
external: false # control frame exists within URDF kinematic chain
4649

4750
fixed_world_frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link)
4851
frame:
49-
id: world # Vic calcs (displacement etc) are done in this frame. Usually the tool or end-effector
50-
external: false # control frame exists within URDF kinematic chain
52+
id: iiwa_base
53+
external: false
5154

5255
gravity_compensation:
5356
frame:
5457
id: ft_sensor
5558
external: false
5659

57-
CoG: # specifies the center of gravity of the end effector (post FT sensor)
60+
CoG:
5861
pos:
59-
- 0.0015 # x
60-
- 0.0001 # y
61-
- 0.0371 # z
62-
force: 0.5 # mass * 9.81
62+
- 0.01
63+
- 0.01
64+
- 0.01
65+
force: 0.0 # mass * 9.81
6366

6467
vic:
6568
frame:
66-
id: interaction_point # Vic calcs (displacement etc) are done in this frame. Usually the tool or end-effector
67-
# Vic rule
69+
id: interaction_point # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
70+
external: false # control frame exists within URDF kinematic chain
71+
# VIC rule
6872
plugin_package: cartesian_vic_controller
69-
plugin_name: cartesian_vic_controller/VanillaCartesianAdmittanceRule # Nominal admittance controller
70-
# plugin_name: cartesian_vic_controller/VanillaCartesianImpedanceRule # Nominal impedance controller
73+
plugin_name: cartesian_vic_controller/VanillaCartesianAdmittanceRule # As nominal controller
74+
75+
# Misc. control parameters
76+
activate_nullspace_control: false
77+
activate_gravity_compensation: false
7178

7279
selected_axes:
7380
- true # x
@@ -77,8 +84,6 @@ cartesian_vic_controller:
7784
- true # ry
7885
- true # rz
7986

80-
# Having ".0" at the end is MUST, otherwise there is a loading error
81-
# F = M*a + D*v + S*(x - x_d)
8287
inertia:
8388
- 5.0
8489
- 5.0
@@ -91,9 +96,9 @@ cartesian_vic_controller:
9196
- 0.9 # x
9297
- 0.9 # y
9398
- 0.9 # z
94-
- 0.9 # rx
95-
- 0.9 # ry
96-
- 0.9 # rz
99+
- 0.99 # rx
100+
- 0.99 # ry
101+
- 0.99 # rz
97102

98103
stiffness:
99104
- 200.0
@@ -102,5 +107,3 @@ cartesian_vic_controller:
102107
- 2.0
103108
- 2.0
104109
- 2.0
105-
106-
joint_damping: 0.5
Lines changed: 116 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,116 @@
1+
cartesian_impedance_controller:
2+
ros__parameters:
3+
command_interfaces:
4+
- force
5+
state_interfaces:
6+
- position
7+
- velocity
8+
joints:
9+
- joint_a1
10+
- joint_a2
11+
- joint_a3
12+
- joint_a4
13+
- joint_a5
14+
- joint_a6
15+
- joint_a7
16+
17+
# Parameters for the controller
18+
# Note: having ".0" at the end of float is a MUST, otherwise there is a loading error
19+
20+
filters:
21+
state_position_filter_cuttoff_freq: -1.0
22+
state_velocity_filter_cuttoff_freq: 100.0
23+
command_filter_cuttoff_freq: -1.0
24+
ft_sensor_filter_cuttoff_freq: 30.0
25+
26+
dynamics:
27+
plugin_name: dynamics_interface_kdl/DynamicsInterfaceKDL
28+
plugin_package: dynamics_interface
29+
base: iiwa_base # Assumed to be stationary
30+
tip: interaction_point
31+
alpha: 0.0005
32+
gravity: [0.0, 0.0, -9.81]
33+
34+
ft_sensor:
35+
name: ft_sensor
36+
frame:
37+
id: ft_sensor # Wrench measurements are in this frame
38+
external: false # force torque frame exists within URDF kinematic chain
39+
40+
external_torque_sensor:
41+
is_enabled: false
42+
name: ""
43+
44+
control:
45+
frame:
46+
id: interaction_point # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
47+
external: false # control frame exists within URDF kinematic chain
48+
49+
fixed_world_frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link)
50+
frame:
51+
id: iiwa_base
52+
external: false
53+
54+
gravity_compensation:
55+
frame:
56+
id: ft_sensor
57+
external: false
58+
59+
CoG:
60+
pos:
61+
- 0.01
62+
- 0.01
63+
- 0.01
64+
force: 0.0 # mass * 9.81
65+
66+
vic:
67+
frame:
68+
id: interaction_point # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
69+
external: false # control frame exists within URDF kinematic chain
70+
# VIC rule
71+
plugin_package: cartesian_vic_controller
72+
plugin_name: cartesian_vic_controller/VanillaCartesianImpedanceRule # As nominal controller
73+
74+
# Misc. control parameters
75+
activate_nullspace_control: true
76+
activate_gravity_compensation: true
77+
78+
selected_axes:
79+
- true # x
80+
- true # y
81+
- true # z
82+
- true # rx
83+
- true # ry
84+
- true # rz
85+
86+
inertia:
87+
- 5.0
88+
- 5.0
89+
- 5.0
90+
- 0.1
91+
- 0.1
92+
- 0.1
93+
94+
damping_ratio: # damping can be used instead: zeta = D / (2 * sqrt( M * S ))
95+
- 0.9 # x
96+
- 0.9 # y
97+
- 0.9 # z
98+
- 0.99 # rx
99+
- 0.99 # ry
100+
- 0.99 # rz
101+
102+
stiffness:
103+
- 200.0
104+
- 200.0
105+
- 200.0
106+
- 2.0
107+
- 2.0
108+
- 2.0
109+
110+
nullspace_control:
111+
# desired_joint_positions: [...] # if empty, defaults to initial joint positions
112+
# desired_joint_positions: [0.0, -0.7854, 0.0, 1.3962, 0.0, 0.6109, 0.0]
113+
joint_inertia: [25.0]
114+
joint_stiffness: [100.0]
115+
joint_damping: [90.0] # e.g., 2 * 0.9 * sqrt (m * k)
116+
# Example values for {M, K, D} : {25, 10, 28}, {25, 100, 90}, {25, 200, 128}

cartesian_vic_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111

1212
<depend>cartesian_control_msgs</depend>
1313
<depend>dynamics_interface</depend>
14+
<depend>dynamics_interface_kdl</depend>
1415

1516
<depend>backward_ros</depend>
1617
<depend>control_msgs</depend>

cartesian_vic_controller/src/cartesian_vic_controller_parameters.yaml

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -148,12 +148,10 @@ cartesian_vic_controller:
148148
}
149149
plugin_name: {
150150
type: string,
151-
default_value: "cartesian_vic_controller/VanillaCartesianAdmittanceRule",
152151
description: "Specifies the name of the vic rule plugin to load."
153152
}
154153
plugin_package: {
155154
type: string,
156-
default_value: "cartesian_vic_controller",
157155
description: "Specifies the package name that contains the admittance rule plugin."
158156
}
159157
selected_axes:
@@ -196,7 +194,7 @@ cartesian_vic_controller:
196194
The damping ratio is defined as: zeta = D / (2 * sqrt( M * S )).",
197195
validation: {
198196
fixed_size<>: 6,
199-
element_bounds<>: [ 0.0, 1.2 ]
197+
element_bounds<>: [ 0.0, 5.0 ]
200198
}
201199
}
202200
stiffness: {

cartesian_vic_controller/test/test_asset_6d_robot_description.hpp

Lines changed: 27 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
1+
// Copyright 2024 ICUBE Laboratory, University of Strasbourg
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -258,6 +258,32 @@ const auto valid_6d_robot_urdf =
258258
</command_interface>
259259
<state_interface name="position"/>
260260
</joint>
261+
<!-- F/T sensor -->
262+
<sensor name="tool0">
263+
<state_interface name="force.x">
264+
<param name="initial_value">0.0</param>
265+
</state_interface>
266+
267+
<state_interface name="force.y">
268+
<param name="initial_value">0.0</param>
269+
</state_interface>
270+
271+
<state_interface name="force.z">
272+
<param name="initial_value">0.0</param>
273+
</state_interface>
274+
275+
<state_interface name="torque.x">
276+
<param name="initial_value">0.0</param>
277+
</state_interface>
278+
279+
<state_interface name="torque.y">
280+
<param name="initial_value">0.0</param>
281+
</state_interface>
282+
283+
<state_interface name="torque.z">
284+
<param name="initial_value">0.0</param>
285+
</state_interface>
286+
</sensor>
261287
</ros2_control>
262288
</robot>
263289
)";

0 commit comments

Comments
 (0)