-
Notifications
You must be signed in to change notification settings - Fork 4
/
data_sources.yaml
139 lines (139 loc) · 4.87 KB
/
data_sources.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
- default_parameters:
max_frequency: 30
# maximum database size in MB
max_database_size: 102400
# whether or not to create a new DB after max size is reached
split_database: false
db_name: 'logs'
db_export_dir: '~/black-box-logs'
- event:
listeners:
- listener:
name: rosparam
event_type: 'ON_CHANGE'
- listener:
name: system_info
event_type: 'ON_STARTUP'
max_frequency: 1
- zyre:
name: black_box_001
groups:
- ROPOD
message_types:
- CMD
- plan
- progress
- RobotPose2D
- ros:
ros_master_uri: localhost
topics:
- topic:
name: /ropod/odom
type: nav_msgs/Odometry
variable_names: [position/x, position/y, position/z, orientation/x, orientation/y, orientation/z, orientation/w, linear/x, linear/y, linear/z, angular/x, angular/y, angular/z]
max_frequency: 10
metadata:
ros:
topic_name: /ropod/odom
msg_type: nav_msgs/Odometry
direct_msg_mapping: true
- topic:
name: amcl_pose
type: geometry_msgs/PoseWithCovarianceStamped
variable_names: [position/x, position/y, position/z, orientation/x, orientation/y, orientation/z, orientation/w, covariance]
max_frequency: 30
metadata:
ros:
topic_name: amcl_pose
msg_type: geometry_msgs/PoseWithCovarianceStamped
direct_msg_mapping: true
- topic:
name: /ropod/laser/scan
type: sensor_msgs/LaserScan
variable_names: [frame_id, angle_min, angle_max, angle_increment, time_increment, scan_time, range_min, range_max, ranges]
max_frequency: 10
metadata:
ros:
topic_name: /ropod/laser/scan
msg_type: sensor_msgs/LaserScan
direct_msg_mapping: true
- topic:
name: /ropod/cmd_vel
type: geometry_msgs/Twist
variable_names: [linear/x, linear/y, linear/z, angular/x, angular/y, angular/z]
max_frequency: 10
metadata:
ros:
topic_name: /ropod/cmd_vel
msg_type: geometry_msgs/Twist
direct_msg_mapping: true
- topic:
name: /sw_ethercat_parser/data
type: ropod_ros_msgs/SmartWheelData
variable_names: [commands, sensors, working_count]
max_frequency: 30
metadata:
ros:
topic_name: /sw_ethercat_parser/data
msg_type: ropod_ros_msgs/SmartWheelData
direct_msg_mapping: true
- topic:
name: /load/cmd_vel
type: geometry_msgs/Twist
variable_names: []
max_frequency: 10
metadata:
ros:
topic_name: /load/cmd_vel
msg_type: geometry_msgs/Twist
direct_msg_mapping: true
- topic:
name: /route_navigation/goal
type: maneuver_navigation/Goal
variable_names: []
max_frequency: 10
metadata:
ros:
topic_name: /route_navigation/goal
msg_type: maneuver_navigation/Goal
direct_msg_mapping: true
- topic:
name: /maneuver_navigation/goal_rviz
type: geometry_msgs/PoseStamped
variable_names: []
max_frequency: 10
metadata:
ros:
topic_name: /maneuver_navigation/goal_rviz
msg_type: geometry_msgs/PoseStamped
direct_msg_mapping: true
- topic:
name: /maneuver_navigation/local_costmap/costmap
type: nav_msgs/OccupancyGrid
variable_names: []
max_frequency: 1
metadata:
ros:
topic_name: /maneuver_navigation/local_costmap/costmap
msg_type: nav_msgs/OccupancyGrid
direct_msg_mapping: true
- topic:
name: /tf
type: tf2_msgs/TFMessage
variable_names: []
max_frequency: 150
metadata:
ros:
topic_name: /tf
msg_type: tf2_msgs/TFMessage
direct_msg_mapping: true
- topic:
name: /ropod/event
type: ropod_ros_msgs/Event
variable_names: []
max_frequency: 1
metadata:
ros:
topic_name: /ropod/event
msg_type: ropod_ros_msgs/Event
direct_msg_mapping: true