mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
156 lines
5.7 KiB
YAML
156 lines
5.7 KiB
YAML
__max_num_config_instances: &max_num_config_instances 3
|
|
|
|
module_name: MAVLink
|
|
serial_config:
|
|
- command: |
|
|
if [ $SERIAL_DEV != ethernet ]; then
|
|
set MAV_ARGS "-d ${SERIAL_DEV} -b p:${BAUD_PARAM} -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE"
|
|
else
|
|
set MAV_ARGS "-u p:MAV_${i}_UDP_PRT -o p:MAV_${i}_REMOTE_PRT -m p:MAV_${i}_MODE -r p:MAV_${i}_RATE"
|
|
if param compare MAV_${i}_BROADCAST 1
|
|
then
|
|
set MAV_ARGS "${MAV_ARGS} -p"
|
|
fi
|
|
if param compare MAV_${i}_BROADCAST 2
|
|
then
|
|
set MAV_ARGS "${MAV_ARGS} -c"
|
|
fi
|
|
fi
|
|
if param compare MAV_${i}_FORWARD 1
|
|
then
|
|
set MAV_ARGS "${MAV_ARGS} -f"
|
|
fi
|
|
if param compare MAV_${i}_RADIO_CTL 1
|
|
then
|
|
set MAV_ARGS "${MAV_ARGS} -s"
|
|
fi
|
|
mavlink start ${MAV_ARGS} -x
|
|
port_config_param:
|
|
name: MAV_${i}_CONFIG
|
|
group: MAVLink
|
|
# MAVLink instances:
|
|
# 0: Telem1 Port (Telemetry Link)
|
|
# 1: Telem2 Port (Companion Link). Disabled by default to reduce RAM usage
|
|
# 2: Board-specific / no fixed function or port
|
|
default: [TEL1, "", ""]
|
|
num_instances: *max_num_config_instances
|
|
supports_networking: true
|
|
|
|
parameters:
|
|
- group: MAVLink
|
|
definitions:
|
|
MAV_${i}_MODE:
|
|
description:
|
|
short: MAVLink Mode for instance ${i}
|
|
long: |
|
|
The MAVLink Mode defines the set of streamed messages (for example the
|
|
vehicle's attitude) and their sending rates.
|
|
|
|
type: enum
|
|
values:
|
|
0: Normal
|
|
1: Custom
|
|
2: Onboard
|
|
3: OSD
|
|
4: Magic
|
|
5: Config
|
|
#6: Iridium # as the user does not need to configure this, hide it from the UI
|
|
7: Minimal
|
|
8: External Vision
|
|
#9: External Vision Minimal # hidden
|
|
10: Gimbal
|
|
11: Onboard Low Bandwidth
|
|
reboot_required: true
|
|
num_instances: *max_num_config_instances
|
|
default: [0, 2, 0]
|
|
|
|
MAV_${i}_RATE:
|
|
description:
|
|
short: Maximum MAVLink sending rate for instance ${i}
|
|
long: |
|
|
Configure the maximum sending rate for the MAVLink streams in Bytes/sec.
|
|
If the configured streams exceed the maximum rate, the sending rate of
|
|
each stream is automatically decreased.
|
|
|
|
If this is set to 0 a value of half of the theoretical maximum bandwidth is used.
|
|
This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on
|
|
8N1-configured links).
|
|
|
|
type: int32
|
|
min: 0
|
|
unit: B/s
|
|
reboot_required: true
|
|
num_instances: *max_num_config_instances
|
|
default: [1200, 0, 0]
|
|
|
|
MAV_${i}_FORWARD:
|
|
description:
|
|
short: Enable MAVLink Message forwarding for instance ${i}
|
|
long: |
|
|
If enabled, forward incoming MAVLink messages to other MAVLink ports if the
|
|
message is either broadcast or the target is not the autopilot.
|
|
|
|
This allows for example a GCS to talk to a camera that is connected to the
|
|
autopilot via MAVLink (on a different link than the GCS).
|
|
|
|
type: boolean
|
|
reboot_required: true
|
|
num_instances: *max_num_config_instances
|
|
default: [true, false, false]
|
|
|
|
MAV_${i}_RADIO_CTL:
|
|
description:
|
|
short: Enable software throttling of mavlink on instance ${i}
|
|
long: |
|
|
If enabled, MAVLink messages will be throttled according to
|
|
`txbuf` field reported by radio_status.
|
|
|
|
Requires a radio to send the mavlink message RADIO_STATUS.
|
|
|
|
type: boolean
|
|
reboot_required: true
|
|
num_instances: *max_num_config_instances
|
|
default: [true, true, true]
|
|
|
|
MAV_${i}_UDP_PRT:
|
|
description:
|
|
short: MAVLink Network Port for instance ${i}
|
|
long: |
|
|
If ethernet enabled and selected as configuration for MAVLink instance ${i},
|
|
selected udp port will be set and used in MAVLink instance ${i}.
|
|
|
|
type: int32
|
|
reboot_required: true
|
|
num_instances: *max_num_config_instances
|
|
default: [14556, 0, 0]
|
|
requires_ethernet: true
|
|
|
|
MAV_${i}_REMOTE_PRT:
|
|
description:
|
|
short: MAVLink Remote Port for instance ${i}
|
|
long: |
|
|
If ethernet enabled and selected as configuration for MAVLink instance ${i},
|
|
selected remote port will be set and used in MAVLink instance ${i}.
|
|
|
|
type: int32
|
|
reboot_required: true
|
|
num_instances: *max_num_config_instances
|
|
default: [14550, 0, 0]
|
|
requires_ethernet: true
|
|
|
|
MAV_${i}_BROADCAST:
|
|
description:
|
|
short: Broadcast heartbeats on local network for MAVLink instance ${i}
|
|
long: |
|
|
This allows a ground control station to automatically find the drone
|
|
on the local network.
|
|
|
|
type: enum
|
|
values:
|
|
0: Never broadcast
|
|
1: Always broadcast
|
|
2: Only multicast
|
|
num_instances: *max_num_config_instances
|
|
default: [1, 0, 0]
|
|
requires_ethernet: true
|