PX4-Autopilot/Tools/serial/serial_params.c.jinja

114 lines
3.4 KiB
Django/Jinja

{# jinja template to generate the serial parameters. #}
{% for serial_device in serial_devices -%}
/**
* Serial Configuration for {{ serial_device.label }} Port
*
* Configure what is running on the {{ serial_device.label }} Serial Port.
*
{% for command in commands -%}
* @value {{ command.value }} {{ command.label }}
{% endfor -%}
* @group Serial
* @reboot_required true
*/
PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_CONFIG, {{
serial_ports[serial_device.tag].defaults["CONFIG"]|default(0) }});
/**
* Baudrate for {{ serial_device.label }} Port
*
* Configure the Baudrate for the {{ serial_device.label }} Serial Port.
*
* Certain drivers such as the GPS determine the Baudrate automatically, and
* changing this parameter will have no effect.
*
* @value 0 Auto
* @value 50 50 8N1
* @value 75 75 8N1
* @value 110 110 8N1
* @value 134 134 8N1
* @value 150 150 8N1
* @value 200 200 8N1
* @value 300 300 8N1
* @value 600 600 8N1
* @value 1200 1200 8N1
* @value 1800 1800 8N1
* @value 2400 2400 8N1
* @value 4800 4800 8N1
* @value 9600 9600 8N1
* @value 19200 19200 8N1
* @value 38400 38400 8N1
* @value 57600 57600 8N1
* @value 115200 115200 8N1
* @value 230400 230400 8N1
* @value 460800 460800 8N1
* @value 500000 500000 8N1
* @value 921600 921600 8N1
* @value 1000000 1000000 8N1
* @value 1500000 1500000 8N1
* @value 3000000 3000000 8N1
* @group Serial
* @reboot_required true
*/
PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_BAUD, {{
serial_ports[serial_device.tag].defaults["BAUD"]|default(0) }});
/**
* MAVLink Mode for {{ serial_device.label }} Port
*
* The MAVLink Mode defines the set of streamed messages (for example the
* vehicle's attitude) and their sending rates.
*
* Note: this is only used if the {{ serial_device.label }} Port is configured to run MAVLink.
*
{% for key, value in mavlink_modes.iteritems() -%}
* @value {{ key }} {{ value }}
{% endfor -%}
* @group Serial
* @reboot_required true
*/
PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_MAV_MDE, {{
serial_ports[serial_device.tag].defaults["MAV_MDE"]|default(0) }});
/**
* Maximum MAVLink sending rate for {{ serial_device.label }} Port
*
* 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 <baudrate>/20 is used, which corresponds to
* half of the theoretical maximum bandwidth.
*
* Note: this is only used if the {{ serial_device.label }} Port is configured to run MAVLink.
*
* @min 0
* @unit B/s
* @group Serial
* @reboot_required true
*/
PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_MAV_R, {{
serial_ports[serial_device.tag].defaults["MAV_R"]|default(0) }});
/**
* Enable MAVLink Message forwarding for {{ serial_device.label }} Port
*
* 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).
*
* Note: this is only used if the {{ serial_device.label }} Port is configured to run MAVLink.
*
* @boolean
* @group Serial
* @reboot_required true
*/
PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_MAV_FWD, {{
serial_ports[serial_device.tag].defaults["MAV_FWD"]|default(0) }});
{% endfor %}