VTOL Airframe - reusing MC motors in FW mode

Hello

Iā€™ve been experimenting with an idea for a VTOL airframe similar to the standard VTOL ( i.e. Fun Cube quad VTOL). It would fly as a quad + when in MC mode and when in FW mode the MC motors would be ā€œrepurposed" to provide pitch and roll control ( this would seem relatively straight forward in a quad + config).

Horizontal Thrust and yaw control would be provided by twin motor configuration, i.e. two extra motors, left and right, that are tilted 90deg to the MC motors (so horizontal) for a total of 6 motors.

Iā€™m keen to do away with having to use extra servos for aileron, elevator, rudder etcā€¦

Would this be possible?

I can get the standard Fun Cube configuration going and have tried to understand how the firmware knows which of the channels defined in the Main and Aux mixer files are used for the MC mode and for the FW mode. I have assumed thus far that the MC uses whatever is defined mixer files as R: and the rest are used for the FW mode, which seems to be the case in the experiments Iā€™ve done.

I was hoping there would be some indexing trickery that could be played on the mixers to give the FW controller to have access to the channels that are used by the MC, however I have not been able to understand the code well enough to make any progress.

Iā€™m aware that this might be a bit unorthodox and could be a wild goose chase as Iā€™m pretty new to this field, but since PX4 seems to be very flexible and configurable Iā€™m hopeful that someone might be able to give me some pointers.

Thank you all for your time.

Eduardo

Hi Eduardo,

The short answer is NO
using the quad motors in a quadplane config is aerodynamically a very bad idea. Also it would use a massive amount of energy compared to the servoā€™s.

Youā€™d have to modify the VTOL code, but itā€™s definitely possible.

As Sander said itā€™s likely not a great idea, but it would certainly be interesting to see!

If youā€™re still interested in pursuing this we could help get you started in the code. Thereā€™s also plenty of work that could be done to further improve the currently supported VTOLs.

Sanders, dagar thank you both for your replies.

Iā€™d be delighted to contribute to the effort, so Iā€™d certainly appreciate if you could help me get going.

I found a way to add this functionality externally with a HW multiplexer, but itā€™s not the most elegant, so doing it properly in a way that can be easily reused by others would be great.

I appreciate that this wouldnā€™t be a very efficient configuration, but I think it would be really helpful for those like me that want to experiment with different wing configurations. Iā€™m hoping that being able to test a wing on the platform without having to worry about installing flaps+servos will make trying out different configurations much easier and faster.

Dagar let me know how youā€™d like to proceed

Thanks

Should obviously read sanderaux, sanders is courtesy of the spellcheckā€¦

Hello dagar
Iā€™m keen to get started, can you let me know how to proceed?
Thanks
Eduardo

@ealdaz have a look at the standard.cpp code (itā€™s base class is vtol_type.cpp which you should also read). The following section disables the MC motors during FW flight: https://github.com/PX4/Firmware/blob/master/src/modules/vtol_att_control/standard.cpp#L403-L408, youā€™d want to remove that. There are also weight variables for multirotor control (like _mc_roll_weight) which are set to 0 during FW flight. They control how much output from the controller goes to the mixer. In the same code location you can play around with those weights and see what happens.

I think the tricky part will be the multirotor thrust weight, as you donā€™t want a lot of thrust but only attitude control. The mixing strategy in PX4 currently doesnā€™t work like this which means you wonā€™t get much attitude control with 0 thrust. I would start experimenting by giving some small thrust weight but full attitude (roll/pitch) weights.

I hope it is clear that you should start testing this without props and on the bench ;). Another option to play with this would be to create a model for the Gazebo simulation.

  • ada
1 Like

This is very helpful information, thanks! Also appreciate the direct link to the code, makes it very easy to follow.

I think playing with the weight variables is a good idea, I will experiment with that.

Thanks for pointing out the coupling between thrust and attitude control in the mc_controller, I too think this is the part that will make things tricky.

Ultimately I would like to be able to control the 4 motors with just pitch and yaw in FW_MODE, i.e. decoupled from thrust ( they will not be used for yaw)

I was hoping to be able to find a way to make the FW actuators ā€œpointā€ to the same hardware PWM channels that the MC actuators are using. For my testing purposes any sort of hack would be acceptable, doesnā€™t have to be a proper long term solution.

Or maybe change the mixer that is used to control the MC actuators and replace it by 4 simple mixer while in FW modeā€¦ if this was any easier?

I think you can try two things:
a) dynamically set the thrust weight according to the control inputs
b) remove the thrust limits in the mixer: https://github.com/PX4/Firmware/blob/0eac63787060c6d7eaa0643322f4e72fb0e8c458/src/modules/systemlib/mixer/mixer_multirotor.cpp#L265-L301

Option b is probably the most promising (and should give you exactly what you want) but also a bit more dangerous to test as you might run into corner cases without these limits while in actual MC mode. It would be interesting to see though. These limits are a hot topic for racers as they loose agility on full and 0 thrust. Maybe at some point we should have options to configure these limits for different applications.

Hi Andreas
Thanks for your tips,
I will try option a) to start with

I ended up modifying standard.cpp as you suggested originally. It works well enough for the first tests I think, I have set the throttle to a fixed value when in FW mode. The next step will be to properly adjust thrust weight like you suggested in your last post.

The steps I followed are:
1- Remove the section that disables the MC during Flight

void Standard::update_fw_state()
{
	VtolType::update_fw_state();

	// in fw mode we need the multirotor motors to stop spinning, in backtransition mode we let them spin up again
        
        //I don't want to disable MC motors so comment out
	if (!_flag_enable_mc_motors) {
		//set_max_mc(950); 
		//set_idle_fw();  // force them to stop, not just idle
		_flag_enable_mc_motors = true;
	}
        
}

2.- Instead of adjusting the weights I founded simpler to change the controls for the mc actuators to the FW ones when in FW mode, as follows:

void Standard::fill_actuator_outputs() { // multirotor controls
_actuators_out_0->timestamp = _actuators_mc_in->timestamp;

if ( _vtol_schedule.flight_mode == FW_MODE )
{

    // roll
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] =
            _actuators_fw_in->control[actuator_controls_s::INDEX_ROLL] ;       
// pitch
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] =
            _actuators_fw_in->control[actuator_controls_s::INDEX_PITCH];

// yaw  ( Don't require yaw from MC)
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = 0; 

// throttle ( Set to an experimental value that gives enough pitch and roll control)
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = 0.1;

}

else
{
    // roll
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] =
	_actuators_mc_in->control[actuator_controls_s::INDEX_ROLL] * _mc_roll_weight;
            
// pitch
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] =
	_actuators_mc_in->control[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight;
// yaw
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = 
	_actuators_mc_in->control[actuator_controls_s::INDEX_YAW] * _mc_yaw_weight;
// throttle
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] = 
	_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE] * _mc_throttle_weight;

}

Looks good. The first thing that comes to mind is the validity of sending the output of the FW attitude controller to the MC mixer for roll and pitch. The FW attitude controller scales the gains based on current airspeed relative to trim airspeed (https://github.com/PX4/ecl/blob/master/attitude_fw/ecl_roll_controller.cpp#L131).
In FW mode the MC attitude controller should still be running using the same attitude setpoint as the FW controller.

Didnā€™t realise that, good point.

Would there be anyway to use the actuators from control group #3 ( Manual passthrough) in standard.cpp ? Can there be accesible in this file somehow?

This is assuming that the output from the FW attitude controller are indeed what is also known Control Group #0 or #1ā€¦? but Iā€™m struggling a bit to follow code here so likely way off markā€¦

Iā€™m not quite following how that would help.

Just for clarity

_actuators_mc_in - control topic published by the MC attitude controller
_actuators_fw_in - control topic published by the FW attitude controller

_actuators_out_0 - MC motors on MAIN output (a VTOL convention)
_actuators_out_1 - FW motors and control surfaces

Iā€™m suggesting that in FW mode you continue copying the roll and pitch control value from the MC controller (_actuators_mc_in) to the MC output (_actuators_out_0). That is if you think the regular MC roll and pitch gains make sense during forward flight.

The reason I wanted to use the manual passthrough was to give me the option be able to control pitch/roll without interference from the FW attitude controller if it turned out to be an issue.

Iā€™ve modified vtol_att_control_main.cpp to subscribe to actuator_controls_3 instead of actuator_controls_virtual_fw and it works as expected (on the bench)

I have realised since that using the Manual Flight mode when on FW would have achieved the same thing, so I will be using that instead of my modification.

Regarding using MC output on FW mode, it was the first thing I tried a while back, but I had no success so I had assumed the MC controller was not running anymore. But I will check again.

Hello, I have read all your posts just now, itā€™s really interesting. There is a question about vtol puzzling me these days. I am studying how px4 converts actuators_control to pwm value recently. To vtol_att_control (eg tailsitter.cpp), there is both actuator_controls_0 and actuator_controls_1, I am confusing about the relationships of them. Is actuator_controls_0 mix by R: and actuator_controls_1 by M: as mixer file defined ? And then they two are convert to pwm value and be plused to drive motors or servos? I am really confusing.Any suggestions will be appreciate!

@ealdaz Did you get this working? Iā€™m doing something similar and am planning on using this as a starting point. Just curious if you got any further. Like, did it fly :slight_smile: