-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathpx4_config.yaml
283 lines (244 loc) · 7.91 KB
/
px4_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
271
272
273
274
275
276
277
278
279
280
281
282
283
# Common configuration for MAVROS
# node:
startup_px4_usb_quirk: false
# --- system plugins ---
# sys_status & sys_time connection options
conn:
heartbeat_rate: 1.0 # send heartbeat rate in Hertz
timeout: 10.0 # heartbeat timeout in seconds
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
# sys_status
sys:
min_voltage: 10.0 # diagnostics min voltage, use a vector i.e. [16.2, 16.0] for multiple batteries, up-to 10 are supported
# to achieve the same on a ROS launch file do: <rosparam param="sys/min_voltage">[16.2, 16.0]</rosparam>
disable_diag: false # disable all sys_status diagnostics, except heartbeat
# sys_time
# System time plugin. Does time syncronization on PX4.
time:
time_ref_source: "fcu" # time_reference source
timesync_mode: MAVLINK
timesync_avg_alpha: 0.6 # timesync averaging factor
# --- mavros plugins (alphabetical order) ---
# 3dr_radio
tdr_radio:
low_rssi: 40 # raw rssi lower level for diagnostics
# actuator_control
# None
# command
# Send COMMAND_LONG to FCU (Arming, set_gome, takeoff, land etc.)
cmd:
use_comp_id_system_control: false # quirk for some old FCUs
# dummy
# None
# ftp
# Support plugin for MAVLink-FTP
# None
# global_position
# Publish global position information fused by FCU and raw GPS data.
global_position:
frame_id: "map" # origin frame
child_frame_id: "base_link" # body-fixed frame
rot_covariance: 99999.0 # covariance for attitude?
gps_uere: 1.0 # User Equivalent Range Error (UERE) of GPS sensor (m)
use_relative_alt: true # use relative altitude for local coordinates
tf:
send: true # send TF?
frame_id: "map" # TF frame_id
global_frame_id: "earth" # TF earth frame_id
child_frame_id: "base_link" # TF child_frame_id
# imu_pub
imu:
frame_id: "base_link"
# need find actual values
linear_acceleration_stdev: 0.0003
angular_velocity_stdev: 0.0003490659 // 0.02 degrees
orientation_stdev: 1.0
magnetic_stdev: 0.0
# local_position
local_position:
frame_id: "map"
tf:
send: false
frame_id: "map"
child_frame_id: "base_link"
send_fcu: false
# param
# None, used for FCU params
# rc_io
# None
# safety_area
safety_area:
p1: {x: 1.0, y: 1.0, z: 1.0}
p2: {x: -1.0, y: -1.0, z: -1.0}
# setpoint_accel
setpoint_accel:
send_force: false
# setpoint_attitude
setpoint_attitude:
reverse_thrust: false # allow reversed thrust
use_quaternion: false # enable PoseStamped topic subscriber
tf:
listen: false # enable tf listener (disable topic subscribers)
frame_id: "map"
child_frame_id: "target_attitude"
rate_limit: 50.0
setpoint_raw:
thrust_scaling: 1.0 # used in setpoint_raw attitude callback.
# Note: PX4 expects normalized thrust values between 0 and 1, which means that
# the scaling needs to be unitary and the inputs should be 0..1 as well.
# setpoint_position
setpoint_position:
tf:
listen: false # enable tf listener (disable topic subscribers)
frame_id: "map"
child_frame_id: "target_position"
rate_limit: 50.0
mav_frame: LOCAL_NED
# setpoint_velocity
setpoint_velocity:
mav_frame: LOCAL_NED
# vfr_hud
# None
# waypoint
mission:
pull_after_gcs: true # update mission if gcs updates
use_mission_item_int: true # use the MISSION_ITEM_INT message instead of MISSION_ITEM
# for uploading waypoints to FCU
# --- mavros extras plugins (same order) ---
# distance_sensor
## Currently available orientations:
# Check http://wiki.ros.org/mavros/Enumerations
##
distance_sensor:
hrlv_ez4_pub:
id: 0
frame_id: "hrlv_ez4_sonar"
orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing
field_of_view: 0.0 # XXX TODO
send_tf: true
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
lidarlite_pub:
id: 1
frame_id: "lidarlite_laser"
orientation: PITCH_270
field_of_view: 0.0 # XXX TODO
send_tf: true
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
sonar_1_sub:
subscriber: true
id: 2
orientation: PITCH_270
horizontal_fov_ratio: 1.0 # horizontal_fov = horizontal_fov_ratio * msg.field_of_view
vertical_fov_ratio: 1.0 # vertical_fov = vertical_fov_ratio * msg.field_of_view
# custom_orientation: # Used for orientation == CUSTOM
# roll: 0
# pitch: 270
# yaw: 0
laser_1_sub:
subscriber: true
id: 3
orientation: PITCH_270
# image_pub
# Publishes images from PX4Flow module
image:
frame_id: "px4flow"
# fake_gps
fake_gps:
# select data source
use_mocap: true # ~mocap/pose
mocap_transform: true # ~mocap/tf instead of pose
use_vision: false # ~vision (pose)
# origin (default: Zürich)
geo_origin:
lat: 47.3667 # latitude [degrees]
lon: 8.5500 # longitude [degrees]
alt: 408.0 # altitude (height over the WGS-84 ellipsoid) [meters]
eph: 2.0
epv: 2.0
satellites_visible: 5 # virtual number of visible satellites
fix_type: 3 # type of GPS fix (default: 3D)
tf:
listen: false
send: false # send TF?
frame_id: "map" # TF frame_id
child_frame_id: "fix" # TF child_frame_id
rate_limit: 10.0 # TF rate
gps_rate: 5.0 # GPS data publishing rate
# landing_target
landing_target:
listen_lt: false
mav_frame: "LOCAL_NED"
land_target_type: "VISION_FIDUCIAL"
image:
width: 640 # [pixels]
height: 480
camera:
fov_x: 2.0071286398 # default: 115 [degrees]
fov_y: 2.0071286398
tf:
send: true
listen: false
frame_id: "landing_target"
child_frame_id: "camera_center"
rate_limit: 10.0
target_size: {x: 0.3, y: 0.3}
# mocap_pose_estimate
mocap:
# select mocap source
use_tf: false # ~mocap/tf
use_pose: true # ~mocap/pose
# # mount_control
# mount:
# debounce_s: 4.0
# err_threshold_deg: 10.0
# negate_measured_roll: false
# negate_measured_pitch: false
# negate_measured_yaw: false
# odom
odometry:
fcu:
odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
odom_child_id_des: "base_link" # desired child frame rotation of the FCU's odometry
# # px4flow
# px4flow:
# frame_id: "px4flow"
# ranger_fov: 0.118682 # 6.8 degrees at 5 meters, 31 degrees at 1 meter
# ranger_min_range: 0.3 # meters
# ranger_max_range: 5.0 # meters
# vision_pose_estimate
# Sends VISION_POSITION_ESTIMATE to FCU from PoseStamped topic.
vision_pose:
tf:
listen: false # enable tf listener (disable topic subscribers)
frame_id: "odom"
child_frame_id: "vision_estimate"
rate_limit: 10.0
# vision_speed_estimate
# Sends vision speed estimates to FCU
vision_speed:
listen_twist: true # enable listen to twist topic, else listen to vec3d topic
twist_cov: true # enable listen to twist with covariance topic
# vibration
# Publish VIBRATION message data
vibration:
frame_id: "base_link"
# wheel_odometry
# wheel_odometry:
# count: 2 # number of wheels to compute odometry
# use_rpm: false # use wheel's RPM instead of cumulative distance to compute odometry
# wheel0: {x: 0.0, y: -0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
# wheel1: {x: 0.0, y: 0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
# send_raw: true # send wheel's RPM and cumulative distance (~/wheel_odometry/rpm, ~/wheel_odometry/distance)
# send_twist: false # send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry
# frame_id: "odom" # origin frame
# child_frame_id: "base_link" # body-fixed frame
# vel_error: 0.1 # wheel velocity measurement error 1-std (m/s)
# tf:
# send: false
# frame_id: "odom"
# child_frame_id: "base_link"
# camera
# camera:
# frame_id: "base_link"
# vim:set ts=2 sw=2 et: