Browse Source

pwm_out_sim: use PWM_FMU for sitl and HIL_ACT for hitl

We might want to change this later, but for now it allows to use the same
airframe configs for sitl/real, and independent hitl configuration.
master
Beat Küng 3 years ago committed by Daniel Agar
parent
commit
44bbe87165
  1. 26
      Tools/module_config/generate_params.py
  2. 9
      src/drivers/pwm_out_sim/PWMSim.hpp
  3. 4
      src/drivers/pwm_out_sim/module.yaml
  4. 1
      src/lib/parameters/CMakeLists.txt

26
Tools/module_config/generate_params.py

@ -29,6 +29,8 @@ parser.add_argument('--timer-config', type=str, action='store', @@ -29,6 +29,8 @@ 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('--board', type=str, action='store',
help='board name, e.g. ')
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
help='Verbose Output')
@ -38,10 +40,28 @@ verbose = args.verbose @@ -38,10 +40,28 @@ verbose = args.verbose
params_output_file = args.params_file
timer_config_file = args.timer_config
ethernet_supported = args.ethernet
board = args.board
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")
def process_param_prefix(param_prefix):
if param_prefix == '${PWM_FMU_OR_HIL}':
if board == 'px4_sitl': return 'PWM_FMU'
return 'HIL_ACT'
if '${' in param_prefix:
raise Exception('unhandled variable in {:}'.format(param_prefix))
return param_prefix
def process_channel_label(channel_label):
if channel_label == '${PWM_FMU_OR_HIL}':
if board == 'px4_sitl': return 'PWM Sim'
return 'HIL actuator'
if '${' in channel_label:
raise Exception('unhandled variable in {:}'.format(channel_label))
return channel_label
def parse_yaml_parameters_config(yaml_config, ethernet_supported):
""" parse the parameters section from the yaml config file """
if 'parameters' not in yaml_config:
@ -152,7 +172,7 @@ def get_actuator_output_params(yaml_config, output_functions, @@ -152,7 +172,7 @@ def get_actuator_output_params(yaml_config, output_functions,
if 'generator' in group:
if group['generator'] == 'pwm':
# We might set these depending on presence of IO in build...
param_prefix = group['param_prefix']
param_prefix = process_param_prefix(group['param_prefix'])
channel_labels = group['channel_labels']
standard_params = group.get('standard_params', [])
extra_function_groups = group.get('extra_function_groups', [])
@ -171,8 +191,8 @@ def get_actuator_output_params(yaml_config, output_functions, @@ -171,8 +191,8 @@ def get_actuator_output_params(yaml_config, output_functions,
continue
num_channels = group['num_channels']
param_prefix = group['param_prefix']
channel_label = group['channel_label']
param_prefix = process_param_prefix(group['param_prefix'])
channel_label = process_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)

9
src/drivers/pwm_out_sim/PWMSim.hpp

@ -44,6 +44,13 @@ @@ -44,6 +44,13 @@
#include <px4_platform_common/time.h>
#include <uORB/topics/parameter_update.h>
#if defined(CONFIG_ARCH_BOARD_PX4_SITL)
#define PARAM_PREFIX "PWM_FMU"
#else
#define PARAM_PREFIX "HIL_ACT"
#endif
using namespace time_literals;
class PWMSim : public cdev::CDev, public ModuleBase<PWMSim>, public OutputModuleInterface
@ -77,7 +84,7 @@ private: @@ -77,7 +84,7 @@ private:
static constexpr uint16_t PWM_SIM_PWM_MIN_MAGIC = 1000;
static constexpr uint16_t PWM_SIM_PWM_MAX_MAGIC = 2000;
MixingOutput _mixing_output{"PWM_SIM", MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
MixingOutput _mixing_output{PARAM_PREFIX, MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
};

4
src/drivers/pwm_out_sim/module.yaml

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
module_name: PWM Sim
actuator_output:
output_groups:
- param_prefix: PWM_SIM
channel_label: 'PWM Sim'
- param_prefix: ${PWM_FMU_OR_HIL}
channel_label: ${PWM_FMU_OR_HIL}
num_channels: 16

1
src/lib/parameters/CMakeLists.txt

@ -90,6 +90,7 @@ add_custom_command(OUTPUT ${generated_serial_params_file} ${generated_module_par @@ -90,6 +90,7 @@ add_custom_command(OUTPUT ${generated_serial_params_file} ${generated_module_par
${added_arguments}
--timer-config ${PX4_BOARD_DIR}/src/timer_config.cpp
--config-files ${module_config_files} #--verbose
--board ${PX4_BOARD}
DEPENDS
${module_config_files}
${jinja_templates}

Loading…
Cancel
Save