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

[RFC] control_allocator: Actuator Effectiveness with generalized configuration parameters (combined MC, VTOL, simple fixed wing support, custom torque, etc) #18558

Closed
wants to merge 1 commit into from

Conversation

dagar
Copy link
Member

@dagar dagar commented Nov 3, 2021

Currently in PX4 we have a legacy output mixing system (.mix files and airframe environment variables) and a wonderful new fully configurable output configuration system tied in with the control allocator. The new system is approaching feature parity for multicopter, but we're still firmly stuck in the old legacy mixer world for FW and VTOL. This pull request is an attempt to bridge that gap, reproducing the vast majority of what people actually use with SimplerMixer.

This pull request introduces a new ActuatorEffectiveness that provides more options for how each actuator is configured. Currently includes...

  1. custom thrust (same as ActuatorEffectivenessMultirotor, but with slightly different parameter naming)
  2. custom torque parameters (CA_ACTn_TRQ_{R,P,Y} for advanced users)
  3. Simple Aileron (roll torque with configurable scale factor CA_ACTn_SC)
  4. Simple Elevator (pitch torque and scale factor CA_ACTn_SC)
  5. Simple Rudder (yaw torque and scale factor CA_ACTn_SC)
  6. Simple Throttle (vehicle X thrust and scale factor CA_ACTn_SC)
  7. Elevon (+) (+roll & pitch torque and scale factor CA_ACTn_SC)
  8. Elevon (-) (-roll & pitch torque and scale factor CA_ACTn_SC)
  9. V-Tail (+) (pitch & +yaw torque and scale factor CA_ACTn_SC)
  10. V-Tail (-) (pitch & -yaw torque and scale factor CA_ACTn_SC)

Questions

  • does this capture the majority of our FW (and FW VTOL) usage?
  • if this is workable should we merge with ActuatorEffectivenessMultirotor and have one unified baseline ActuatorEffectiveness?

@dagar dagar changed the title [RFC] control_allocator: generalized configuration parameters (VTOL, simple fixed wing support, custom torque, etc) [RFC] control_allocator: Actuator Effectiveness with generalized configuration parameters (combined MC, VTOL, simple fixed wing support, custom torque, etc) Nov 3, 2021
@dagar dagar force-pushed the pr-control_allocator_custom_params branch from a791474 to 7e224d6 Compare November 3, 2021 02:08
@bresch bresch self-requested a review November 3, 2021 09:09
@bkueng
Copy link
Member

bkueng commented Nov 3, 2021

This looks good. For the metadata & UI to work, I see 2 things:

  • The setup_required flag is a fixed bool per actuator and cannot depend on a param (e.g. CA_ACT${i}_FUNC disabled or not). We could extend that, but simpler is to add an explicit 'count' parameter (which I wanted to do for MC as well), or just not requiring those to be assigned.
  • The metadata requires a fixed assignment for a list of actuators (dynamic or fixed size) to an actuator type.

It could look like this:

    config:
        param: CA_AIRFRAME
        types:
            0: # Multirotor
                type: "multirotor"
                actuators:
                  - actuator_type: 'motor'
                    count: 'CA_MC_R_COUNT'
                    per_item_parameters:
                        standard:
                            position: [ 'CA_MC_R${i}_PX', 'CA_MC_R${i}_PY', 'CA_MC_R${i}_PZ' ]
                        extra:
                          - name: 'CA_MC_R${i}_KM'
                            label: 'Direction CCW'
                            function: 'spin-dir'
                            show_as: 'true-if-positive'

            2: # Tiltrotor VTOL example
                actuators:
                  - actuator_type: 'motor'
                    instances:
                      - name: 'Front Left Motor'
                        position: [ 0.3, -0.3, 0 ]
                      - name: 'Front Right Motor'
                        position: [ 0.3, 0.3, 0 ]
                      - name: 'Rear Motor'
                        position: [ -0.75, 0.3, 0 ]
                  - actuator_type: 'servo'
                    instances:
                      - name: 'Front Left Tilt'
                        position: [ 0.3, -0.3, 0 ]
                      - name: 'Front Right Tilt'
                        position: [ 0.3, 0.3, 0 ]
                      - name: 'Left Elevon'
                        position: [ 0, -0.3, 0 ]
                      - name: 'Right Elevon'
                        position: [ 0, 0.3, 0 ]

            3: # custom
                actuators:
                  - actuator_type: 'motor'
                    count: 'CA_ACT_R_COUNT'
                    per_item_parameters:
                        standard:
                            position: [ 'CA_ACT${i}_PX', 'CA_ACT${i}_PY', 'CA_ACT${i}_PZ' ]
                        extra:
                          - name: 'CA_ACT_R${i}_THR_X'
                            label: 'Thrust X'
                          - name: 'CA_ACT_R${i}_THR_Y'
                            label: 'Thrust Y'
                          - name: 'CA_ACT_R${i}_THR_Z'
                            label: 'Thrust Z'
                  - actuator_type: 'servo'
                    count: 'CA_ACT_S_COUNT'
                    per_item_parameters:
                        extra:
                          - name: 'CA_ACT_S${i}_F'
                            label: 'Function'
                          - name: 'CA_ACT_S${i}_SC'
                            label: 'Scale'

@dagar
Copy link
Member Author

dagar commented Nov 3, 2021

Thanks @bkueng, the first quick thing I wanted to align on was parameter naming to try and minimize the number of generated parameters.

Things like position and even axis will be reusable in other places, any objection to updating AcutatorEffectivenessMulticopter to use the same parameters?

  • CA_MC_Rn_P{X,Y,Z} -> CA_ACTn_P{X,Y,Z}
  • CA_MC_Rn_A{X,Y,Z} -> CA_ACTn_A{X,Y,Z}
  • CA_MC_Rn_CT -> CA_ACTn_CT
  • CA_MC_Rn_KM -> CA_ACTn_KM

@bkueng
Copy link
Member

bkueng commented Nov 3, 2021

Things like position and even axis will be reusable in other places, any objection to updating AcutatorEffectivenessMulticopter to use the same parameters?

I don't see any problem, as long as we don't use the same params for different actuator types in a single mixer config (the param indexing would not work that way).

Let me bring my current WIP upstream so we can better coordinate and reduce the amount of conflicts: #18563

@jlecoeur
Copy link
Contributor

jlecoeur commented Nov 3, 2021

Sounds good to me.
Elevons and Vtail might need different gains for their two effects, do you model that? (Haven't looked at the code yet)

@jlecoeur jlecoeur self-requested a review November 3, 2021 19:34
@dagar
Copy link
Member Author

dagar commented Nov 3, 2021

Elevons and Vtail might need different gains for their two effects, do you model that? (Haven't looked at the code yet)

No it's just a dumb split, and that's why manually entering the per axis torque is also an option.

This is simply intended as a crutch to get us off the old mixers, and didn't seem any worse than most of the current elevon and v-tail usage I've seen.

If/when these actuator functions need more parameterized configuration we'll probably need a slightly different approach to prevent a parameter explosion (every possible option for every possible actuator).

101: Elevator
102: Rudder
103: Throttle
104: Elevon (+)
Copy link
Member Author

Choose a reason for hiding this comment

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

Maybe left and right elevon would be better?

@dagar
Copy link
Member Author

dagar commented Nov 3, 2021

Here's a slight variation that just occurred to me.

Instead of the overly simplistic actuator functions being a scale factor, what if they were more like training wheels for editing the effectiveness directly? Selecting a particular function could unlock of appropriate torque parameters and enforce conservative constraints to keep it sane.

Examples

  • Actuator 2 Right aileron
    • read only CA_ACT2_TRQ_R (parameter is constrained [0, 1]), default parameter value is 1.0
  • Actuator 3 Left aileron
    • read only CA_ACT3_TRQ_R (parameter is constrained [-1, 0]), default parameter value is -1.0
  • Actuator 4 Elevator
    • read only CA_ACT4_TRQ_P (parameter is constrained [0, 1]), default parameter value is 1.0
  • Actuator 5 Right Elevon
    • read CA_ACT5_TRQ_R (parameter is constrained [0, 1]), default parameter value is 0.5
    • read CA_ACT5_TRQ_P (parameter is constrained [0, 1]), default parameter value is 0.5
  • Actuator 6 Pusher Throttle
    • read CA_ACT6_THR_X, etc

Perhaps later we could have a control allocation parameter for something like normalized or unit mode.

This way we'd preserve more context for interactive and semi automated preflight checks. Users would adjust the direction of the physical output (PWM, UAVCAN, etc), rather than the potential double negative.

Semi-automated preflight check routine

  • system raises right aileron fully up and asks the user to verify (click next), then full down (click next)
  • repeat for every actuator with user interactive verification

@jlecoeur
Copy link
Contributor

jlecoeur commented Nov 4, 2021

I like it because it involves fewer parameters and also helps more advanced users.
Where would the concept of "Right aileron" be implemented? In the GUI only? If yes, it makes me wonder if the same should be done for multirotor: you enter the rotors position and axis in the GUI but in the end the lower level TRQ parameters are set.

@jstrebel
Copy link

jstrebel commented Nov 4, 2021

Just for my understanding.
Do you mean Elevator the rudders who control pitch up and down? Therefore we have a Elevon rudder on the right side and on the left side actuated by two servos.
(Personally I fly Fixed wing models for many years. Crashed happened to me either when the mechanical conection to a rudder was broken in the air or a servo died during flight)

Regarding non-linear deflections of servos for fixed wing I like to add.
It is common to add non-linear functions to the control deflections of rudders in order to adapt the servo deflection to the aircraft's inputs.
Exponential curves are common, where the rudder deflections are smaller near the center position and increase progressively outward. With positive and negative rudder deflections the progressivity is adjusted separately.
A simple solution would be to achieve non-linearity of the rudder travel via a control table. If necessary, I would be happy to make a sketch.

@dagar
Copy link
Member Author

dagar commented Nov 4, 2021

I like it because it involves fewer parameters and also helps more advanced users. Where would the concept of "Right aileron" be implemented? In the GUI only?

At the moment I'm talking about implementing/enforcing it within PX4, but ultimately the GUI will need to be in sync some how.

I'm imagining the full table of actuators and torque (roll/pitch/yaw), if "Right aileron" was selected for one of the actuators then the pitch and yaw cells would either be grayed out or forced to zero or something. You would also only be allowed to set the roll torque magnitude in the right direction.

Ideally the GUI could directly enforce these constraints, and internally PX4 would enforce it as a backup (or editing airframes directly). Shorter term the GUI allowing you to set a cell, then PX4 immediately updating it (zero or constrained) might also be good enough as a start.

If yes, it makes me wonder if the same should be done for multirotor: you enter the rotors position and axis in the GUI but in the end the lower level TRQ parameters are set.

I was wondering about that, but ultimately for the default or generic airframes we carry I think it's much more accessible or self explanatory as the rotor geometry.

I actually considered doing both, but it seemed a bit wasteful. The base ActuatorEffectiveness is nothing more than the full torque and thrust parameters per actuator, then there are specializations like multirotor or right aileron that help you generate those entries.

All that is to say, I don't know what the best overall solution is, but I'm flexible and committed to finding something that's workable for both the GUI and standalone airframe parameters.

@dagar
Copy link
Member Author

dagar commented Nov 4, 2021

Just for my understanding. Do you mean Elevator the rudders who control pitch up and down? Therefore we have a Elevon rudder on the right side and on the left side actuated by two servos. (Personally I fly Fixed wing models for many years. Crashed happened to me either when the mechanical conection to a rudder was broken in the air or a servo died during flight)

In this particular context it's about capturing the high level function from an actuator effectiveness perspective. Ailerons are split left and right because the roll torque is opposite. In the split elevator case a separate left and right elevator would be the same, but split elevons would be different.

Note you can add multiple actuators that are the same "function". If one of those actuators dies it can be removed from the effectiveness matrix, the mix would be recomputed (pseduo inverse), and the new mix would account for using only the remaining actuator. We'll need to come back to this later to think about the case of redundant actuators on the same control surface vs split control surfaces.

Regarding non-linear deflections of servos for fixed wing I like to add. It is common to add non-linear functions to the control deflections of rudders in order to adapt the servo deflection to the aircraft's inputs. Exponential curves are common, where the rudder deflections are smaller near the center position and increase progressively outward. With positive and negative rudder deflections the progressivity is adjusted separately. A simple solution would be to achieve non-linearity of the rudder travel via a control table. If necessary, I would be happy to make a sketch.

If this is primarily for implementing "expo" for the pilot then it should be handled on the input side (PX4 manual control setpoint in different modes).

Somewhat related for ESCs we currently have an optional thrust curve parameter (THR_MDL_FAC) to linearize. This idea can be expanded for other outputs if needed.

It sounds like we might want to expand that concept not just for ESCs (handling it differently for different motors), but also control surfaces.

@jstrebel
Copy link

jstrebel commented Nov 4, 2021

Regarding non-linear deflections of servos for fixed wing I like to add. It is common to add non-linear functions to the control deflections of rudders in order to adapt the servo deflection to the aircraft's inputs. Exponential curves are common, where the rudder deflections are smaller near the center position and increase progressively outward. With positive and negative rudder deflections the progressivity is adjusted separately. A simple solution would be to achieve non-linearity of the rudder travel via a control table. If necessary, I would be happy to make a sketch.

If this is primarily for implementing "expo" for the pilot then it should be handled on the input side (PX4 manual control setpoint in different modes).

The effect of progessive function like expo and "degressive" function depend mainly on the characteristic of the airplane. therefor I vote it is best to put it at the end (just in front to the actuator).

@dagar
Copy link
Member Author

dagar commented Nov 4, 2021

Thanks @jstrebel, we can definitely add that. If you have any specific details please start capturing them in a new issue.

We can think about how to parameterize the adjustment per physical output. I also wonder if it might be interesting to be able to optionally carry a full calibration for a control surface so you know the deflection angle?

@jstrebel
Copy link

jstrebel commented Nov 4, 2021

We can think about how to parameterize the adjustment per physical output. I also wonder if it might be interesting to be able to optionally carry a full calibration for a control surface so you know the deflection angle?

This would be most useful for the Flaps. But makes als sense for the elevon and ailerons.
BTW: what is the difference between Elevator and Elevon?

@dagar
Copy link
Member Author

dagar commented Nov 4, 2021

We can think about how to parameterize the adjustment per physical output. I also wonder if it might be interesting to be able to optionally carry a full calibration for a control surface so you know the deflection angle?

This would be most useful for the Flaps. But makes als sense for the elevon and ailerons. BTW: what is the difference between Elevator and Elevon?

Elevon (aka taileron) is combined roll + pitch mixing like on a flying wing.

@dagar
Copy link
Member Author

dagar commented Nov 4, 2021

We might as well throw canards on the list while we're at it.

@jlecoeur
Copy link
Contributor

jlecoeur commented Nov 4, 2021

We might as well throw canards on the list while we're at it.

Yes good point. Same thing as elevator, except with inverted sign. Will prevent fatal inversion during pre-flight check when the user is requested to check that the elevator/canard control surface deflects up and down.

@bkueng
Copy link
Member

bkueng commented Nov 8, 2021

Ok this is how a configurable standard vtol could look like on the UI side:
image

The constraints in the form of Type -> min/max/default/disabled {roll,pitch,yaw} torque params are not supported yet.
If everyone agrees I will go ahead and add that.

@dagar
Copy link
Member Author

dagar commented Nov 9, 2021

Ok this is how a configurable standard vtol could look like on the UI side: image

The constraints in the form of Type -> min/max/default/disabled {roll,pitch,yaw} torque params are not supported yet. If everyone agrees I will go ahead and add that.

Would this layout with the first entry pusher come from CA_AIRFRAME (quadplane) or is it selectable for a fully configurable ActuatorEffectivenessCustom?

The other thing we need for control surfaces is a configurable trim per actuator. Should we carry this at the level of the control allocator or the output module? At the moment it feels like it would be more intuitive pushed to the physical output where it could set in native units.

@bkueng
Copy link
Member

bkueng commented Nov 9, 2021

Would this layout with the first entry pusher come from CA_AIRFRAME (quadplane) or is it selectable for a fully configurable ActuatorEffectivenessCustom?

It comes from CA_AIRFRAME.

The other thing we need for control surfaces is a configurable trim per actuator. Should we carry this at the level of the control allocator or the output module? At the moment it feels like it would be more intuitive pushed to the physical output where it could set in native units.

My intention was to put this on the control allocator, so that saturation can be handled correctly.

Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

I've started playing around with dynamic control allocation for FW. Got it to fly in SITL without a lot of pain, I so far like the how the configuration is done (even without the nice UI).
Next up is doing the same with a standard VTOL.


case 103: {
// 103: Throttle, scaled (CA_ACTn_SC) X thrust
_effectiveness(4, n) = getScaleParameter(n);
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
_effectiveness(4, n) = getScaleParameter(n);
_effectiveness(3, n) = getScaleParameter(n);


float scale = 1.f;

if (param_get(param_handle, &scale) != PX4_OK) {
Copy link
Contributor

Choose a reason for hiding this comment

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

What's the intent here exactly? Shouldn't it set the scale to 0 in case of !PX4_OK, and otherwise to whatever the param resulted in?

@sfuhrer
Copy link
Contributor

sfuhrer commented Jan 7, 2022

Proceeded in #18776 - or do you want to keep this one for discussion around FW control surfaces configuration @dagar ? As we're there not quite 100% sure if the current approach is the best?

@dagar
Copy link
Member Author

dagar commented Jan 7, 2022

We can close this now. Thanks everyone.

@dagar dagar closed this Jan 7, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants