forked from Archive/PX4-Autopilot
Tools/serial: use per-module serial port config params, instead of per-port
This commit is contained in:
parent
dc412e4cd5
commit
dae292631c
|
@ -145,6 +145,8 @@ if (NOT EXTERNAL_MODULES_LOCATION STREQUAL "")
|
|||
get_filename_component(EXTERNAL_MODULES_LOCATION "${EXTERNAL_MODULES_LOCATION}" ABSOLUTE)
|
||||
endif()
|
||||
|
||||
set_property(GLOBAL PROPERTY PX4_MODULE_CONFIG_FILES)
|
||||
|
||||
include(platforms/${OS}/cmake/px4_impl_os.cmake)
|
||||
include(configs/${CONFIG})
|
||||
list(APPEND CMAKE_MODULE_PATH ${PX4_SOURCE_DIR}/platforms/${OS}/cmake)
|
||||
|
@ -473,9 +475,12 @@ add_custom_target(metadata_airframes
|
|||
USES_TERMINAL
|
||||
)
|
||||
|
||||
file(GLOB_RECURSE yaml_config_files ${PX4_SOURCE_DIR}/src/modules/*.yaml
|
||||
${PX4_SOURCE_DIR}/src/drivers/*.yaml ${PX4_SOURCE_DIR}/src/lib/*.yaml)
|
||||
add_custom_target(metadata_parameters
|
||||
COMMAND ${CMAKE_COMMAND} -E make_directory ${PX4_BINARY_DIR}/docs
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/serial/generate_config.py --all-ports --params-file ${PX4_SOURCE_DIR}/src/generated_serial_params.c
|
||||
COMMAND ${PYTHON_EXECUTABLE}
|
||||
${PX4_SOURCE_DIR}/Tools/serial/generate_config.py --all-ports --params-file ${PX4_SOURCE_DIR}/src/generated_serial_params.c --config-files ${yaml_config_files}
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/src/lib/parameters/px_process_params.py
|
||||
--src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d`
|
||||
--inject-xml ${PX4_SOURCE_DIR}/src/lib/parameters/parameters_injected.xml
|
||||
|
|
|
@ -73,6 +73,11 @@ add_subdirectory(${romfs_src_dir})
|
|||
# copy all romfs files, process airframes, prune comments
|
||||
get_property(romfs_cmake_files GLOBAL PROPERTY PX4_ROMFS_CMAKE_FILES)
|
||||
get_property(romfs_copy_files GLOBAL PROPERTY PX4_ROMFS_FILES)
|
||||
get_property(module_config_files GLOBAL PROPERTY PX4_MODULE_CONFIG_FILES)
|
||||
file(GLOB jinja_templates ${PX4_SOURCE_DIR}/Tools/serial/*.jinja)
|
||||
if (px4_constrained_flash_build)
|
||||
set(added_arguments --constrained-flash)
|
||||
endif()
|
||||
add_custom_command(OUTPUT ${romfs_gen_root_dir}/init.d/rcS ${romfs_gen_root_dir}/init.d/rc.serial ${romfs_gen_root_dir}/init.d/rc.autostart
|
||||
COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}
|
||||
# TODO: we should only copy the files in ${romfs_copy_files}
|
||||
|
@ -84,11 +89,14 @@ add_custom_command(OUTPUT ${romfs_gen_root_dir}/init.d/rcS ${romfs_gen_root_dir}
|
|||
--start-script ${romfs_gen_root_dir}/init.d/rc.autostart
|
||||
--board ${BOARD}
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/serial/generate_config.py
|
||||
--rc-file ${romfs_temp_dir}/init.d/rc.serial
|
||||
--serial-ports ${board_serial_ports} #--verbose
|
||||
--rc-dir ${romfs_gen_root_dir}/init.d
|
||||
--serial-ports ${board_serial_ports} ${added_arguments}
|
||||
--config-files ${module_config_files} #--verbose
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_romfs_pruner.py
|
||||
--folder ${romfs_gen_root_dir} --board ${BOARD}
|
||||
DEPENDS
|
||||
${jinja_templates}
|
||||
${module_config_files}
|
||||
${romfs_cmake_files}
|
||||
${romfs_copy_files}
|
||||
${PX4_SOURCE_DIR}/Tools/px_process_airframes.py
|
||||
|
|
|
@ -17,12 +17,13 @@ set +e
|
|||
#
|
||||
# UART mapping on FMUv2/3/4:
|
||||
#
|
||||
# UART1 /dev/ttyS0 IO debug (except v4, there ttyS0 is the wifi)
|
||||
# UART1 /dev/ttyS0 IO debug (except v4, there ttyS0 is the wifi,
|
||||
# v4pro: TELEM3)
|
||||
# USART2 /dev/ttyS1 TELEM1 (flow control)
|
||||
# USART3 /dev/ttyS2 TELEM2 (flow control)
|
||||
# UART4
|
||||
# UART7 CONSOLE
|
||||
# UART8 SERIAL4
|
||||
# UART8 /dev/ttyS6 SERIAL4/TELEM4
|
||||
#
|
||||
#------------------------------------------------------------------------------
|
||||
#
|
||||
|
@ -41,8 +42,9 @@ set +e
|
|||
# UART mapping on OMNIBUSF4SD:
|
||||
#
|
||||
# USART1 /dev/ttyS0 SerialRX
|
||||
# USART4 /dev/ttyS1 TELEM1
|
||||
# USART6 /dev/ttyS2 GPS
|
||||
# (USART3 configured as I2C)
|
||||
# USART4 /dev/ttyS1 TELEM2 (TX=RSSI, RX=PWM out 5)
|
||||
# USART6 /dev/ttyS2 URT6
|
||||
#
|
||||
|
||||
#------------------------------------------------------------------------------
|
||||
|
|
|
@ -9,154 +9,73 @@ import sys
|
|||
|
||||
from jinja2 import Environment, FileSystemLoader
|
||||
|
||||
try:
|
||||
import yaml
|
||||
except:
|
||||
print("Failed to import yaml.")
|
||||
print("You may need to install it with 'sudo pip install pyyaml'")
|
||||
print("")
|
||||
raise
|
||||
|
||||
|
||||
## Configuration
|
||||
|
||||
# All possible Serial ports and their default param values.
|
||||
# Omitted default values will be set to 0.
|
||||
# All possible Serial ports
|
||||
# Note: do not re-use or change indexes. When adding a port, always use an
|
||||
# index that has never been used before. This is important for compatibility
|
||||
# with QGC (parameter metadata)
|
||||
serial_ports = {
|
||||
"GPS1": {
|
||||
"label": "GPS 1",
|
||||
"defaults": {
|
||||
"CONFIG": 'Main GPS',
|
||||
"BAUD": 0,
|
||||
},
|
||||
},
|
||||
"GPS2": {
|
||||
"label": "GPS 2",
|
||||
"defaults": {
|
||||
"CONFIG": 'Disabled',
|
||||
"BAUD": 0,
|
||||
},
|
||||
},
|
||||
"TEL1": {
|
||||
# index 0 means disabled
|
||||
"TEL1": { # telemetry link
|
||||
"label": "TELEM 1",
|
||||
"defaults": {
|
||||
"CONFIG": 'MAVLink',
|
||||
"BAUD": 57600,
|
||||
"MAV_MDE": 'Normal',
|
||||
"MAV_R": 1200,
|
||||
"MAV_FWD": 1,
|
||||
},
|
||||
"index": 1,
|
||||
"default_baudrate": 57600,
|
||||
},
|
||||
"TEL2": { # companion port
|
||||
"label": "TELEM 2",
|
||||
"defaults": {
|
||||
"CONFIG": 'Disabled', # disabled by default to reduce RAM usage
|
||||
"BAUD": 57600,
|
||||
"MAV_MDE": 'OSD',
|
||||
},
|
||||
"index": 2,
|
||||
"default_baudrate": 921600,
|
||||
},
|
||||
"TEL3": {
|
||||
"label": "TELEM 3",
|
||||
"defaults": {
|
||||
"CONFIG": 'Disabled',
|
||||
"BAUD": 57600,
|
||||
"MAV_MDE": 'Normal',
|
||||
},
|
||||
"index": 3,
|
||||
"default_baudrate": 57600,
|
||||
},
|
||||
"TEL4": {
|
||||
"label": "TELEM 4",
|
||||
"defaults": {
|
||||
"CONFIG": 'MAVLink',
|
||||
"BAUD": 57600,
|
||||
"MAV_MDE": 'Normal',
|
||||
"MAV_R": 1200,
|
||||
},
|
||||
"label": "TELEM/SERIAL 4",
|
||||
"index": 4,
|
||||
"default_baudrate": 57600,
|
||||
},
|
||||
"URT3": { # for Omnibus
|
||||
"label": "UART 3",
|
||||
"defaults": {
|
||||
"CONFIG": 'MAVLink',
|
||||
"BAUD": 57600,
|
||||
"MAV_MDE": 'Normal',
|
||||
"MAV_R": 1200,
|
||||
"MAV_FWD": 1,
|
||||
},
|
||||
"GPS1": {
|
||||
"label": "GPS 1",
|
||||
"index": 5,
|
||||
"default_baudrate": 0,
|
||||
},
|
||||
"GPS2": {
|
||||
"label": "GPS 2",
|
||||
"index": 6,
|
||||
"default_baudrate": 0,
|
||||
},
|
||||
"URT6": { # for Omnibus
|
||||
"label": "UART 6",
|
||||
"defaults": {
|
||||
"CONFIG": 'Main GPS',
|
||||
"BAUD": 0,
|
||||
},
|
||||
"index": 7,
|
||||
"default_baudrate": 0,
|
||||
},
|
||||
}
|
||||
|
||||
# Serial commands: each dict entry is a list with 2 items:
|
||||
# - user-facing label (must be short, will be shown in a drop-down list)
|
||||
# - ROMFS command (can be more than one or any scripting logic).
|
||||
# These variables can be used:
|
||||
# ${SER_DEV} Serial device (e.g. /dev/ttyS1)
|
||||
# ${SER_TAG} Serial tag (e.g. GPS1)
|
||||
# SER_${SER_TAG}_CONFIG Param name for the current configuration
|
||||
# SER_${SER_TAG}_BAUD Param name for the current baudrate
|
||||
# SER_${SER_TAG}_MAV_MDE Param name for the current mavlink mode
|
||||
# SER_${SER_TAG}_MAV_R Param name for the current mavlink rate
|
||||
# SER_${SER_TAG}_MAV_FWD Param name for current mavlink forwarding
|
||||
# ${DUAL_GPS_ARGS} Arguments passed to the gps to start the secondary GPS
|
||||
# ${MAV_ARGS} Mavlink arguments (baudrate, mode and rate)
|
||||
#
|
||||
# Note: do NOT re-use or change indexes. When adding a command, always use an
|
||||
# index that has never been used before. This is important for compatibility
|
||||
# with QGC
|
||||
serial_commands = {
|
||||
0: ["Disabled", ""],
|
||||
|
||||
# MAVLink & RTPS
|
||||
1: ["MAVLink", "mavlink start -d ${SER_DEV} ${MAV_ARGS} -x"],
|
||||
|
||||
2: ["MAVLink over Syslink", '''
|
||||
syslink start
|
||||
mavlink start -d /dev/bridge0 ${MAV_ARGS}
|
||||
'''],
|
||||
|
||||
3: ["MAVLink over Iridium", '''
|
||||
iridiumsbd start -d ${SER_DEV}
|
||||
mavlink start -d /dev/iridium -b 19200 -m iridium -r 10
|
||||
'''],
|
||||
|
||||
4: ["MAVLink + FastRTPS", '''
|
||||
protocol_splitter start ${SER_DEV}
|
||||
mavlink start -d /dev/mavlink ${MAV_ARGS} -x
|
||||
micrortps_client start -d /dev/rtps -b p:SER_${SER_TAG}_BAUD -l -1
|
||||
'''],
|
||||
5: ["FastRTPS", "micrortps_client start -d ${SER_DEV} -b p:SER_${SER_TAG}_BAUD -l -1"],
|
||||
|
||||
# GPS
|
||||
50: ["Main GPS", "gps start -d ${SER_DEV} ${DUAL_GPS_ARGS}"],
|
||||
51: ["Secondary GPS", ""], # special handling for the command
|
||||
|
||||
# Telemetry
|
||||
100: ["FrSky Telemetry", "frsky_telemetry start -d ${SER_DEV}"],
|
||||
101: ["HoTT Telemetry", "hott_telemetry start -d ${SER_DEV}"],
|
||||
|
||||
# Sensor drivers
|
||||
200: ["LeddarOne Rangefinder", "leddar_one start -d ${SER_DEV}"],
|
||||
201: ["Benewake TFmini Rangefinder", "tfmini start -d ${SER_DEV}"],
|
||||
202: ["Lightware Laser Rangefinder", "sf0x start -d ${SER_DEV}"],
|
||||
}
|
||||
|
||||
mavlink_modes = {
|
||||
0: "Normal",
|
||||
1: "Custom",
|
||||
2: "Onboard",
|
||||
3: "OSD",
|
||||
4: "Magic",
|
||||
5: "Config",
|
||||
6: "Iridium",
|
||||
7: "Minimal",
|
||||
}
|
||||
|
||||
parser = argparse.ArgumentParser(description='Generate Serial params & startup script')
|
||||
|
||||
parser.add_argument('--serial-ports', type=str, nargs='*', metavar="TAG:DEVICE",
|
||||
default=[],
|
||||
help='Serial ports: mappings from the tag name to the device (e.g. GPS1:/dev/ttyS1)')
|
||||
parser.add_argument('--config-files', type=str, nargs='*', default=[],
|
||||
help='YAML module config file(s)')
|
||||
parser.add_argument('--all-ports', action='store_true',
|
||||
help='Generate output for all known ports (params file only)')
|
||||
parser.add_argument('--rc-file', type=str, action='store',
|
||||
help='ROMFS output script', default=None)
|
||||
parser.add_argument('--constrained-flash', action='store_true',
|
||||
help='Reduce verbosity in ROMFS scripts to reduce flash size')
|
||||
parser.add_argument('--rc-dir', type=str, action='store',
|
||||
help='ROMFS output directory', default=None)
|
||||
parser.add_argument('--params-file', type=str, action='store',
|
||||
help='Parameter output file', default=None)
|
||||
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
|
||||
|
@ -166,11 +85,13 @@ args = parser.parse_args()
|
|||
|
||||
arg_board_serial_ports = args.serial_ports
|
||||
verbose = args.verbose
|
||||
rc_serial_output_file = args.rc_file
|
||||
rc_serial_output_dir = args.rc_dir
|
||||
rc_serial_template = 'rc.serial.jinja'
|
||||
rc_serial_port_template = 'rc.serial_port.jinja'
|
||||
serial_params_output_file = args.params_file
|
||||
serial_params_template = 'serial_params.c.jinja'
|
||||
generate_for_all_ports = args.all_ports
|
||||
constrained_flash = args.constrained_flash
|
||||
|
||||
if generate_for_all_ports:
|
||||
board_ports = [(key, "") for key in serial_ports]
|
||||
|
@ -179,28 +100,109 @@ else:
|
|||
board_ports = [tuple(port.split(":")) for port in arg_board_serial_ports]
|
||||
|
||||
|
||||
if rc_serial_output_file is None and serial_params_output_file is None:
|
||||
raise Exception("At least one of --rc-file (e.g. rc.serial) or --params-file "
|
||||
if rc_serial_output_dir is None and serial_params_output_file is None:
|
||||
raise Exception("At least one of --rc-dir or --params-file "
|
||||
"(e.g. serial_params.c) needs to be specified")
|
||||
|
||||
|
||||
# replace strings in defaults with their numerical value
|
||||
for key in serial_ports:
|
||||
defaults = serial_ports[key]["defaults"]
|
||||
# parse the YAML files
|
||||
serial_commands = []
|
||||
additional_params = ""
|
||||
|
||||
if "CONFIG" in defaults and isinstance(defaults["CONFIG"], str):
|
||||
config_index_list = [ key for key in serial_commands \
|
||||
if serial_commands[key][0] == defaults["CONFIG"]]
|
||||
if len(config_index_list) == 0:
|
||||
raise Exception("Config mode {:} not found".format(defaults["CONFIG"]))
|
||||
defaults["CONFIG"] = config_index_list[0]
|
||||
def parse_yaml_serial_config(yaml_config):
|
||||
""" parse the serial_config section from the yaml config file """
|
||||
if 'serial_config' not in yaml_config:
|
||||
return []
|
||||
ret = []
|
||||
module_name = yaml_config['module_name']
|
||||
for serial_config in yaml_config['serial_config']:
|
||||
if 'label' not in serial_config:
|
||||
serial_config['label'] = module_name
|
||||
ret.append(serial_config)
|
||||
return ret
|
||||
|
||||
if "MAV_MDE" in defaults and isinstance(defaults["MAV_MDE"], str):
|
||||
mode_index_list = [ key for key in mavlink_modes \
|
||||
if mavlink_modes[key] == defaults["MAV_MDE"]]
|
||||
if len(mode_index_list) == 0:
|
||||
raise Exception("Mavlink mode {:} not found".format(defaults["MAV_MDE"]))
|
||||
defaults["MAV_MDE"] = mode_index_list[0]
|
||||
def parse_yaml_parameters_config(yaml_config):
|
||||
""" parse the parameters section from the yaml config file """
|
||||
if 'parameters' not in yaml_config:
|
||||
return ''
|
||||
parameters_section_list = yaml_config['parameters']
|
||||
for parameters_section in parameters_section_list:
|
||||
if 'definitions' not in parameters_section:
|
||||
return ''
|
||||
definitions = parameters_section['definitions']
|
||||
ret = ''
|
||||
param_group = parameters_section.get('group', None)
|
||||
for param_name in definitions:
|
||||
param = definitions[param_name]
|
||||
num_instances = param.get('num_instances', 1)
|
||||
instance_start = param.get('instance_start', 0) # offset
|
||||
|
||||
# get the type and extract all tags
|
||||
tags = '@group {:}'.format(param_group)
|
||||
if param['type'] == 'enum':
|
||||
param_type = 'INT32'
|
||||
for key in param['values']:
|
||||
tags += '\n * @value {:} {:}'.format(key, param['values'][key])
|
||||
elif param['type'] == 'boolean':
|
||||
param_type = 'INT32'
|
||||
tags += '\n * @boolean'
|
||||
elif param['type'] == 'int32':
|
||||
param_type = 'INT32'
|
||||
elif param['type'] == 'float':
|
||||
param_type = 'FLOAT'
|
||||
else:
|
||||
raise Exception("unknown param type {:}".format(param['type']))
|
||||
|
||||
for tag in ['decimal', 'increment', 'category', 'volatile', 'bit',
|
||||
'min', 'max', 'unit', 'reboot_required']:
|
||||
if tag in param:
|
||||
tags += '\n * @{:} {:}'.format(tag, param[tag])
|
||||
|
||||
for i in range(num_instances):
|
||||
# default value
|
||||
default_value = 0
|
||||
if 'default' in param:
|
||||
# default can be a list of num_instances or a single value
|
||||
if type(param['default']) == list:
|
||||
assert len(param['default']) == num_instances
|
||||
default_value = param['default'][i]
|
||||
else:
|
||||
default_value = param['default']
|
||||
|
||||
if type(default_value) == bool:
|
||||
default_value = int(default_value)
|
||||
|
||||
# output the existing C-style format
|
||||
ret += '''
|
||||
/**
|
||||
* {short_descr}
|
||||
*
|
||||
* {long_descr}
|
||||
*
|
||||
* {tags}
|
||||
*/
|
||||
PARAM_DEFINE_{param_type}({name}, {default_value});
|
||||
'''.format(short_descr=param['description']['short'].replace("\n", "\n * "),
|
||||
long_descr=param['description']['long'].replace("\n", "\n * "),
|
||||
tags=tags,
|
||||
param_type=param_type,
|
||||
name=param_name,
|
||||
default_value=default_value,
|
||||
).replace('${i}', str(i+instance_start))
|
||||
return ret
|
||||
|
||||
for yaml_file in args.config_files:
|
||||
with open(yaml_file, 'r') as stream:
|
||||
try:
|
||||
yaml_config = yaml.load(stream)
|
||||
serial_commands.extend(parse_yaml_serial_config(yaml_config))
|
||||
|
||||
# TODO: additional params should be parsed in a separate script
|
||||
additional_params += parse_yaml_parameters_config(yaml_config)
|
||||
|
||||
except yaml.YAMLError as exc:
|
||||
print(exc)
|
||||
raise
|
||||
|
||||
|
||||
# sanity check (makes sure the param names don't exceed the max length of 16 chars)
|
||||
|
@ -217,23 +219,41 @@ for tag, device in board_ports:
|
|||
serial_devices.append({
|
||||
'tag': tag,
|
||||
'device': device,
|
||||
'label': serial_ports[tag]["label"]
|
||||
'label': serial_ports[tag]["label"],
|
||||
'index': serial_ports[tag]["index"],
|
||||
'default_baudrate': serial_ports[tag]["default_baudrate"]
|
||||
})
|
||||
|
||||
|
||||
# construct commands based on selected board
|
||||
commands = []
|
||||
disabled_commands = [] # e.g. ["HoTT Telemetry"] TODO: do we need support for that and configure it from the board config?
|
||||
for key in serial_commands:
|
||||
if serial_commands[key][0] in disabled_commands:
|
||||
continue
|
||||
label = serial_commands[key][0]
|
||||
command = serial_commands[key][1]
|
||||
commands.append({
|
||||
'value': key,
|
||||
'command': command,
|
||||
'label': label
|
||||
})
|
||||
for serial_command in serial_commands:
|
||||
num_instances = serial_command.get('num_instances', 1)
|
||||
# TODO: use a loop in the script instead of explicitly enumerating all instances
|
||||
for i in range(num_instances):
|
||||
port_config = serial_command['port_config_param']
|
||||
port_param_name = port_config['name'].replace('${i}', str(i))
|
||||
default_port = 0 # disabled
|
||||
if 'default' in port_config:
|
||||
if type(port_config['default']) == list:
|
||||
assert len(port_config['default']) == num_instances
|
||||
default_port_str = port_config['default'][i]
|
||||
else:
|
||||
default_port_str = port_config['default']
|
||||
if default_port_str != "":
|
||||
if default_port_str not in serial_ports:
|
||||
raise Exception("Default Port {:} not found for {:}".format(default_port_str, serial_command['label']))
|
||||
default_port = serial_ports[default_port_str]['index']
|
||||
|
||||
commands.append({
|
||||
'command': serial_command['command'],
|
||||
'label': serial_command['label'],
|
||||
'instance': i,
|
||||
'multi_instance': num_instances > 1,
|
||||
'port_param_name': port_param_name,
|
||||
'default_port': default_port,
|
||||
'param_group': port_config['group']
|
||||
})
|
||||
|
||||
if verbose:
|
||||
print("Serial Devices: {:}".format(serial_devices))
|
||||
|
@ -244,9 +264,11 @@ jinja_env = Environment(loader=FileSystemLoader(
|
|||
os.path.dirname(os.path.realpath(__file__))))
|
||||
|
||||
# generate the ROMFS script using a jinja template
|
||||
if rc_serial_output_file is not None:
|
||||
if rc_serial_output_dir is not None:
|
||||
if generate_for_all_ports:
|
||||
raise Exception("Cannot create rc file for --all-ports")
|
||||
rc_serial_output_file = os.path.join(rc_serial_output_dir, "rc.serial")
|
||||
rc_serial_port_output_file = os.path.join(rc_serial_output_dir, "rc.serial_port")
|
||||
|
||||
if verbose: print("Generating {:}".format(rc_serial_output_file))
|
||||
if len(serial_devices) == 0:
|
||||
|
@ -255,13 +277,15 @@ if rc_serial_output_file is not None:
|
|||
else:
|
||||
template = jinja_env.get_template(rc_serial_template)
|
||||
with open(rc_serial_output_file, 'w') as fid:
|
||||
secondary_gps_value = 51
|
||||
# sanity-check
|
||||
if serial_commands[secondary_gps_value][0] != "Secondary GPS":
|
||||
raise Exception("Unexpected value for Secondary GPS")
|
||||
fid.write(template.render(serial_devices=serial_devices,
|
||||
secondary_gps_value=secondary_gps_value,
|
||||
commands=commands))
|
||||
commands=commands,
|
||||
constrained_flash=constrained_flash))
|
||||
|
||||
if verbose: print("Generating {:}".format(rc_serial_port_output_file))
|
||||
template = jinja_env.get_template(rc_serial_port_template)
|
||||
with open(rc_serial_port_output_file, 'w') as fid:
|
||||
fid.write(template.render(serial_devices=serial_devices,
|
||||
constrained_flash=constrained_flash))
|
||||
|
||||
# parameter definitions
|
||||
if serial_params_output_file is not None:
|
||||
|
@ -269,6 +293,6 @@ if serial_params_output_file is not None:
|
|||
template = jinja_env.get_template(serial_params_template)
|
||||
with open(serial_params_output_file, 'w') as fid:
|
||||
fid.write(template.render(serial_devices=serial_devices,
|
||||
commands=commands, mavlink_modes=mavlink_modes,
|
||||
serial_ports=serial_ports))
|
||||
commands=commands, serial_ports=serial_ports,
|
||||
additional_definitions=additional_params))
|
||||
|
||||
|
|
|
@ -3,84 +3,33 @@
|
|||
# serial autostart script generated with generate_serial_config.py
|
||||
|
||||
|
||||
# set dual gps args
|
||||
set DUAL_GPS_ARGS ""
|
||||
set SER_TAG {{ serial_devices[0].tag }}
|
||||
set SER_DEV {{ serial_devices[0].device }}
|
||||
while [ ${SER_TAG} != exit ]
|
||||
do
|
||||
if param compare SER_${SER_TAG}_CONFIG {{ secondary_gps_value }}
|
||||
then
|
||||
set DUAL_GPS_ARGS "-e ${SER_DEV}"
|
||||
echo "Starting Secondary GPS on ${SER_DEV} (${SER_TAG})"
|
||||
fi
|
||||
# make sure all baudrates are marked as used
|
||||
param touch
|
||||
{%- for serial_device in serial_devices %} SER_{{ serial_device.tag }}_BAUD
|
||||
{%- endfor %}
|
||||
|
||||
# loop iteration
|
||||
{# need to iterate in reversed order -#}
|
||||
{% set last = serial_devices|last -%}
|
||||
if [ ${SER_TAG} == {{ last.tag }} ]
|
||||
then
|
||||
set SER_TAG exit
|
||||
fi
|
||||
{% for serial_device in serial_devices | reverse -%}
|
||||
{% if not loop.first -%}
|
||||
{% set next = loop.previtem -%}
|
||||
if [ ${SER_TAG} == {{ serial_device.tag }} ]
|
||||
then
|
||||
set SER_TAG {{ next.tag }}
|
||||
set SER_DEV {{ next.device }}
|
||||
fi
|
||||
{% endif -%}
|
||||
{% endfor %}
|
||||
done
|
||||
set PRT_F /etc/init.d/rc.serial_port
|
||||
|
||||
# start the devices on the configured ports
|
||||
set SER_TAG {{ serial_devices[0].tag }}
|
||||
set SER_DEV {{ serial_devices[0].device }}
|
||||
while [ ${SER_TAG} != exit ]
|
||||
do
|
||||
# Access all params so that they're sent to a GCS upon param loading
|
||||
param touch SER_${SER_TAG}_BAUD SER_${SER_TAG}_MAV_MDE SER_${SER_TAG}_MAV_R SER_${SER_TAG}_MAV_FWD
|
||||
{% for command in commands -%}
|
||||
set PRT {{ command.port_param_name }}
|
||||
{% if command.multi_instance -%}
|
||||
set i {{ command.instance }}
|
||||
{% endif -%}
|
||||
# get the device & baudrate
|
||||
sh $PRT_F
|
||||
if [ $SERIAL_DEV != none ]
|
||||
then
|
||||
{% if not constrained_flash -%}
|
||||
echo "Starting {{ command.label }} on $SERIAL_DEV"
|
||||
{% endif -%}
|
||||
{{ command.command }}
|
||||
fi
|
||||
|
||||
# initialize params
|
||||
set MAV_ARGS "-b p:SER_${SER_TAG}_BAUD -m p:SER_${SER_TAG}_MAV_MDE -r p:SER_${SER_TAG}_MAV_R"
|
||||
if param compare SER_${SER_TAG}_MAV_FWD 1
|
||||
then
|
||||
set MAV_ARGS "${MAV_ARGS} -f"
|
||||
fi
|
||||
{% endfor %}
|
||||
|
||||
# start commands
|
||||
{% for command in commands -%}
|
||||
{% if command.command | length > 0 -%}
|
||||
if param compare SER_${SER_TAG}_CONFIG {{ command.value }}
|
||||
then
|
||||
{# the echo can be disabled if too verbose... -#}
|
||||
echo "Starting {{ command.label }} on ${SER_DEV} (${SER_TAG})"
|
||||
{{ command.command }}
|
||||
fi
|
||||
{% endif -%}
|
||||
{% endfor %}
|
||||
unset i
|
||||
unset SERIAL_DEV
|
||||
unset PRT
|
||||
unset PRT_F
|
||||
unset BAUD_PARAM
|
||||
|
||||
# loop iteration
|
||||
{# need to iterate in reversed order -#}
|
||||
{% set last = serial_devices|last -%}
|
||||
if [ ${SER_TAG} == {{ last.tag }} ]
|
||||
then
|
||||
set SER_TAG exit
|
||||
fi
|
||||
{% for serial_device in serial_devices | reverse -%}
|
||||
{% if not loop.first -%}
|
||||
{% set next = loop.previtem -%}
|
||||
if [ ${SER_TAG} == {{ serial_device.tag }} ]
|
||||
then
|
||||
set SER_TAG {{ next.tag }}
|
||||
set SER_DEV {{ next.device }}
|
||||
fi
|
||||
{% endif -%}
|
||||
{% endfor %}
|
||||
done
|
||||
|
||||
unset DUAL_GPS_ARGS
|
||||
unset SER_TAG
|
||||
unset SER_DEV
|
||||
unset MAV_ARGS
|
||||
|
|
|
@ -0,0 +1,21 @@
|
|||
{# jinja template to generate the serial port rc.uart_port script. #}
|
||||
|
||||
# serial port script generated with generate_serial_config.py
|
||||
|
||||
set SERIAL_DEV none
|
||||
{% for serial_device in serial_devices -%}
|
||||
if param compare "$PRT" {{ serial_device.index }}
|
||||
then
|
||||
if [ "x$PRT_{{ serial_device.tag }}_" == "x" ]
|
||||
then
|
||||
set SERIAL_DEV {{ serial_device.device }}
|
||||
set BAUD_PARAM SER_{{ serial_device.tag }}_BAUD
|
||||
set PRT_{{ serial_device.tag }}_ 1
|
||||
{% if not constrained_flash -%}
|
||||
else
|
||||
echo "Conflicting config for {{ serial_device.device }}"
|
||||
{% endif -%}
|
||||
fi
|
||||
fi
|
||||
|
||||
{% endfor %}
|
|
@ -2,27 +2,13 @@
|
|||
|
||||
|
||||
{% 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
|
||||
* Baudrate for the {{ serial_device.label }} Serial 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.
|
||||
* Note: certain drivers such as the GPS can determine the Baudrate automatically.
|
||||
*
|
||||
* @value 0 Auto
|
||||
* @value 50 50 8N1
|
||||
|
@ -48,66 +34,35 @@ PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_CONFIG, {{
|
|||
* @value 921600 921600 8N1
|
||||
* @value 1000000 1000000 8N1
|
||||
* @value 1500000 1500000 8N1
|
||||
* @value 2000000 2000000 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) }});
|
||||
PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_BAUD, {{ serial_device.default_baudrate }});
|
||||
|
||||
{% endfor %}
|
||||
|
||||
|
||||
{%- if serial_devices|length > 0 %}
|
||||
{% for command in commands -%}
|
||||
/**
|
||||
* Serial Configuration for {{ command.label }}
|
||||
{%- if command.multi_instance %} (instance {{ command.instance }}){% endif %}
|
||||
*
|
||||
* Configure on which serial port to run {{ command.label }}.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
{% for serial_device in serial_devices -%}
|
||||
* @value {{ serial_device.index }} {{ serial_device.label }}
|
||||
{% endfor -%}
|
||||
* @group {{ command.param_group }}
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32({{ command.port_param_name }}, {{ command.default_port }});
|
||||
|
||||
{% endfor -%}
|
||||
{% endif %}
|
||||
|
||||
{{ additional_definitions }}
|
||||
|
||||
|
|
|
@ -160,6 +160,8 @@ endfunction()
|
|||
# [ COMPILE_FLAGS <list> ]
|
||||
# [ INCLUDES <list> ]
|
||||
# [ DEPENDS <string> ]
|
||||
# [ SRCS <list> ]
|
||||
# [ MODULE_CONFIG <list> ]
|
||||
# [ EXTERNAL ]
|
||||
# )
|
||||
#
|
||||
|
@ -172,6 +174,7 @@ endfunction()
|
|||
# COMPILE_FLAGS : compile flags
|
||||
# LINK_FLAGS : link flags
|
||||
# SRCS : source files
|
||||
# MODULE_CONFIG : yaml config file(s)
|
||||
# INCLUDES : include directories
|
||||
# DEPENDS : targets which this module depends on
|
||||
# EXTERNAL : flag to indicate that this module is out-of-tree
|
||||
|
@ -194,7 +197,7 @@ function(px4_add_module)
|
|||
px4_parse_function_args(
|
||||
NAME px4_add_module
|
||||
ONE_VALUE MODULE MAIN STACK STACK_MAIN STACK_MAX PRIORITY
|
||||
MULTI_VALUE COMPILE_FLAGS LINK_FLAGS SRCS INCLUDES DEPENDS
|
||||
MULTI_VALUE COMPILE_FLAGS LINK_FLAGS SRCS INCLUDES DEPENDS MODULE_CONFIG
|
||||
OPTIONS EXTERNAL UNITY_BUILD
|
||||
REQUIRED MODULE MAIN
|
||||
ARGN ${ARGN})
|
||||
|
@ -306,6 +309,12 @@ function(px4_add_module)
|
|||
set_target_properties(${MODULE} PROPERTIES ${prop} ${${prop}})
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
if(MODULE_CONFIG)
|
||||
foreach(module_config ${MODULE_CONFIG})
|
||||
set_property(GLOBAL APPEND PROPERTY PX4_MODULE_CONFIG_FILES ${CMAKE_CURRENT_SOURCE_DIR}/${module_config})
|
||||
endforeach()
|
||||
endif()
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
|
|
|
@ -7,6 +7,8 @@ set(board_serial_ports
|
|||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS6)
|
||||
|
||||
set(px4_constrained_flash_build 1)
|
||||
|
||||
#set(config_uavcan_num_ifaces 2)
|
||||
|
||||
set(config_bl_file ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/extras/px4fmuv3_bl.bin)
|
||||
|
|
|
@ -71,12 +71,19 @@ list(REMOVE_DUPLICATES module_list)
|
|||
get_property(module_config_files GLOBAL PROPERTY PX4_MODULE_CONFIG_FILES)
|
||||
set(generated_params_dir ${PX4_BINARY_DIR}/generated_params)
|
||||
set(generated_serial_params_file ${generated_params_dir}/serial_params.c)
|
||||
file(GLOB jinja_templates ${PX4_SOURCE_DIR}/Tools/serial/*.jinja)
|
||||
if (px4_constrained_flash_build)
|
||||
set(added_arguments --constrained-flash)
|
||||
endif()
|
||||
add_custom_command(OUTPUT ${generated_serial_params_file}
|
||||
COMMAND ${CMAKE_COMMAND} -E make_directory ${generated_params_dir}
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/serial/generate_config.py
|
||||
--params-file ${generated_serial_params_file}
|
||||
--serial-ports ${board_serial_ports} #--verbose
|
||||
--serial-ports ${board_serial_ports} ${added_arguments}
|
||||
--config-files ${module_config_files} #--verbose
|
||||
DEPENDS
|
||||
${module_config_files}
|
||||
${jinja_templates}
|
||||
${PX4_SOURCE_DIR}/Tools/serial/generate_config.py
|
||||
COMMENT "Generating serial_params.c"
|
||||
)
|
||||
|
|
Loading…
Reference in New Issue