-
Notifications
You must be signed in to change notification settings - Fork 56
/
Copy pathlbr_controllers.yaml
124 lines (105 loc) · 3.58 KB
/
lbr_controllers.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
# Use of /** so that the configurations hold for controller
# managers regardless of their namespace. Usefull in multi-robot setups.
/**/controller_manager:
ros__parameters:
update_rate: 100
# ROS 2 control broadcasters
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
force_torque_broadcaster:
type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster
# LBR ROS 2 control broadcasters
lbr_state_broadcaster:
type: lbr_ros2_control/LBRStateBroadcaster
# ROS 2 control controllers
joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
forward_position_controller:
type: position_controllers/JointGroupPositionController
# LBR ROS 2 control controllers
admittance_controller:
type: lbr_ros2_control/AdmittanceController
lbr_joint_position_command_controller:
type: lbr_ros2_control/LBRJointPositionCommandController
lbr_torque_command_controller:
type: lbr_ros2_control/LBRTorqueCommandController
lbr_wrench_command_controller:
type: lbr_ros2_control/LBRWrenchCommandController
twist_controller:
type: lbr_ros2_control/TwistController
# ROS 2 control broadcasters
/**/force_torque_broadcaster:
ros__parameters:
frame_id: lbr_link_ee # namespace: https://github.com/ros2/rviz/issues/1103
sensor_name: estimated_ft_sensor
# LBR ROS 2 control broadcasters
/**/lbr_state_broadcaster:
ros__parameters:
robot_name: lbr
# ROS 2 control controllers
/**/joint_trajectory_controller:
ros__parameters:
joints:
- lbr_A1
- lbr_A2
- lbr_A3
- lbr_A4
- lbr_A5
- lbr_A6
- lbr_A7
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 50.0
action_monitor_rate: 20.0
/**/forward_position_controller:
ros__parameters:
joints:
- lbr_A1
- lbr_A2
- lbr_A3
- lbr_A4
- lbr_A5
- lbr_A6
- lbr_A7
interface_name: position
# LBR ROS 2 control controllers
/**/lbr_joint_position_command_controller:
ros__parameters:
robot_name: lbr
/**/lbr_torque_command_controller:
ros__parameters:
robot_name: lbr
/**/lbr_wrench_command_controller:
ros__parameters:
robot_name: lbr
/**/admittance_controller:
ros__parameters:
robot_name: lbr
admittance:
mass: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
damping: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
stiffness: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
inv_jac_ctrl:
chain_root: lbr_link_0
chain_tip: lbr_link_ee
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
max_linear_velocity: 2.0 # maximum linear velocity
max_angular_velocity: 2.0 # maximum linear acceleration
joint_gains: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # joint gains
cartesian_gains: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # cartesian gains
/**/twist_controller:
ros__parameters:
robot_name: lbr
inv_jac_ctrl:
chain_root: lbr_link_0
chain_tip: lbr_link_ee
twist_in_tip_frame: true # if true, the twist command is expressed in the tip frame, otherwise in the root frame
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
max_linear_velocity: 0.1 # maximum linear velocity
max_angular_velocity: 0.1 # maximum linear acceleration
joint_gains: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # joint gains
cartesian_gains: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # cartesian gains
timeout: 0.2 # stop controller if no command is received within this time [s]