Control multicopter via thrust F and moments M

Hello everyone,

For my current project, I need to control my quadrotor via a scalar thrust F and a moment vector M.

So far, I am aware of the following:

  • The general multicopter controller is defined in Firmware\src\modules\mc_att_control.
  • The mc_att_control does not send any PWM signals directly to the motors. It only sends a uORB/ORB message with the topic vehicle_attitude_setpoint or vehicle_rates_setpoint depending on the flight mode. I wasn’t able to figure out, which module is on the receiving end.
  • There exists the ACRO flight mode, which controls the multicopter via angular velocities. Am I right to assume, that the controller first calculates the angular moments based on the angular velocities and afterwards the PWM inputs based on the moments? If so, is this done by a Mixer?

Now my question is as follows:
How would I implement a controller, which controls the multicopter via thrust and moments? What are the uORB-topics I would need to use? Or is there already something similar?
I guess, I would be able to calculate the needed PWM signals based on the calculated thrust/moments if this is the only way.

Thank you!

1 Like

mc_att_control also publishes vehicle_actuator_controls
Then vehicle_actuator_controls are handled by the mixer in the output module such as fmu.cpp (for AUX pins) or the px4io.cpp (also see these docs).

I think that’s correct, it’s currently done by the mixer.

You could investigate if you can make a pass-through mixer (like this) and then do the mixing (or whatever you call it) beforehand yourself.

Hi, I am having the same problem. Have you found any solution?

Not yet.
But I think the way to go would be either by creating an entirely new multicopter-controller based on mc_att_control or writing a simple app depending on where you calculate your control inputs.
Both then need to be combined with a passthrough mixer (e.g. /etc/mixers/IO_pass.main.mix).
If you have done any work yet, please let me know, maybe we can combine forces if our research topics match!

Yes, I am reading the mc_att_control.cpp in the px4. I guess the first question for me is to find out how the normalised thrust value is processed in the current controller.

I will let you know, if I get some news

So it’s still WIP but here is, what I achieved so far:

  • I pulled PR #10863 for a modified PX4 Firmware and merged it with the current stable v1.8.2
    – Note: there exists a corresponding PR for the changed MAVROS message (PR #1120) but for now I skipped that.
  • I deactivated the auto-lander module in my make-file as it was interfering and forced a mode switch to AUTO.LAND. In my case the edit was done in the cmake config for Aerocore 2.
  • Now I added a uORB publisher to the mc_att_control_main.cpp file in L#766. The code for that is basically:
_v_control_mode.flag_control_motor_output_enabled = true;
if (_v_control_mode_pub != nullptr) {
	orb_publish(ORB_ID(vehicle_control_mode), _v_control_mode_pub, &_v_control_mode);
}
else {
	_v_control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &_v_control_mode);
}

Remeber to add orb_advert_t _v_control_mode_pub{ nullptr }; /**< control mode publication */ in the mc_att_control.hpp.

  • Now (just for testing) I’ve manually overridden the control-inputs. One could do that via:
// Override the _actuators value
_actuators.control[0] =  1.0f;
_actuators.control[1] = -1.0f;
_actuators.control[2] = -1.0f;
_actuators.control[3] =  0.0f;

But remember that the input scales from -1 to 1.

Next step is obviously to implement the mentioned controller but I figured just controlling each motor on it’s own might help already.

And as this is by far more than a “hacky” way of doing so and as it is still WIP, not intended for testing, … I did not push my changes anywhere. I’ll probably do so, once I got it working in a more flexible and usable way.

2 Likes

I am also interested in this, but in fixed-wing case. I have Force and Moment vectors.

Hi, do you have any news?

Do you have any news?

Hi, if you manage to directly control motors, let us know.

1 Like

With the latest addition of control allocation feature, this (commanding Force and Moment) is directly supported: Control Allocation (Mixing) | PX4 User Guide

Note that the units aren’t in scientific units, but rather normalized on vehicle’s maximum capable Force/Moment, for which you would need a mapping gain (for normalization)

1 Like