Browse Source

OutputModuleInterface::updateOutputs return bool to control actuator_outputs pub

Required for pwm_out_sim: only publish actuator_outputs when we get
actuator_controls. Otherwise lockstep startup does not work.
The issue was there before but hidden, due to a long poll timeout.

Works with HIL too.
sbg
Beat Küng 5 years ago
parent
commit
a8f6622831
  1. 8
      src/drivers/dshot/dshot.cpp
  2. 6
      src/drivers/pwm_out_sim/PWMSim.cpp
  3. 2
      src/drivers/pwm_out_sim/PWMSim.hpp
  4. 8
      src/drivers/px4fmu/fmu.cpp
  5. 21
      src/lib/mixer_module/mixer_module.cpp
  6. 11
      src/lib/mixer_module/mixer_module.hpp

8
src/drivers/dshot/dshot.cpp

@ -146,7 +146,7 @@ public: @@ -146,7 +146,7 @@ public:
hrt_abstime edge_time, uint32_t edge_state,
uint32_t overflow);
void updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
void mixerChanged() override;
@ -686,11 +686,11 @@ void DShotOutput::mixerChanged() @@ -686,11 +686,11 @@ void DShotOutput::mixerChanged()
updateTelemetryNumMotors();
}
void DShotOutput::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
bool DShotOutput::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated)
{
if (!_outputs_on) {
return;
return false;
}
int requested_telemetry_index = -1;
@ -740,6 +740,8 @@ void DShotOutput::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS @@ -740,6 +740,8 @@ void DShotOutput::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS
if (stop_motors || num_control_groups_updated > 0) {
up_dshot_trigger();
}
return true;
}
void

6
src/drivers/pwm_out_sim/PWMSim.cpp

@ -79,11 +79,13 @@ PWMSim::Run() @@ -79,11 +79,13 @@ PWMSim::Run()
_mixing_output.updateSubscriptions(true);
}
void
bool
PWMSim::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs,
unsigned num_control_groups_updated)
{
// nothing to do, as we are only interested in the actuator_outputs topic publication
// Nothing to do, as we are only interested in the actuator_outputs topic publication.
// That should only be published once we receive actuator_controls (important for lock-step to work correctly)
return num_control_groups_updated > 0;
}
int

2
src/drivers/pwm_out_sim/PWMSim.hpp

@ -66,7 +66,7 @@ public: @@ -66,7 +66,7 @@ public:
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;
void updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
private:

8
src/drivers/px4fmu/fmu.cpp

@ -156,7 +156,7 @@ public: @@ -156,7 +156,7 @@ public:
void update_pwm_trims();
void updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
private:
@ -719,11 +719,11 @@ PX4FMU::update_pwm_out_state(bool on) @@ -719,11 +719,11 @@ PX4FMU::update_pwm_out_state(bool on)
}
void PX4FMU::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
bool PX4FMU::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated)
{
if (_test_mode) {
return;
return false;
}
/* output to the servos */
@ -739,6 +739,8 @@ void PX4FMU::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], @@ -739,6 +739,8 @@ void PX4FMU::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
if (num_control_groups_updated > 0) {
up_pwm_update();
}
return true;
}
void

21
src/lib/mixer_module/mixer_module.cpp

@ -308,9 +308,11 @@ bool MixingOutput::update() @@ -308,9 +308,11 @@ bool MixingOutput::update()
unsigned num_motor_test = motorTest();
if (num_motor_test > 0) {
_interface.updateOutputs(false, _current_output_value, num_motor_test, 1);
actuator_outputs_s actuator_outputs{};
setAndPublishActuatorOutputs(num_motor_test, actuator_outputs);
if (_interface.updateOutputs(false, _current_output_value, num_motor_test, 1)) {
actuator_outputs_s actuator_outputs{};
setAndPublishActuatorOutputs(num_motor_test, actuator_outputs);
}
checkSafetyButton();
handleCommands();
return true;
@ -375,14 +377,13 @@ bool MixingOutput::update() @@ -375,14 +377,13 @@ bool MixingOutput::update()
reorderOutputs(_current_output_value);
/* now return the outputs to the driver */
_interface.updateOutputs(stop_motors, _current_output_value, mixed_num_outputs, n_updates);
if (_interface.updateOutputs(stop_motors, _current_output_value, mixed_num_outputs, n_updates)) {
actuator_outputs_s actuator_outputs{};
setAndPublishActuatorOutputs(mixed_num_outputs, actuator_outputs);
actuator_outputs_s actuator_outputs{};
setAndPublishActuatorOutputs(mixed_num_outputs, actuator_outputs);
publishMixerStatus(actuator_outputs);
updateLatencyPerfCounter(actuator_outputs);
publishMixerStatus(actuator_outputs);
updateLatencyPerfCounter(actuator_outputs);
}
checkSafetyButton();
handleCommands();

11
src/lib/mixer_module/mixer_module.hpp

@ -66,7 +66,16 @@ public: @@ -66,7 +66,16 @@ public:
OutputModuleInterface(const char *name, const px4::wq_config_t &config)
: px4::ScheduledWorkItem(name, config), ModuleParams(nullptr) {}
virtual void updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
/**
* Callback to update the (physical) actuator outputs in the driver
* @param stop_motors if true, all motors must be stopped (if false, individual motors
* might still be stopped via outputs[i] == disarmed_value)
* @param outputs individual actuator outputs in range [min, max] or failsafe/disarmed value
* @param num_outputs number of outputs (<= max_num_outputs)
* @param num_control_groups_updated number of actuator_control groups updated
* @return if true, the update got handled, and actuator_outputs can be published
*/
virtual bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) = 0;
/** called whenever the mixer gets updated/reset */

Loading…
Cancel
Save