mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
config: cleanup ethernet configuration
This commit is contained in:
@@ -190,7 +190,6 @@ if rc_serial_output_dir is None and serial_params_output_file is None:
|
|||||||
serial_commands = []
|
serial_commands = []
|
||||||
ethernet_configuration = []
|
ethernet_configuration = []
|
||||||
additional_params = ""
|
additional_params = ""
|
||||||
additional_ethernet_params = ""
|
|
||||||
|
|
||||||
if ethernet_supported:
|
if ethernet_supported:
|
||||||
ethernet_configuration.append({
|
ethernet_configuration.append({
|
||||||
@@ -211,7 +210,7 @@ def parse_yaml_serial_config(yaml_config):
|
|||||||
ret.append(serial_config)
|
ret.append(serial_config)
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
def parse_yaml_parameters_config(yaml_config):
|
def parse_yaml_parameters_config(yaml_config, ethernet_supported):
|
||||||
""" parse the parameters section from the yaml config file """
|
""" parse the parameters section from the yaml config file """
|
||||||
if 'parameters' not in yaml_config:
|
if 'parameters' not in yaml_config:
|
||||||
return ''
|
return ''
|
||||||
@@ -224,79 +223,7 @@ def parse_yaml_parameters_config(yaml_config):
|
|||||||
param_group = parameters_section.get('group', None)
|
param_group = parameters_section.get('group', None)
|
||||||
for param_name in definitions:
|
for param_name in definitions:
|
||||||
param = definitions[param_name]
|
param = definitions[param_name]
|
||||||
if 'ethernet' in param:
|
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
|
|
||||||
|
|
||||||
# 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
|
|
||||||
|
|
||||||
def parse_yaml_ethernet_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]
|
|
||||||
if 'ethernet' not in param:
|
|
||||||
continue
|
continue
|
||||||
num_instances = param.get('num_instances', 1)
|
num_instances = param.get('num_instances', 1)
|
||||||
instance_start = param.get('instance_start', 0) # offset
|
instance_start = param.get('instance_start', 0) # offset
|
||||||
@@ -362,9 +289,8 @@ for yaml_file in args.config_files:
|
|||||||
serial_commands.extend(parse_yaml_serial_config(yaml_config))
|
serial_commands.extend(parse_yaml_serial_config(yaml_config))
|
||||||
|
|
||||||
# TODO: additional params should be parsed in a separate script
|
# TODO: additional params should be parsed in a separate script
|
||||||
additional_params += parse_yaml_parameters_config(yaml_config)
|
additional_params += parse_yaml_parameters_config(
|
||||||
if ethernet_supported:
|
yaml_config, ethernet_supported)
|
||||||
additional_ethernet_params += parse_yaml_ethernet_parameters_config(yaml_config)
|
|
||||||
|
|
||||||
except yaml.YAMLError as exc:
|
except yaml.YAMLError as exc:
|
||||||
print(exc)
|
print(exc)
|
||||||
@@ -429,7 +355,7 @@ for serial_command in serial_commands:
|
|||||||
'default_port': default_port,
|
'default_port': default_port,
|
||||||
'param_group': port_config['group'],
|
'param_group': port_config['group'],
|
||||||
'description_extended': port_config.get('description_extended', ''),
|
'description_extended': port_config.get('description_extended', ''),
|
||||||
'ethernet_config': serial_command.get('ethernet', 'none')
|
'supports_networking': serial_command.get('supports_networking', False)
|
||||||
})
|
})
|
||||||
|
|
||||||
if verbose:
|
if verbose:
|
||||||
@@ -473,6 +399,5 @@ if serial_params_output_file is not None:
|
|||||||
fid.write(template.render(serial_devices=serial_devices,
|
fid.write(template.render(serial_devices=serial_devices,
|
||||||
ethernet_configuration=ethernet_configuration,
|
ethernet_configuration=ethernet_configuration,
|
||||||
commands=commands, serial_ports=serial_ports,
|
commands=commands, serial_ports=serial_ports,
|
||||||
additional_definitions=additional_params,
|
additional_definitions=additional_params))
|
||||||
additional_ethernet_definitions=additional_ethernet_params))
|
|
||||||
|
|
||||||
|
|||||||
@@ -17,9 +17,9 @@ if param compare "$PRT" {{ serial_device.index }}; then
|
|||||||
fi
|
fi
|
||||||
|
|
||||||
{% endfor %}
|
{% endfor %}
|
||||||
|
|
||||||
{% for config in ethernet_configuration -%}
|
{% for config in ethernet_configuration -%}
|
||||||
if param compare "$PRT" {{ config.index }}; then
|
if param compare "$PRT" {{ config.index }}; then
|
||||||
set SERIAL_DEV ethernet
|
set SERIAL_DEV ethernet
|
||||||
fi
|
fi
|
||||||
|
|
||||||
{% endfor %}
|
{% endfor %}
|
||||||
|
|||||||
@@ -58,10 +58,11 @@ PARAM_DEFINE_INT32(SER_{{ serial_device.tag }}_BAUD, {{ serial_device.default_ba
|
|||||||
{%- for serial_device in serial_devices %}
|
{%- for serial_device in serial_devices %}
|
||||||
* @value {{ serial_device.index }} {{ serial_device.label }}
|
* @value {{ serial_device.index }} {{ serial_device.label }}
|
||||||
{%- endfor %}
|
{%- endfor %}
|
||||||
{%- if command.ethernet_config != "none" %}
|
{%- if command.supports_networking %}
|
||||||
{%- for config in ethernet_configuration %}
|
{%- for config in ethernet_configuration %}
|
||||||
* @value {{ config.index }} {{ config.label }}
|
* @value {{ config.index }} {{ config.label }}
|
||||||
{%- endfor %}{% endif %}
|
{%- endfor %}
|
||||||
|
{%- endif %}
|
||||||
* @group {{ command.param_group }}
|
* @group {{ command.param_group }}
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
*/
|
*/
|
||||||
@@ -72,5 +73,3 @@ PARAM_DEFINE_INT32({{ command.port_param_name }}, {{ command.default_port }});
|
|||||||
|
|
||||||
{{ additional_definitions }}
|
{{ additional_definitions }}
|
||||||
|
|
||||||
{{ additional_ethernet_definitions }}
|
|
||||||
|
|
||||||
|
|||||||
@@ -34,7 +34,7 @@ serial_config:
|
|||||||
# 2: Board-specific / no fixed function or port
|
# 2: Board-specific / no fixed function or port
|
||||||
default: [TEL1, "", ""]
|
default: [TEL1, "", ""]
|
||||||
num_instances: *max_num_config_instances
|
num_instances: *max_num_config_instances
|
||||||
ethernet:
|
supports_networking: true
|
||||||
|
|
||||||
parameters:
|
parameters:
|
||||||
- group: MAVLink
|
- group: MAVLink
|
||||||
@@ -123,7 +123,7 @@ parameters:
|
|||||||
reboot_required: true
|
reboot_required: true
|
||||||
num_instances: *max_num_config_instances
|
num_instances: *max_num_config_instances
|
||||||
default: [14556, 0, 0]
|
default: [14556, 0, 0]
|
||||||
ethernet:
|
requires_ethernet: true
|
||||||
|
|
||||||
MAV_${i}_REMOTE_PRT:
|
MAV_${i}_REMOTE_PRT:
|
||||||
description:
|
description:
|
||||||
@@ -136,7 +136,7 @@ parameters:
|
|||||||
reboot_required: true
|
reboot_required: true
|
||||||
num_instances: *max_num_config_instances
|
num_instances: *max_num_config_instances
|
||||||
default: [14550, 0, 0]
|
default: [14550, 0, 0]
|
||||||
ethernet:
|
requires_ethernet: true
|
||||||
|
|
||||||
MAV_${i}_BROADCAST:
|
MAV_${i}_BROADCAST:
|
||||||
description:
|
description:
|
||||||
@@ -152,4 +152,4 @@ parameters:
|
|||||||
2: Only multicast
|
2: Only multicast
|
||||||
num_instances: *max_num_config_instances
|
num_instances: *max_num_config_instances
|
||||||
default: [1, 0, 0]
|
default: [1, 0, 0]
|
||||||
ethernet:
|
requires_ethernet: true
|
||||||
|
|||||||
@@ -75,10 +75,9 @@ serial_config:
|
|||||||
# Default: 1
|
# Default: 1
|
||||||
type: integer
|
type: integer
|
||||||
min: 1
|
min: 1
|
||||||
ethernet:
|
supports_networking:
|
||||||
# Optional command ethernet.
|
# set to true if the module supports networking (UDP)
|
||||||
# If omitted, ethernet condiguration value will be omitted.
|
type: boolean
|
||||||
nullable: True
|
|
||||||
|
|
||||||
|
|
||||||
parameters:
|
parameters:
|
||||||
@@ -212,9 +211,9 @@ parameters:
|
|||||||
# [0, N-1]
|
# [0, N-1]
|
||||||
# Default: 0
|
# Default: 0
|
||||||
type: integer
|
type: integer
|
||||||
ethernet:
|
requires_ethernet:
|
||||||
# Optional command ethernet.
|
# param is only added if the board has ethernet
|
||||||
# If specified, parameter will be generated only if board supports Ethernet.
|
# support
|
||||||
nullable: True
|
type: boolean
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user