Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

pwm_out_sim: refactor to work queue and use the MixingOutput library #13205

Merged
merged 8 commits into from
Oct 21, 2019

Conversation

bkueng
Copy link
Member

@bkueng bkueng commented Oct 16, 2019

This refactors pwm_out_sim to use the MixingOutput library so that SITL uses the same code as on HW.
It also adds support for the test_motor uORB topic (motor_test CLI command) to MixingOutput (it works in SITL as well).
Next we can interface that to MAVLink, which possibly requires more changes to the uORB topic.

Tested with DShot + FMU PWM, SITL and HITL.

Checking the first output_limited for a disarmed value is fragile.
For example a disarmed value might be within the range of min/max output
values and could then be triggered while armed.
@bkueng bkueng force-pushed the pwm_out_sim_refactor branch from e3c0a9d to 0860638 Compare October 16, 2019 11:36
@bkueng bkueng force-pushed the pwm_out_sim_refactor branch from 0860638 to ffbd166 Compare October 16, 2019 12:07
…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.
@bkueng bkueng force-pushed the pwm_out_sim_refactor branch from 010bb95 to c9524f5 Compare October 17, 2019 06:01
@julianoes julianoes self-requested a review October 17, 2019 09:58
Copy link
Contributor

@julianoes julianoes left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Very nice, lots of red!

break;

case PWM_SERVO_GET_DEFAULT_UPDATE_RATE:
*(uint32_t *)arg = 400;
*(uint32_t *)arg = 9999;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Couldn't this be the MAVLink update rate of 250 Hz?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It depends on the use-case and config. There is no good value, and this one makes that clear.

_groups_required = 0;
}

_mixing_output.resetMixerThreadSafe();
break;

case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strnlen(buf, 1024);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Where does this 1024 value come from?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's get rid of it then: 7bbcc15
It's not needed, the buffer is guaranteed to be null-terminated.

@@ -70,6 +73,12 @@ _control_latency_perf(perf_alloc(PC_ELAPSED, "control latency"))
#endif

px4_sem_init(&_lock, 0, 1);

// Enforce the existence of the test_motor topic, so we won't miss initial publications
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why would we miss initial publications otherwise? I want to understand that.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If the topic does not exist, the subscriber checks for the existence in delayed intervals, which is typically not an issue. We however need to get the data immediately upon first publication here.

src/lib/mixer_module/mixer_module.cpp Outdated Show resolved Hide resolved
src/lib/mixer_module/mixer_module.hpp Show resolved Hide resolved
@@ -226,6 +252,7 @@ class MixingOutput : public ModuleParams

bool _safety_off{false}; ///< State of the safety button from the subscribed _safety_sub topic
bool _throttle_armed{false};
bool _ignore_lockdown{false}; ///< if true, ignore the _armed.lockdown flag (for HIL outputs)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do we do lockdown if when the ignore it again? That seems weird.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, why can't pwm_out_sim be oblivious to HIL?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I initially thought so I well, when I tested HIL and it did not work.
Commander sets lockdown in HIL mode unconditionally. It is an additional safety-precaution, to avoid real actuators from responding. And given the importance of that I find this not a bad idea.

@dagar
Copy link
Member

dagar commented Oct 17, 2019

I'm now wondering if this should be a "PWM" output sim driver at all.

We do all this work to mix and create PWM outputs, then in both the simulator and mavlink modules we have this chunk of code that based on vehicle type (MAV_TYPE) and typical mixers undoes the PWM scaling, including guessing at servos vs ESCs.

The mixer already has this information, so why not just skip the PWM part entirely and publish the control outputs [-1, 1] ([0, 1] for motors)?

https://github.com/PX4/Firmware/blob/be1f966e5f793206cc418711d17d8b4431d7b6c2/src/modules/simulator/simulator_mavlink.cpp#L78-L171

https://github.com/PX4/Firmware/blob/be1f966e5f793206cc418711d17d8b4431d7b6c2/src/modules/mavlink/mavlink_messages.cpp#L3093-L3167

https://mavlink.io/en/messages/common.html#HIL_ACTUATOR_CONTROLS

image

mixer.cpp ensures the string is null-terminated (buffer length is 2048).
The assumption is that the system can only ever get into armed state if
the safety button is already off.
@bkueng
Copy link
Member Author

bkueng commented Oct 18, 2019

I'm now wondering if this should be a "PWM" output sim driver at all.

We can look into that, yes (outside the scope of this PR).

@dagar
Copy link
Member

dagar commented Oct 18, 2019

I'm now wondering if this should be a "PWM" output sim driver at all.

We can look into that, yes (outside the scope of this PR).

That's fair, although it actually came to mind from the comment above discussing PWM_SERVO_GET_DEFAULT_UPDATE_RATE.

@bkueng bkueng merged commit f956baf into master Oct 21, 2019
@bkueng bkueng deleted the pwm_out_sim_refactor branch October 21, 2019 07:42
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants