-
Notifications
You must be signed in to change notification settings - Fork 20
/
motoros2_config.yaml
270 lines (244 loc) · 10.6 KB
/
motoros2_config.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
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
---
# SPDX-FileCopyrightText: 2022-2023, Yaskawa America, Inc.
# SPDX-FileCopyrightText: 2022-2023, Delft University of Technology
#
# SPDX-License-Identifier: Apache-2.0
#-----------------------------------------------------------------------------
# REQUIRED
# IP address and UDP port number of the Micro-ROS Agent PC. All communication
# to/from MotoROS2 will route through the Agent application.
# (There is no default value for these fields. They must be specified by
# the user.)
#agent_ip_address: "192.168.255.50"
#agent_port_number: 8888
# Any settings that are not specified will be set to their DEFAULT value.
#-----------------------------------------------------------------------------
# The (DDS) domain to join
#
# Please refer to the ROS 2 documentation on DDS domain IDs for more
# information. This setting works exactly like its ROS 2 analogue.
#
# DEFAULT: 0 (the default ROS 2 domain ID)
#ros_domain_id: 0
#-----------------------------------------------------------------------------
# Name under which MotoROS2 should register with the ROS 2 node graph.
#
# DEFAULT: "motoman_xx_yy_zz" (xyz: last three bytes of robot's MAC address)
#node_name: ""
#-----------------------------------------------------------------------------
# Namespace to use for the MotoROS2 node and all topics.
#
# DEFAULT: "" (empty string)
#node_namespace: ""
#-----------------------------------------------------------------------------
# Remap rules to apply to ROS 2 resource names.
#
# This configures the micro-ROS equivalent of the ROS 2 remap functionality.
#
# The current implementation expects all remap rules as a single,
# space-separated string. Whitespace in resource names is not allowed, so
# this should not pose any issues.
#
# Maximum total length of the remap_rules string: 255 chars. Any characters
# beyond that will be ignored (and likely result in parsing failures).
#
# Please refer to the ROS 2 documentation on remapping for more information
# on syntax and contraints.
#
# Example: the following remaps the 'joint_states' topic to 'my_joint_states',
# and the 'read_single_io' service to 'io/read_single':
#
# "joint_states:=my_joint_states read_single_io:=io/read_single"
#
# DEFAULT: "" (empty string)
#remap_rules: ""
#-----------------------------------------------------------------------------
# This will ensure that when timestamps are sampled, they will match the clock
# of the Agent PC. This is useful if the date/time of the robot controller is
# not synchronized.
#
# DEFAULT: true
sync_timeclock_with_agent: true
#-----------------------------------------------------------------------------
# Should MotoROS2 monitor the link state of the ethernet port used to
# communicate with the Agent?
#
# If enabled, this will cause immediate notification of loss-of-connection
# when the link goes down, causing MotoROS2 to activate it's shutdown
# behaviour (ie: stop all motion (if enabled), release resources, wait for
# link up and attempt reconnection with the Agent).
#
# If this is disabled, Agent disconnection detection uses an application
# layer based timeout mechanism which takes longer to detect disconnects (but
# might be more robust against intermittent link-layer disconnects which do not
# cause network disconnections).
#
# DEFAULT: true
#userlan_monitor_enabled: true
#-----------------------------------------------------------------------------
# Which port should MotoROS2 monitor, if 'userlan_monitor_enabled' is 'true'?
#
# If not specified, MotoROS2 will attempt to auto-detect the network port
# that is used to connect to the micro-ROS Agent. It will do this by
# comparing the 'agent_ip_address' setting against the IP addresses (and
# netmasks) of all available network interfaces.
#
# If the Agent can be reached directly over a particular interface, or via a
# configured default gateway on the same interface, the associated port will be
# monitored for link drops.
#
# To disable auto-detection, uncomment 'userlan_monitor_port' below and set
# it to the desired port.
#
# NOTE: this setting only applies to YRC1000 and YRC1000u controllers.
# DX200 and FS100 controllers only have a single ethernet port, and any
# value other than 1 will be ignored.
#
# NOTE 2: auto-detection is not perfect. It can't determine whether the Agent
# might be reachable using multiple hops. Nor can it determine whether
# any routers have been configured to forward particular types of
# traffic or firewalls exist between MotoROS2 and the micro-ROS Agent.
# For deployments with complex network configurations, disable
# auto-detection by configuring 'userlan_monitor_port' below.
#
# NOTE 3: the port specified here is NOT checked against 'agent_ip_address'.
# In other words: if 'agent_ip_address' is on 'USER_LAN1', but
# 'userlan_monitor_port' is set to 'USER_LAN2', MotoROS2 will detect
# link down events on 'USER_LAN2', whether or not that port is used
# to communicate with the Agent.
#
# OPTIONS: USER_LAN1, USER_LAN2
# DEFAULT: USER_LAN1
#userlan_monitor_port: USER_LAN1
#-----------------------------------------------------------------------------
# If the Agent PC disconnects from the robot while it is in motion, should the
# robot come to a stop?
#
# DEFAULT: true
stop_motion_on_disconnect: true
#-----------------------------------------------------------------------------
# Should MotoROS2 broadcast transforms on '/tf'? This can be disabled if
# the data will interfere with applications such as robot_state_publisher.
#
# DEFAULT: true
publish_tf: true
#-----------------------------------------------------------------------------
# Should the 'tf' topic be namespaced if 'node_namespace' is configured with a
# non-empty string?
#
# Setting this to 'false' will make MotoROS2 broadcast transforms on the '/tf'
# global topic, which cannot be namespaced (due to being an absolute name).
# Otherwise, it will broadcast on 'tf', which can be namespaced.
#
# DEFAULT: true
namespace_tf: true
#-----------------------------------------------------------------------------
# Similar to the 'frame_prefix' parameter of the ROS 2 'robot_state_publisher'
# node. All published TF frames will be prefixed with this string.
#
# Example: with this parameter set to "left/", the "r1/tool0" frame would be
# published as "left/r1/tool0".
#
# NOTE: the prefix must include a separator (fi: '/') if one should be included
# in the final name of the TF frames. Such a separator is not added
# automatically.
#
# DEFAULT: "" (empty string)
#tf_frame_prefix: ""
#-----------------------------------------------------------------------------
# Joints in this configuration file must be listed in the order of Robots,
# Base-axes, Station-axes.
#
# Example: R1+B1+R2+S1 system
#
# joint_names:
# - [r1_s_axis, r1_l_axis, r1_u_axis, r1_r_axis, r1_b_axis, r1_t_axis]
# - [r2_s_axis, r2_l_axis, r2_u_axis, r2_r_axis, r2_b_axis, r2_t_axis, r2_e_axis]
# - [b1_axis]
# - [s1_axis_1, s1_axis_2]
#
# When using a 7 axis robot arm with an elbow joint (E) in the middle of the
# arm, the elbow axis should be listed last (SLURBTE).
#
# DEFAULT: "group_x/joint_y"
#joint_names:
#- [group_1/joint_1, group_1/joint_2, group_1/joint_3, group_1/joint_4, group_1/joint_5, group_1/joint_6]
#-----------------------------------------------------------------------------
# Logging settings
logging:
# All log messages are broadcast on the network on port UDP 21789.
# Additionally, the messages can be printed to the standard output stream of
# the robot controller. This would be visible over a telnet connection, or by
# attaching a VGA debug monitor to the robot controller.
#
# NOTE: this WILL slow down the application.
#
# DEFAULT: false
log_to_stdout: false
#-----------------------------------------------------------------------------
update_periods:
# The delay between checks for incoming activity on the network. A lower
# number will result in quicker responsiveness to received messages.
# Additionally, it determines the rate at which the feedback_publisher timers
# are checked.
# This value should be <= to action_feedback_publisher_period as executor_sleep_period
# is the rate at which the action-feedback timer is checked. If the value for
# action_feedback_publisher_period is < executor_sleep_period, it will effectively
# be treated as having the same value executor_sleep_period at runtime.
#
# DEFAULT: 10 milliseconds
executor_sleep_period: 10
# The delay between each publish of feedback position and status information.
# A lower number will publish the feedback data more frequently.
# This value should be >= to executor_sleep_period and
# controller_status_monitor_period.
#
# DEFAULT: 20 milliseconds
action_feedback_publisher_period: 20
# The delay between each poll of the robot I/O and controller status data.
# This value should be <= to action_feedback_publisher_period.
#
# DEFAULT: 10 milliseconds
controller_status_monitor_period: 10
#-----------------------------------------------------------------------------
# QoS profile to use for various publishers MotoROS2 creates.
# The default values here are based on tests and inspection of the source code
# of typical consumers of messages on these topics.
#
# NOTE : RViz2 expects/requires 'tf' to use the 'default' profile (ie: reliable).
# NOTE2: MoveIt2 expects/requires 'joint_states' to use the 'default' profile.
publisher_qos:
# DEFAULT: sensor_data
robot_status: sensor_data
# DEFAULT: sensor_data
joint_states: sensor_data
# DEFAULT: default
tf: default
#-----------------------------------------------------------------------------
# Name of the INFORM job to be used (and monitored) by MotoROS2.
#
# Maximum length: 32 UTF-8 characters. 16 Japanese (Shift-JIS) characters.
#
# Set this to a custom value when using a custom INFORM job with a different
# name.
#
# NOTE: do NOT include the file extension here (ie: '.JBI'). Only the name
# of the job should be specified.
#
# DEFAULT: "INIT_ROS"
#inform_job_name: "INIT_ROS"
#-----------------------------------------------------------------------------
# Allow custom INFORM job.
#
# If MotoROS2 detects that the specified INFORM job is not formatted properly
# then an alarm will be raised at startup.
# This flag indicates that the job is intentionally configured and will
# suppress the alarm.
#
# When this flag is set to 'true', then MotoROS2 will not validate whether the
# job is compatible. It is the responsibility of the user to make sure the
# custom job includes the required INFORM statements and in the expected order
# (refer to the provided INFORM job files for the general structure).
#
# DEFAULT: false
#allow_custom_inform: false