Combine feedforward control with the PX4 control structure

Hi everyone,

TL;DR:
What’s the best way to fuse flatness-based feedforward terms with the current PX4 feedback controllers? In this post we bring up possible ideas and discuss their implementation, focusing quite a bit on the mixing procedure. If there’s a way to do this, great. If there’s a way to do something similar/with limitations, also quite ok. Any advice / experience is welcome.

Our system and current status:
We are currently working with an Intel Aero running the PX4 flight stack v1.9.2. So far we’ve been flying offboard, providing trajectories via mavros/setpoint_raw/local. The trajectory generator is implemented in MATLAB, calculates trajectories for position, yaw, and their derivatives up to snap, and finally fills in position and yaw in the mavros message.

Goal:
We expect better tracking performance exploiting the flatness property of the system. Hence, instead of directly using the trajectory generator for setpoints, we want to use it to calculate feedforward terms, send them to the flight controller and use the PX4 controllers for feedback stabilization. Hence we are looking for a method to fuse our feedforward terms with the PX4 feedback terms.

Shortly on the math:
For the flatness parametrization we followed this paper (without drag though). The underlying model is best depicted here in equations (1)-(7), as here thrust and torque are already linked to forces via the parameter kappa. Forces will later be linked to PWM as described below. So with this approach we know the desired values for motor forces, PWM, body rotation etc.

What to feedforward:
This variety of values first brings up the question what to feedforward. Ideas include:

  1. PWM values, as that’s the purest form of feedforward
  2. thrust and body rates, but still relying on the internal mixing structure.

So far 2) is preferred, as it allows to use, e.g., the internal saturation regulations and is more likely to work with ROS (which is desired due to the current project status).

How to feedforward:
To provide thrust and body rates, these are the ideas we investigated:

  1. MC_ROLLRATE_FF, MC_PITCHRATE_FF, MC_YAWRATE_FF seem to only be multiplicative factors but not allow to superimpose our feedforward values.
  2. if we’d continue working with MAVROS (which is desired to keep working with ROS)
    2.1) MAVROS/setpoint_raw/attitude allows to send body rates and thrust and is successfully used, e.g., by @Jaeyoung-Lim in his github repo. However, it looks like these values first pass another PX4 controller and hence are not really feedforward values (correct me if I’m wrong). Maybe an inverted model of the controller behavior could be derived to backcalculate the pure feedforward values to setpoints.
    2.2) MAVROS/actuator_control seems to provide the pure mixer input. However, we are not sure how this could be combined with the existing controller, as it rather sounds like overwriting / disabling the current control values (again, correct me if I’m wrong).
  3. Leave ROS and set up our own PX4 module that reads in the trajectory via a newly defined message, calculates feedforward terms, and sends them to the fmu, where they have to be fused with the PX4 control values.

Because 3) involves undesired fiddling around with the fmu module, 2) was used for further investigation.

Parameters in mixing
This further investigation mainly included the mixer structure (seems to be not well understood topic quite often, as indicated, e.g., here). Hopefully this post can get us a step closer to a full documentation).

Say we manage to fuse the feedforward terms with the PX4 control values and can input that in the mixer. We now want to make sure the internal mixer fits our model mentioned above, in order to provide the correct values in the first place. We inspected the mixer table creation in px_generate_mixers.py and compared the result to our model. Adapting motor positions and the constants Ct and Cm in the geometry file (quad_x.toml) or the scale values in the mixer file (quad_x.main.mix) allow to fit the mixer table to our table (i.e. to kappa and the arm length). Also forces and be linked to PWM via the parameter THR_MDL_FAC. However, some questions remain open:

  1. It’s not clear whether physical quantities like the arm length should be included at all. The default geometry lists motor positions to be +/-sqrt(2)/2, which leaves open whether the position must be normalized or is in meters. Also if the multiplied actuator controls vector and the resulting force vector is unitless, why would the matrix include units? Although we don’t understand it, it’s suggested e.g. here that units occur in the matrix.

  2. Same goes for the inertia. In our model we map forces to thrust and torques, no inertia needed for that. But actuator controls includes body rates instead of torques, so one would need another matrix multiplication as suggested in jlecoeurs notebook (chapter “Taking Mass and Inertia into account”), right? Or does PX4 normalize values in a way that torques and body rates can be used interchangeably? If so, where?

  3. Multiple mixer header files are generated by px_generate_mixers.py . Which one should be used? In line 194 of the same file it says normalized values should not be used, but they seem to be the default choice in mixer_multirotor.cpp#71. Is there any reason for this?

Conclusion:
I know this was a lot now, but I did not want to split this into multiple topics to keep the bigger picture and use synergies.

Maybe some people can share insight even only on subparts, any advice / experience / discussion is warmly welcomed.

Best Regards,
Dominik

1 Like

Hi,I’m starting to work to the same topic for a master thesis, I need to implement the HOSM (Higher order sliding mode) control into the PX4 firmware so i need to use a feedforward strategy too, i’m trying to understand how the control strategy works and how to add/modify the code to implement it. For the moment i think that the easiest way is to leave the control how it is (since it has all the failsafe mode implemented like landing etc.) and put in parallel my controller giving to the actuators only the outputs computed by the new contro strategy. It’s everithing work in progress but we could help each others.

Hi,
sounds like an interesting thesis! Unfortunately, I’m not involved in the project anymore and am not in a position to say whether your approach will work out or not. All I can do is point you to a discussion we had with @Jaeyoung-Lim, which made use leave this idea behind. Maybe it is interesting for you to read as well. :slight_smile:

1 Like