params: add script to parse timer_config.cpp for timer group info

This allows to generate pwm params in the form of:
module_name: PWM Output
actuator_output:
  output_groups:
    - generator: pwm
      param_prefix: PWM_FMU
      channel_labels: ['PWM Main', 'PWM Capture']
      standard_params:
        disarmed: { min: 800, max: 2200, default: 900 }
        min: { min: 800, max: 1400, default: 1000 }
        max: { min: 1600, max: 2200, default: 2000 }
        failsafe: { min: 800, max: 2200 }
      extra_function_groups: [ pwm_fmu ]
      pwm_timer_param:
        description:
            short: Output Protocol Configuration for ${label}
            long: |
                Select which Output Protocol to use for outputs ${label}.

                Custom PWM rates can be used by directly setting any value >0.
        type: enum
        default: 400
        values:
            -5: DShot150
            -4: DShot300
            -3: DShot600
            -2: DShot1200
            -1: OneShot
            50: PWM50
            100: PWM100
            200: PWM200
            400: PWM400
        reboot_required: true
This commit is contained in:
Beat Küng 2021-09-15 13:58:44 +02:00 committed by Daniel Agar
parent db28ea9cfa
commit 916447e804
3 changed files with 263 additions and 11 deletions

View File

@ -7,6 +7,7 @@ import argparse
import os
import sys
from output_groups_from_timer_config import get_timer_groups, get_output_groups
try:
import yaml
@ -24,6 +25,8 @@ parser.add_argument('--config-files', type=str, nargs='*', default=[],
help='YAML module config file(s)')
parser.add_argument('--params-file', type=str, action='store',
help='Parameter output file')
parser.add_argument('--timer-config', type=str, action='store',
help='board-specific timer_config.cpp file')
parser.add_argument('--ethernet', action='store_true',
help='Ethernet support')
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
@ -33,6 +36,7 @@ args = parser.parse_args()
verbose = args.verbose
params_output_file = args.params_file
timer_config_file = args.timer_config
ethernet_supported = args.ethernet
root_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../..")
@ -62,6 +66,7 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
continue
num_instances = param.get('num_instances', 1)
instance_start = param.get('instance_start', 0) # offset
instance_start_label = param.get('instance_start_label', instance_start)
# get the type and extract all tags
tags = '@group {:}'.format(param_group)
@ -112,13 +117,14 @@ PARAM_DEFINE_{param_type}({name}, {default_value});
long_descr=param['description']['long'].replace("\n", "\n * "),
tags=tags,
param_type=param_type,
name=param_name,
name=param_name.replace('${i}', str(i+instance_start)),
default_value=default_value,
).replace('${i}', str(i+instance_start))
).replace('${i}', str(i+instance_start_label))
return ret
def get_actuator_output_params(yaml_config, output_functions):
def get_actuator_output_params(yaml_config, output_functions,
timer_config_file, verbose):
""" parse the actuator_output section from the yaml config file
:return: dict of param definitions
"""
@ -126,11 +132,50 @@ def get_actuator_output_params(yaml_config, output_functions):
return {}
output_groups = yaml_config['actuator_output']['output_groups']
all_params = {}
for group in output_groups:
group_idx = 0
def add_local_param(param_name, param_def):
nonlocal all_params
# add as a list, as there can be multiple entries with the same param_name
if not param_name in all_params:
all_params[param_name] = []
all_params[param_name].append(param_def)
while group_idx < len(output_groups):
group = output_groups[group_idx]
group_idx += 1
if verbose: print("processing group: {:}".format(group))
# Check for generator and generate additional data.
# We do this by extending the output_groups list and parse in a later iteration
if 'generator' in group:
if group['generator'] == 'pwm':
# We might set these depending on presence of IO in build...
param_prefix = group['param_prefix']
channel_labels = group['channel_labels']
standard_params = group.get('standard_params', [])
extra_function_groups = group.get('extra_function_groups', [])
pwm_timer_param = group.get('pwm_timer_param', None)
if timer_config_file is None:
raise Exception('trying to generate pwm outputs, but --timer-config not set')
timer_groups = get_timer_groups(timer_config_file, verbose)
timer_output_groups, timer_params = get_output_groups(timer_groups,
param_prefix, channel_labels,
standard_params, extra_function_groups, pwm_timer_param,
verbose=verbose)
all_params.update(timer_params)
output_groups.extend(timer_output_groups)
else:
raise Exception('unknown generator {:}'.format(group['generator']))
continue
num_channels = group['num_channels']
param_prefix = group['param_prefix']
channel_label = group['channel_label']
standard_params = group.get('standard_params', {})
instance_start = group.get('instance_start', 1)
instance_start_label = group.get('instance_start_label', instance_start)
if len(param_prefix) > 9: # 16 - len('_FAIL') - 2 (2 digits for index)
raise Exception("param prefix {:} too long (max length=10)".format(param_prefix))
# collect the functions
@ -140,13 +185,14 @@ def get_actuator_output_params(yaml_config, output_functions):
for function_group in function_groups:
group = output_functions[function_group]
for function_name in group:
function_name_label = function_name.replace('_', ' ')
if isinstance(group[function_name], int):
output_function_values[group[function_name]] = function_name
output_function_values[group[function_name]] = function_name_label
else:
start = group[function_name]['start']
count = group[function_name]['count']
for i in range(count):
output_function_values[start+i] = function_name+str(i+1)
output_function_values[start+i] = function_name_label+' '+str(i+1)
# function param
param = {
@ -164,12 +210,13 @@ The default failsafe value is set according to the selected function:
'''.format(channel_label),
},
'type': 'enum',
'instance_start': 1,
'instance_start': instance_start,
'instance_start_label': instance_start_label,
'num_instances': num_channels,
'default': 0,
'values': output_function_values
}
all_params[param_prefix+'_FUNC${i}'] = param
add_local_param(param_prefix+'_FUNC${i}', param)
# handle standard_params
disarmed_description = \
@ -217,13 +264,14 @@ When set to -1 (default), the value depends on the function (see {:}).
'long': description
},
'type': 'int32',
'instance_start': 1,
'instance_start': instance_start,
'instance_start_label': instance_start_label,
'num_instances': num_channels,
'min': standard_params[key]['min'],
'max': standard_params[key]['max'],
'default': standard_params[key]['default'],
}
all_params[param_prefix+'_'+param_suffix+'${i}'] = param
add_local_param(param_prefix+'_'+param_suffix+'${i}', param)
if verbose: print('adding actuator params: {:}'.format(all_params))
return all_params
@ -246,7 +294,8 @@ for yaml_file in args.config_files:
# convert 'output_groups' section into additional params
try:
actuator_output_params = get_actuator_output_params(yaml_config, output_functions)
actuator_output_params = get_actuator_output_params(yaml_config,
output_functions, timer_config_file, verbose)
except Exception as e:
print('Exception while parsing {:}:'.format(yaml_file))
raise e

View File

@ -0,0 +1,202 @@
#!/usr/bin/env python3
""" Script to parse board-specific timer_config.cpp and print the output groups
and timer config params to stdout
"""
import argparse
import os
import sys
import re
from itertools import groupby
from copy import deepcopy
def find_matching_brackets(brackets, s, verbose):
idx = 0
opening = 0
first_open = -1
while idx < len(s):
if s[idx] == brackets[0]:
opening += 1
if first_open == -1:
first_open = idx
if s[idx] == brackets[1]:
opening -= 1
if opening == 0:
if verbose: print(first_open, idx, s[first_open:idx+1])
return first_open+1, idx
idx += 1
raise Exception('Failed to find opening/closing brackets in {:}'.format(s))
def extract_timer(line):
# Try format: initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
search = re.search('Timer::([0-9a-zA-Z_]+)[,\)]', line, re.IGNORECASE)
if search:
return search.group(1)
# nxp rt1062 format: initIOPWM(PWM::FlexPWM2),
search = re.search('PWM::Flex([0-9a-zA-Z_]+)[,\)]', line, re.IGNORECASE)
if search:
return search.group(1)
return None
def extract_timer_from_channel(line):
# Try format: initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
search = re.search('Timer::([0-9a-zA-Z_]+), ', line, re.IGNORECASE)
if search:
return search.group(1)
# nxp rt1062 format: initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06),
search = re.search('PWM::(PWM[0-9]+)[_,\)]', line, re.IGNORECASE)
if search:
return search.group(1)
return None
def get_timer_groups(timer_config_file, verbose=False):
with open(timer_config_file, 'r') as f:
timer_config = f.read()
# timers
dshot_support = {} # key: timer
timers_start_marker = 'io_timers_t io_timers'
timers_start = timer_config.find(timers_start_marker)
if timers_start == -1:
raise Exception('"{:}" not found in {:}'.format(timers_start_marker, timer_config_file))
timer_config = timer_config[timers_start:]
open_idx, close_idx = find_matching_brackets(('{', '}'), timer_config, verbose)
timers = timer_config[open_idx:close_idx]
for line in timers.splitlines():
line = line.strip()
if len(line) == 0 or line.startswith('//'):
continue
timer = extract_timer(line)
if timer:
if verbose: print('found timer def: {:}'.format(timer))
dshot_support[timer] = 'DMA' in line
else:
# Make sure we don't miss anything (e.g. for different syntax) or misparse (e.g. multi-line comments)
raise Exception('Unparsed timer in line: {:}'.format(line))
# channels
channels_start_marker = 'timer_io_channels_t timer_io_channels'
channels_start = timer_config.find(channels_start_marker)
if channels_start == -1:
raise Exception('"{:}" not found in {:}'.format(channels_start_marker, timer_config_file))
timer_config = timer_config[channels_start:]
open_idx, close_idx = find_matching_brackets(('{', '}'), timer_config, verbose)
channels = timer_config[open_idx:close_idx]
channel_timers = []
channel_types = []
for line in channels.splitlines():
line = line.strip()
if len(line) == 0 or line.startswith('//'):
continue
if verbose: print('--'+line+'--')
timer = extract_timer_from_channel(line)
if timer:
if verbose: print('Found timer: {:} in channel line {:}'.format(timer, line))
channel_types.append('cap' if 'capture' in line.lower() else 'pwm')
channel_timers.append(timer)
else:
# Make sure we don't miss anything (e.g. for different syntax) or misparse (e.g. multi-line comments)
raise Exception('Unparsed channel in line: {:}'.format(line))
if len(channel_timers) == 0:
raise Exception('No channels found in "{:}"'.format(channels))
groups = [(len(list(g)), dshot_support[k]) for k, g in groupby(channel_timers)]
outputs = {
'types': channel_types,
'groups': groups
}
return outputs
def get_output_groups(timer_groups, param_prefix="PWM_MAIN",
channel_labels=["PWM Main", "PWM Capture"],
standard_params=[],
extra_function_groups=[], pwm_timer_param=None,
verbose=False):
""" convert the timer groups into an output_groups section of module.yaml
and extra timer params
"""
instance_start = 1
output_groups = []
timer_params = {}
timer_index = 0
instance_start_label = [ 1, 1 ]
for group_count, dshot_support in timer_groups['groups']:
# check for capture vs normal pins for the label
types = timer_groups['types'][instance_start-1:instance_start+group_count-1]
if not all(types[0] == t for t in types):
# Should this ever be needed, we can extend this script to handle that
raise Exception('Implementation requires all channel types for a timer to be equal (types: {:})'.format(types))
if types[0] == 'pwm':
channel_type_idx = 0
elif types[0] == 'cap':
channel_type_idx = 1
else:
raise Exception('unsupported channel type: {:}'.format(types[0]))
channel_label = channel_labels[channel_type_idx]
channel_type_instance = instance_start_label[channel_type_idx]
group = {
'param_prefix': param_prefix,
'channel_label': channel_label,
'instance_start': instance_start,
'instance_start_label': channel_type_instance,
'extra_function_groups': deepcopy(extra_function_groups),
'num_channels': group_count,
'standard_params': deepcopy(standard_params),
}
output_groups.append(group)
if pwm_timer_param is not None:
timer_channels_label = channel_label + ' ' + str(channel_type_instance)
if group_count > 1:
timer_channels_label += '-' + str(channel_type_instance+group_count-1)
pwm_timer_param_cp = deepcopy(pwm_timer_param)
if not dshot_support:
# remove dshot entries if no dshot support
values = pwm_timer_param_cp['values']
for key in list(values.keys()):
if 'dshot' in values[key].lower():
del values[key]
for descr_type in ['short', 'long']:
descr = pwm_timer_param_cp['description'][descr_type]
pwm_timer_param_cp['description'][descr_type] = \
descr.replace('${label}', timer_channels_label)
timer_params[param_prefix+'_TIM'+str(timer_index)] = pwm_timer_param_cp
instance_start += group_count
instance_start_label[channel_type_idx] += group_count
timer_index += 1
return (output_groups, timer_params)
if __name__ == '__main__':
parser = argparse.ArgumentParser(description='Extract output groups from timer_config.cpp')
parser.add_argument('--timer-config', type=str, action='store',
help='timer_config.cpp file', required=True)
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
help='Verbose Output')
args = parser.parse_args()
verbose = args.verbose
timer_groups = get_timer_groups(args.timer_config, verbose)
print('timer groups: {:}'.format(timer_groups))
output_groups, timer_params = get_output_groups(timer_groups, verbose=verbose)
print('output groups: {:}'.format(output_groups))
print('timer params: {:}'.format(timer_params))

View File

@ -88,6 +88,7 @@ add_custom_command(OUTPUT ${generated_serial_params_file} ${generated_module_par
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/module_config/generate_params.py
--params-file ${generated_module_params_file}
${added_arguments}
--timer-config ${PX4_BOARD_DIR}/src/timer_config.cpp
--config-files ${module_config_files} #--verbose
DEPENDS
${module_config_files}