Skip to content

Commit f1686b1

Browse files
bkuengdagar
authored andcommitted
px4io: add dynamic mixing support
1 parent 837a106 commit f1686b1

File tree

9 files changed

+206
-33
lines changed

9 files changed

+206
-33
lines changed

Tools/module_config/generate_params.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,8 @@ def add_local_param(param_name, param_def):
186186
standard_params = group.get('standard_params', [])
187187
extra_function_groups = group.get('extra_function_groups', [])
188188
pwm_timer_param = group.get('pwm_timer_param', None)
189+
if 'timer_config_file' in group:
190+
timer_config_file = os.path.join(root_dir, group['timer_config_file'])
189191
if timer_config_file is None:
190192
raise Exception('trying to generate pwm outputs, but --timer-config not set')
191193
timer_groups = get_timer_groups(timer_config_file, verbose)

src/drivers/px4io/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ px4_add_module(
3939
px4io.cpp
4040
px4io_serial.cpp
4141
px4io_uploader.cpp
42+
MODULE_CONFIG
43+
module.yaml
4244
DEPENDS
4345
arch_px4io_serial
4446
circuit_breaker

src/drivers/px4io/module.yaml

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
module_name: IO PWM Output
2+
actuator_output:
3+
output_groups:
4+
- generator: pwm
5+
param_prefix: PWM_MAIN
6+
channel_labels: ['PWM Main', 'PWM Capture']
7+
timer_config_file: "boards/px4/io-v2/src/timer_config.cpp"
8+
standard_params:
9+
disarmed: { min: 800, max: 2200, default: 900 }
10+
min: { min: 800, max: 1400, default: 1000 }
11+
max: { min: 1600, max: 2200, default: 2000 }
12+
failsafe: { min: 800, max: 2200 }
13+
pwm_timer_param:
14+
description:
15+
short: Output Protocol Configuration for ${label}
16+
long: |
17+
Select which Output Protocol to use for outputs ${label}.
18+
19+
Custom PWM rates can be used by directly setting any value >0.
20+
type: enum
21+
default: 400
22+
values:
23+
-1: OneShot
24+
50: PWM50
25+
100: PWM100
26+
200: PWM200
27+
400: PWM400
28+
reboot_required: true
29+

src/drivers/px4io/px4io.cpp

Lines changed: 98 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -174,6 +174,7 @@ class PX4IO : public cdev::CDev, public ModuleBase<PX4IO>, public OutputModuleIn
174174

175175
void updateDisarmed();
176176
void updateFailsafe();
177+
void updateTimerRateGroups();
177178

178179
static int checkcrc(int argc, char *argv[]);
179180
static int bind(int argc, char *argv[]);
@@ -218,6 +219,7 @@ class PX4IO : public cdev::CDev, public ModuleBase<PX4IO>, public OutputModuleIn
218219
hrt_abstime _last_status_publish{0};
219220

220221
bool _param_update_force{true}; ///< force a parameter update
222+
bool _timer_rates_configured{false};
221223

222224
/* advertised topics */
223225
uORB::PublicationMulti<input_rc_s> _to_input_rc{ORB_ID(input_rc)};
@@ -364,8 +366,12 @@ PX4IO::PX4IO(device::Device *interface) :
364366
OutputModuleInterface(MODULE_NAME, px4::serial_port_to_wq(PX4IO_SERIAL_DEVICE)),
365367
_interface(interface)
366368
{
367-
_mixing_output.setAllMinValues(PWM_DEFAULT_MIN);
368-
_mixing_output.setAllMaxValues(PWM_DEFAULT_MAX);
369+
if (!_mixing_output.useDynamicMixing()) {
370+
_mixing_output.setAllMinValues(PWM_DEFAULT_MIN);
371+
_mixing_output.setAllMaxValues(PWM_DEFAULT_MAX);
372+
}
373+
374+
_mixing_output.setLowrateSchedulingInterval(20_ms);
369375
}
370376

371377
PX4IO::~PX4IO()
@@ -555,7 +561,7 @@ void PX4IO::updateFailsafe()
555561
pwm_output_values pwm{};
556562

557563
for (unsigned i = 0; i < _max_actuators; i++) {
558-
pwm.values[i] = _mixing_output.failsafeValue(i);
564+
pwm.values[i] = _mixing_output.actualFailsafeValue(i);
559565
}
560566

561567
io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, pwm.values, _max_actuators);
@@ -575,7 +581,9 @@ void PX4IO::Run()
575581
perf_count(_interval_perf);
576582

577583
// schedule minimal update rate if there are no actuator controls
578-
ScheduleDelayed(20_ms);
584+
if (!_mixing_output.useDynamicMixing()) {
585+
ScheduleDelayed(20_ms);
586+
}
579587

580588
/* if we have new control data from the ORB, handle it */
581589
if (_param_sys_hitl.get() <= 0) {
@@ -705,10 +713,60 @@ void PX4IO::Run()
705713
perf_end(_cycle_perf);
706714
}
707715

716+
void PX4IO::updateTimerRateGroups()
717+
{
718+
if (_timer_rates_configured) { // avoid setting timer rates on each param update
719+
return;
720+
}
721+
722+
_timer_rates_configured = true;
723+
724+
int timer = 0;
725+
726+
uint16_t timer_rates[PX4IO_P_SETUP_PWM_RATE_GROUP3 - PX4IO_P_SETUP_PWM_RATE_GROUP0 + 1] {};
727+
728+
for (uint8_t offset = PX4IO_P_SETUP_PWM_RATE_GROUP0; offset <= PX4IO_P_SETUP_PWM_RATE_GROUP3; ++offset) {
729+
char param_name[17];
730+
snprintf(param_name, sizeof(param_name), "%s_TIM%u", _mixing_output.paramPrefix(), timer);
731+
732+
int32_t tim_config = 0;
733+
param_t handle = param_find(param_name);
734+
735+
if (handle == PARAM_INVALID) {
736+
break;
737+
}
738+
739+
param_get(handle, &tim_config);
740+
741+
if (tim_config > 0) {
742+
timer_rates[timer] = tim_config;
743+
744+
} else if (tim_config == -1) { // OneShot
745+
timer_rates[timer] = 0;
746+
}
747+
748+
++timer;
749+
}
750+
751+
int ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATE_GROUP0, timer_rates, timer);
752+
753+
if (ret != 0) {
754+
PX4_ERR("io_reg_set failed (%i)", ret);
755+
}
756+
}
757+
708758
void PX4IO::update_params()
709759
{
760+
if (!_mixing_output.armed().armed && _mixing_output.useDynamicMixing()) {
761+
// sync params to IO
762+
updateTimerRateGroups();
763+
updateFailsafe();
764+
updateDisarmed();
765+
return;
766+
}
767+
710768
// skip update when armed or PWM disabled
711-
if (_mixing_output.armed().armed || _class_instance == -1) {
769+
if (_mixing_output.armed().armed || _class_instance == -1 || _mixing_output.useDynamicMixing()) {
712770
return;
713771
}
714772

@@ -1140,18 +1198,29 @@ int PX4IO::io_get_status()
11401198
status.pwm_failsafe[i] = io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i);
11411199
}
11421200

1143-
// PWM rates, 0 = low rate, 1 = high rate
1144-
const uint16_t pwm_rate = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES);
1201+
if (_mixing_output.useDynamicMixing()) {
11451202

1146-
const int pwm_low_rate = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE);
1147-
const int pwm_high_rate = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE);
1203+
int i = 0;
11481204

1149-
for (unsigned i = 0; i < _max_actuators; i++) {
1150-
if (pwm_rate & (1 << i)) {
1151-
status.pwm_rate_hz[i] = pwm_high_rate;
1205+
for (uint8_t offset = PX4IO_P_SETUP_PWM_RATE_GROUP0; offset <= PX4IO_P_SETUP_PWM_RATE_GROUP3; ++offset) {
1206+
// This is a bit different than below, setting the groups, not the channels
1207+
status.pwm_rate_hz[i++] = io_reg_get(PX4IO_PAGE_SETUP, offset);
1208+
}
11521209

1153-
} else {
1154-
status.pwm_rate_hz[i] = pwm_low_rate;
1210+
} else {
1211+
// PWM rates, 0 = low rate, 1 = high rate
1212+
const uint16_t pwm_rate = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES);
1213+
1214+
const int pwm_low_rate = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE);
1215+
const int pwm_high_rate = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE);
1216+
1217+
for (unsigned i = 0; i < _max_actuators; i++) {
1218+
if (pwm_rate & (1 << i)) {
1219+
status.pwm_rate_hz[i] = pwm_high_rate;
1220+
1221+
} else {
1222+
status.pwm_rate_hz[i] = pwm_low_rate;
1223+
}
11551224
}
11561225
}
11571226

@@ -1532,6 +1601,12 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
15321601

15331602
case PWM_SERVO_SET_UPDATE_RATE:
15341603
PX4_DEBUG("PWM_SERVO_SET_UPDATE_RATE");
1604+
1605+
if (_mixing_output.useDynamicMixing()) {
1606+
ret = -EINVAL;
1607+
break;
1608+
}
1609+
15351610
/* set the requested alternate rate */
15361611
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE, arg);
15371612
break;
@@ -1545,6 +1620,11 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
15451620
case PWM_SERVO_SET_SELECT_UPDATE_RATE: {
15461621
PX4_DEBUG("PWM_SERVO_SET_SELECT_UPDATE_RATE");
15471622

1623+
if (_mixing_output.useDynamicMixing()) {
1624+
ret = -EINVAL;
1625+
break;
1626+
}
1627+
15481628
/* blindly clear the PWM update alarm - might be set for some other reason */
15491629
io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
15501630

@@ -1579,7 +1659,7 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
15791659
}
15801660

15811661
for (unsigned i = 0; i < pwm->channel_count; i++) {
1582-
if (pwm->values[i] != 0) {
1662+
if (pwm->values[i] != 0 && !_mixing_output.useDynamicMixing()) {
15831663
_mixing_output.failsafeValue(i) = math::constrain(pwm->values[i], (uint16_t)PWM_LOWEST_MIN, (uint16_t)PWM_HIGHEST_MAX);
15841664
}
15851665
}
@@ -1613,7 +1693,7 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
16131693
}
16141694

16151695
for (unsigned i = 0; i < pwm->channel_count; i++) {
1616-
if (pwm->values[i] != 0) {
1696+
if (pwm->values[i] != 0 && !_mixing_output.useDynamicMixing()) {
16171697
_mixing_output.disarmedValue(i) = math::constrain(pwm->values[i], (uint16_t)PWM_LOWEST_MIN, (uint16_t)PWM_HIGHEST_MAX);
16181698
}
16191699
}
@@ -1645,7 +1725,7 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
16451725
}
16461726

16471727
for (unsigned i = 0; i < pwm->channel_count; i++) {
1648-
if (pwm->values[i] != 0) {
1728+
if (pwm->values[i] != 0 && !_mixing_output.useDynamicMixing()) {
16491729
_mixing_output.minValue(i) = math::constrain(pwm->values[i], (uint16_t)PWM_LOWEST_MIN, (uint16_t)PWM_HIGHEST_MIN);
16501730
}
16511731
}
@@ -1675,7 +1755,7 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
16751755
}
16761756

16771757
for (unsigned i = 0; i < pwm->channel_count; i++) {
1678-
if (pwm->values[i] != 0) {
1758+
if (pwm->values[i] != 0 && !_mixing_output.useDynamicMixing()) {
16791759
_mixing_output.maxValue(i) = math::constrain(pwm->values[i], (uint16_t)PWM_LOWEST_MAX, (uint16_t)PWM_HIGHEST_MAX);
16801760
}
16811761
}

src/lib/mixer_module/mixer_module.cpp

Lines changed: 28 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -461,7 +461,7 @@ bool MixingOutput::updateSubscriptionsDynamicMixer(bool allow_wq_switch, bool li
461461
}
462462

463463
} else if (all_disabled) {
464-
_interface.ScheduleOnInterval(300_ms);
464+
_interface.ScheduleOnInterval(_lowrate_schedule_interval);
465465
PX4_DEBUG("Scheduling at low rate");
466466

467467
} else {
@@ -817,19 +817,7 @@ MixingOutput::limitAndUpdateOutputs(float outputs[MAX_ACTUATORS], bool has_updat
817817
/* overwrite outputs in case of force_failsafe with _failsafe_value values */
818818
if (_armed.force_failsafe) {
819819
for (size_t i = 0; i < _max_num_outputs; i++) {
820-
if (_failsafe_value[i] == UINT16_MAX) { // if set to default, use the one provided by the function
821-
float default_failsafe = NAN;
822-
823-
if (_functions[i]) {
824-
default_failsafe = _functions[i]->defaultFailsafeValue(_function_assignment[i]);
825-
}
826-
827-
_current_output_value[i] = output_limit_calc_single(_reverse_output_mask & (1 << i),
828-
_disarmed_value[i], _min_value[i], _max_value[i], default_failsafe);
829-
830-
} else {
831-
_current_output_value[i] = _failsafe_value[i];
832-
}
820+
_current_output_value[i] = actualFailsafeValue(i);
833821
}
834822
}
835823

@@ -908,6 +896,32 @@ MixingOutput::updateLatencyPerfCounter(const actuator_outputs_s &actuator_output
908896
}
909897
}
910898

899+
uint16_t
900+
MixingOutput::actualFailsafeValue(int index)
901+
{
902+
if (!_use_dynamic_mixing) {
903+
return failsafeValue(index);
904+
}
905+
906+
uint16_t value = 0;
907+
908+
if (_failsafe_value[index] == UINT16_MAX) { // if set to default, use the one provided by the function
909+
float default_failsafe = NAN;
910+
911+
if (_functions[index]) {
912+
default_failsafe = _functions[index]->defaultFailsafeValue(_function_assignment[index]);
913+
}
914+
915+
value = output_limit_calc_single(_reverse_output_mask & (1 << index),
916+
_disarmed_value[index], _min_value[index], _max_value[index], default_failsafe);
917+
918+
} else {
919+
value = _failsafe_value[index];
920+
}
921+
922+
return value;
923+
}
924+
911925
void
912926
MixingOutput::reorderOutputs(uint16_t values[MAX_ACTUATORS])
913927
{

src/lib/mixer_module/mixer_module.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,8 @@
5454
#include <uORB/topics/parameter_update.h>
5555
#include <uORB/topics/test_motor.h>
5656

57+
using namespace time_literals;
58+
5759
/**
5860
* @class OutputModuleInterface
5961
* Base class for an output module.
@@ -187,6 +189,11 @@ class MixingOutput : public ModuleParams
187189
uint16_t &minValue(int index) { return _min_value[index]; }
188190
uint16_t &maxValue(int index) { return _max_value[index]; }
189191

192+
/**
193+
* Returns the actual failsafe value taking into account the assigned function
194+
*/
195+
uint16_t actualFailsafeValue(int index);
196+
190197
/**
191198
* Get the motor index that maps from PX4 convention to the configured one
192199
* @param index motor index in [0, num_motors-1]
@@ -203,6 +210,8 @@ class MixingOutput : public ModuleParams
203210

204211
const char *paramPrefix() const { return _param_prefix; }
205212

213+
void setLowrateSchedulingInterval(hrt_abstime interval) { _lowrate_schedule_interval = interval; }
214+
206215
protected:
207216
void updateParams() override;
208217

@@ -330,6 +339,7 @@ class MixingOutput : public ModuleParams
330339
false; ///< whether or not the output module supports reversible motors (range [-1, 0] for motors)
331340
const char *const _param_prefix;
332341
ParamHandles _param_handles[MAX_ACTUATORS];
342+
hrt_abstime _lowrate_schedule_interval{300_ms};
333343

334344
uORB::SubscriptionCallbackWorkItem *_subscription_callback{nullptr}; ///< current scheduling callback
335345

src/modules/px4iofirmware/protocol.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -193,6 +193,10 @@ enum { /* DSM bind states */
193193
#define PX4IO_P_SETUP_SBUS_RATE 16 /**< frame rate of SBUS1 output in Hz */
194194
#define PX4IO_P_SETUP_THERMAL 17 /**< thermal management */
195195
#define PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION 18 /**< flight termination; false if the circuit breaker (CBRK_FLIGHTTERM) is set */
196+
#define PX4IO_P_SETUP_PWM_RATE_GROUP0 19 /* Configure timer group 0 update rate in Hz */
197+
#define PX4IO_P_SETUP_PWM_RATE_GROUP1 20 /* Configure timer group 1 update rate in Hz */
198+
#define PX4IO_P_SETUP_PWM_RATE_GROUP2 21 /* Configure timer group 2 update rate in Hz */
199+
#define PX4IO_P_SETUP_PWM_RATE_GROUP3 22 /* Configure timer group 3 update rate in Hz */
196200

197201
#define PX4IO_THERMAL_IGNORE UINT16_MAX
198202
#define PX4IO_THERMAL_OFF 0

0 commit comments

Comments
 (0)