2021-09-13 11:11:42 -03:00
|
|
|
#!/usr/bin/env python3
|
|
|
|
""" Script to params from module.yaml config file(s)
|
|
|
|
Note: serial params are handled in Tools/serial/generate_config.py
|
|
|
|
"""
|
|
|
|
|
|
|
|
import argparse
|
|
|
|
import os
|
|
|
|
import sys
|
2021-11-22 06:33:14 -04:00
|
|
|
from copy import deepcopy
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-15 08:58:44 -03:00
|
|
|
from output_groups_from_timer_config import get_timer_groups, get_output_groups
|
2021-09-13 11:11:42 -03:00
|
|
|
|
|
|
|
try:
|
|
|
|
import yaml
|
|
|
|
except ImportError as e:
|
|
|
|
print("Failed to import yaml: " + str(e))
|
|
|
|
print("")
|
|
|
|
print("You may need to install it using:")
|
|
|
|
print(" pip3 install --user pyyaml")
|
|
|
|
print("")
|
|
|
|
sys.exit(1)
|
|
|
|
|
|
|
|
parser = argparse.ArgumentParser(description='Generate params from module.yaml file(s)')
|
|
|
|
|
|
|
|
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')
|
2021-09-15 08:58:44 -03:00
|
|
|
parser.add_argument('--timer-config', type=str, action='store',
|
|
|
|
help='board-specific timer_config.cpp file')
|
2021-09-13 11:11:42 -03:00
|
|
|
parser.add_argument('--ethernet', action='store_true',
|
|
|
|
help='Ethernet support')
|
2021-09-17 10:48:36 -03:00
|
|
|
parser.add_argument('--board', type=str, action='store',
|
|
|
|
help='board name, e.g. ')
|
2021-10-05 08:26:52 -03:00
|
|
|
parser.add_argument('--board-with-io', dest='board_with_io', action='store_true',
|
|
|
|
help='Indicate that the board as an IO for extra PWM',
|
|
|
|
default=False)
|
2021-09-13 11:11:42 -03:00
|
|
|
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
|
|
|
|
help='Verbose Output')
|
|
|
|
|
|
|
|
args = parser.parse_args()
|
|
|
|
|
|
|
|
verbose = args.verbose
|
|
|
|
params_output_file = args.params_file
|
2021-09-15 08:58:44 -03:00
|
|
|
timer_config_file = args.timer_config
|
2021-09-13 11:11:42 -03:00
|
|
|
ethernet_supported = args.ethernet
|
2021-10-05 08:26:52 -03:00
|
|
|
board_with_io = args.board_with_io
|
2021-09-17 10:48:36 -03:00
|
|
|
board = args.board
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-14 09:52:34 -03:00
|
|
|
root_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../..")
|
|
|
|
output_functions_file = os.path.join(root_dir,"src/lib/mixer_module/output_functions.yaml")
|
|
|
|
|
2021-09-17 10:48:36 -03:00
|
|
|
def process_param_prefix(param_prefix):
|
2021-10-05 08:26:52 -03:00
|
|
|
if param_prefix == '${PWM_MAIN_OR_HIL}':
|
|
|
|
if board == 'px4_sitl': return 'PWM_MAIN'
|
2021-09-17 10:48:36 -03:00
|
|
|
return 'HIL_ACT'
|
2021-10-05 08:26:52 -03:00
|
|
|
if param_prefix == '${PWM_MAIN_OR_AUX}':
|
|
|
|
if board_with_io: return 'PWM_AUX'
|
|
|
|
return 'PWM_MAIN'
|
2021-09-17 10:48:36 -03:00
|
|
|
if '${' in param_prefix:
|
|
|
|
raise Exception('unhandled variable in {:}'.format(param_prefix))
|
|
|
|
return param_prefix
|
|
|
|
|
|
|
|
def process_channel_label(channel_label):
|
2021-10-05 08:26:52 -03:00
|
|
|
if channel_label == '${PWM_MAIN_OR_HIL}':
|
2021-09-17 10:48:36 -03:00
|
|
|
if board == 'px4_sitl': return 'PWM Sim'
|
|
|
|
return 'HIL actuator'
|
2021-10-05 08:26:52 -03:00
|
|
|
if channel_label == '${PWM_MAIN_OR_AUX}':
|
|
|
|
if board_with_io: return 'PWM Aux'
|
|
|
|
return 'PWM Main'
|
2021-09-17 10:48:36 -03:00
|
|
|
if '${' in channel_label:
|
|
|
|
raise Exception('unhandled variable in {:}'.format(channel_label))
|
|
|
|
return channel_label
|
|
|
|
|
|
|
|
|
2021-09-13 11:11:42 -03:00
|
|
|
def parse_yaml_parameters_config(yaml_config, ethernet_supported):
|
|
|
|
""" parse the parameters section from the yaml config file """
|
|
|
|
if 'parameters' not in yaml_config:
|
|
|
|
return ''
|
|
|
|
parameters_section_list = yaml_config['parameters']
|
2021-09-14 08:54:34 -03:00
|
|
|
ret = ''
|
2021-09-13 11:11:42 -03:00
|
|
|
for parameters_section in parameters_section_list:
|
|
|
|
if 'definitions' not in parameters_section:
|
2021-09-14 08:54:34 -03:00
|
|
|
continue
|
2021-09-13 11:11:42 -03:00
|
|
|
definitions = parameters_section['definitions']
|
|
|
|
param_group = parameters_section.get('group', None)
|
|
|
|
for param_name in definitions:
|
2021-09-15 08:47:40 -03:00
|
|
|
# 'definitions' either contains the param definition directly (dict),
|
|
|
|
# or a list of definitions with that name (multiple entries for a
|
|
|
|
# multi-instance param with different instance_start)
|
|
|
|
param_list = definitions[param_name]
|
|
|
|
if not isinstance(param_list, list):
|
|
|
|
param_list = [param_list]
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-15 08:47:40 -03:00
|
|
|
for param in param_list:
|
|
|
|
if param.get('requires_ethernet', False) and not ethernet_supported:
|
|
|
|
continue
|
|
|
|
num_instances = param.get('num_instances', 1)
|
|
|
|
instance_start = param.get('instance_start', 0) # offset
|
2021-09-15 08:58:44 -03:00
|
|
|
instance_start_label = param.get('instance_start_label', instance_start)
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-15 08:47:40 -03:00
|
|
|
# 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']))
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-15 08:47:40 -03:00
|
|
|
for tag in ['decimal', 'increment', 'category', 'volatile', 'bit',
|
|
|
|
'min', 'max', 'unit', 'reboot_required']:
|
|
|
|
if tag in param:
|
|
|
|
tags += '\n * @{:} {:}'.format(tag, param[tag])
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-15 08:47:40 -03:00
|
|
|
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']
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-15 08:47:40 -03:00
|
|
|
if type(default_value) == bool:
|
|
|
|
default_value = int(default_value)
|
|
|
|
|
|
|
|
# output the existing C-style format
|
|
|
|
ret += '''
|
2021-09-13 11:11:42 -03:00
|
|
|
/**
|
|
|
|
* {short_descr}
|
|
|
|
*
|
|
|
|
* {long_descr}
|
|
|
|
*
|
|
|
|
* {tags}
|
|
|
|
*/
|
|
|
|
PARAM_DEFINE_{param_type}({name}, {default_value});
|
|
|
|
'''.format(short_descr=param['description']['short'].replace("\n", "\n * "),
|
2021-11-02 12:06:36 -03:00
|
|
|
long_descr=param['description'].get('long', "").replace("\n", "\n * "),
|
2021-09-13 11:11:42 -03:00
|
|
|
tags=tags,
|
|
|
|
param_type=param_type,
|
2021-09-15 08:58:44 -03:00
|
|
|
name=param_name.replace('${i}', str(i+instance_start)),
|
2021-09-13 11:11:42 -03:00
|
|
|
default_value=default_value,
|
2021-09-15 08:58:44 -03:00
|
|
|
).replace('${i}', str(i+instance_start_label))
|
2021-09-13 11:11:42 -03:00
|
|
|
return ret
|
|
|
|
|
|
|
|
|
2021-09-15 08:58:44 -03:00
|
|
|
def get_actuator_output_params(yaml_config, output_functions,
|
|
|
|
timer_config_file, verbose):
|
2021-09-14 09:52:34 -03:00
|
|
|
""" parse the actuator_output section from the yaml config file
|
|
|
|
:return: dict of param definitions
|
|
|
|
"""
|
|
|
|
if not 'actuator_output' in yaml_config:
|
|
|
|
return {}
|
|
|
|
output_groups = yaml_config['actuator_output']['output_groups']
|
|
|
|
all_params = {}
|
2021-09-15 08:58:44 -03:00
|
|
|
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':
|
2021-09-17 10:48:36 -03:00
|
|
|
param_prefix = process_param_prefix(group['param_prefix'])
|
2021-10-05 08:26:52 -03:00
|
|
|
channel_labels = [process_channel_label(label) for label in group['channel_labels']]
|
2021-09-15 08:58:44 -03:00
|
|
|
standard_params = group.get('standard_params', [])
|
|
|
|
extra_function_groups = group.get('extra_function_groups', [])
|
|
|
|
pwm_timer_param = group.get('pwm_timer_param', None)
|
2021-10-05 08:36:28 -03:00
|
|
|
if 'timer_config_file' in group:
|
|
|
|
timer_config_file = os.path.join(root_dir, group['timer_config_file'])
|
2021-09-15 08:58:44 -03:00
|
|
|
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)
|
2021-11-22 06:33:14 -04:00
|
|
|
|
|
|
|
# In case of a board w/o IO and >8 PWM channels, pwm_out splits
|
|
|
|
# into 2 instances (if SYS_CTRL_ALLOC==0) and we need to add the
|
|
|
|
# PWM_AUX min/max/disarmed params as well.
|
|
|
|
num_channels = len(timer_groups['types'])
|
|
|
|
if not board_with_io and num_channels > 8:
|
|
|
|
output_groups.append(
|
|
|
|
{
|
|
|
|
'param_prefix': 'PWM_AUX',
|
|
|
|
'channel_label': 'PWM AUX',
|
|
|
|
'instance_start': 1,
|
|
|
|
'num_channels': num_channels - 8,
|
|
|
|
'standard_params': deepcopy(timer_output_groups[0]['standard_params'])
|
|
|
|
})
|
|
|
|
|
2021-09-15 08:58:44 -03:00
|
|
|
else:
|
|
|
|
raise Exception('unknown generator {:}'.format(group['generator']))
|
|
|
|
continue
|
|
|
|
|
2021-09-14 09:52:34 -03:00
|
|
|
num_channels = group['num_channels']
|
2021-09-17 10:48:36 -03:00
|
|
|
param_prefix = process_param_prefix(group['param_prefix'])
|
|
|
|
channel_label = process_channel_label(group['channel_label'])
|
2021-09-14 09:52:34 -03:00
|
|
|
standard_params = group.get('standard_params', {})
|
2021-09-15 08:58:44 -03:00
|
|
|
instance_start = group.get('instance_start', 1)
|
|
|
|
instance_start_label = group.get('instance_start_label', instance_start)
|
2021-09-14 09:52:34 -03:00
|
|
|
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
|
|
|
|
function_groups = ['common']
|
|
|
|
function_groups.extend(group.get('extra_function_groups', []))
|
|
|
|
output_function_values = {}
|
|
|
|
for function_group in function_groups:
|
|
|
|
group = output_functions[function_group]
|
|
|
|
for function_name in group:
|
2021-09-15 08:58:44 -03:00
|
|
|
function_name_label = function_name.replace('_', ' ')
|
2021-09-14 09:52:34 -03:00
|
|
|
if isinstance(group[function_name], int):
|
2021-09-15 08:58:44 -03:00
|
|
|
output_function_values[group[function_name]] = function_name_label
|
2021-09-14 09:52:34 -03:00
|
|
|
else:
|
|
|
|
start = group[function_name]['start']
|
|
|
|
count = group[function_name]['count']
|
|
|
|
for i in range(count):
|
2021-09-15 08:58:44 -03:00
|
|
|
output_function_values[start+i] = function_name_label+' '+str(i+1)
|
2021-09-14 09:52:34 -03:00
|
|
|
|
|
|
|
# function param
|
|
|
|
param = {
|
|
|
|
'description': {
|
|
|
|
'short': channel_label+' ${i} Output Function',
|
|
|
|
'long':
|
|
|
|
'''Select what should be output on {:} ${{i}}.
|
|
|
|
|
|
|
|
The default failsafe value is set according to the selected function:
|
|
|
|
- 'Min' for ConstantMin
|
|
|
|
- 'Max' for ConstantMax
|
|
|
|
- 'Max' for Parachute
|
|
|
|
- ('Max'+'Min')/2 for Servos
|
|
|
|
- 'Disarmed' for the rest
|
|
|
|
'''.format(channel_label),
|
|
|
|
},
|
|
|
|
'type': 'enum',
|
2021-09-15 08:58:44 -03:00
|
|
|
'instance_start': instance_start,
|
|
|
|
'instance_start_label': instance_start_label,
|
2021-09-14 09:52:34 -03:00
|
|
|
'num_instances': num_channels,
|
|
|
|
'default': 0,
|
|
|
|
'values': output_function_values
|
|
|
|
}
|
2021-09-15 08:58:44 -03:00
|
|
|
add_local_param(param_prefix+'_FUNC${i}', param)
|
2021-09-14 09:52:34 -03:00
|
|
|
|
|
|
|
# handle standard_params
|
|
|
|
disarmed_description = \
|
|
|
|
'''This is the output value that is set when not armed.
|
|
|
|
|
|
|
|
Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set.
|
|
|
|
'''
|
|
|
|
minimum_description = \
|
|
|
|
'''Minimum output value (when not disarmed).
|
|
|
|
|
|
|
|
The output range can be reversed by setting Min > Max.
|
|
|
|
'''
|
|
|
|
maximum_description = \
|
|
|
|
'''Maxmimum output value (when not disarmed).
|
|
|
|
|
|
|
|
The output range can be reversed by setting Min > Max.
|
|
|
|
'''
|
|
|
|
failsafe_description = \
|
|
|
|
'''This is the output value that is set when in failsafe mode.
|
|
|
|
|
|
|
|
When set to -1 (default), the value depends on the function (see {:}).
|
|
|
|
'''.format(param_prefix+'_FUNC${i}')
|
|
|
|
standard_params_array = [
|
|
|
|
( 'disarmed', 'Disarmed', 'DIS', disarmed_description ),
|
|
|
|
( 'min', 'Minimum', 'MIN', minimum_description ),
|
|
|
|
( 'max', 'Maximum', 'MAX', maximum_description ),
|
|
|
|
( 'failsafe', 'Failsafe', 'FAIL', failsafe_description ),
|
|
|
|
]
|
|
|
|
for key, label, param_suffix, description in standard_params_array:
|
|
|
|
if key in standard_params:
|
|
|
|
|
|
|
|
# values must be in range of an uint16_t
|
|
|
|
if standard_params[key]['min'] < 0:
|
|
|
|
raise Exception('minimum value for {:} expected >= 0 (got {:})'.format(key, standard_params[key]['min']))
|
|
|
|
if standard_params[key]['max'] >= 1<<16:
|
|
|
|
raise Exception('maximum value for {:} expected <= {:} (got {:})'.format(key, 1<<16, standard_params[key]['max']))
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-14 09:52:34 -03:00
|
|
|
if key == 'failsafe':
|
|
|
|
standard_params[key]['default'] = -1
|
|
|
|
standard_params[key]['min'] = -1
|
2021-09-13 11:11:42 -03:00
|
|
|
|
2021-09-14 09:52:34 -03:00
|
|
|
param = {
|
|
|
|
'description': {
|
|
|
|
'short': channel_label+' ${i} '+label+' Value',
|
|
|
|
'long': description
|
|
|
|
},
|
|
|
|
'type': 'int32',
|
2021-09-15 08:58:44 -03:00
|
|
|
'instance_start': instance_start,
|
|
|
|
'instance_start_label': instance_start_label,
|
2021-09-14 09:52:34 -03:00
|
|
|
'num_instances': num_channels,
|
|
|
|
'min': standard_params[key]['min'],
|
|
|
|
'max': standard_params[key]['max'],
|
|
|
|
'default': standard_params[key]['default'],
|
|
|
|
}
|
2021-09-15 08:58:44 -03:00
|
|
|
add_local_param(param_prefix+'_'+param_suffix+'${i}', param)
|
2021-09-14 09:52:34 -03:00
|
|
|
|
|
|
|
if verbose: print('adding actuator params: {:}'.format(all_params))
|
|
|
|
return all_params
|
|
|
|
|
|
|
|
def load_yaml_file(file_name):
|
|
|
|
with open(file_name, 'r') as stream:
|
|
|
|
try:
|
|
|
|
return yaml.safe_load(stream)
|
2021-09-13 11:11:42 -03:00
|
|
|
except yaml.YAMLError as exc:
|
|
|
|
print(exc)
|
|
|
|
raise
|
|
|
|
|
2021-09-14 09:52:34 -03:00
|
|
|
output_functions_yaml = load_yaml_file(output_functions_file)
|
|
|
|
output_functions = output_functions_yaml['functions']
|
|
|
|
|
|
|
|
all_params = ""
|
|
|
|
|
|
|
|
for yaml_file in args.config_files:
|
|
|
|
yaml_config = load_yaml_file(yaml_file)
|
|
|
|
|
|
|
|
# convert 'output_groups' section into additional params
|
|
|
|
try:
|
2021-09-15 08:58:44 -03:00
|
|
|
actuator_output_params = get_actuator_output_params(yaml_config,
|
|
|
|
output_functions, timer_config_file, verbose)
|
2021-09-14 09:52:34 -03:00
|
|
|
except Exception as e:
|
|
|
|
print('Exception while parsing {:}:'.format(yaml_file))
|
|
|
|
raise e
|
|
|
|
# now add them to the yaml config
|
|
|
|
if not 'parameters' in yaml_config:
|
|
|
|
yaml_config['parameters'] = []
|
|
|
|
group_name = 'Actuator Outputs'
|
|
|
|
yaml_config['parameters'].append({'group': group_name, 'definitions': actuator_output_params})
|
|
|
|
|
|
|
|
all_params += parse_yaml_parameters_config(yaml_config, ethernet_supported)
|
|
|
|
|
|
|
|
|
2021-09-13 11:11:42 -03:00
|
|
|
if verbose: print("Generating {:}".format(params_output_file))
|
|
|
|
with open(params_output_file, 'w') as fid:
|
|
|
|
fid.write(all_params)
|