New TriCopter-Quadplane Concept

Hi guys

Thought I’d start a thread based on a new concept I’m working on. Basically, this is a reverse tricopter using the QuadPlane code with a twist. At the centre of the frame, I’m adding a EDF unit at the centre (C.G) that will provide (some) vertical thrust in QHOVER and then rotate to horizontal position for foward flight.

I have succeeded in getting the tricopter to hover (with tail rotor facing forward). The question I have for the Dev team, how can I drive the EDF in hover so that some thrust is derived from throttle position and then rotate the EDF when switching into forward flight? The EDF will provide forward thrust in cruise. Wings not shown in image.

Thanks!

Fanman

using plane throttle output may work, if not will require some small code changes

Thanks Peter. My understanding is that plane throttle is inactive when in QHOVER mode? Is there a setting to link plane throttle to assist with lift?

Hey, just saw this… http://ardupilot.org/copter/docs/booster-motor.html#booster-motor

Only question is how can I link boost motor SERVOx_FUNCTION = 81 to plane throttle in forward flight?

cheers

Fanman

it will need a small code change i think

As far as I know you might need a small chage in the code.

Thanks guys. I’m not really a software engineer so some guidance would be appreciated.

From what I can see,

  1. In QHOVER -> SERVOx_FUNCTION = 81
  2. In FBWA or Auto -> SERVOx_FUNCTION = 70

Help please :slight_smile:

Hi Dev Team

I have setup the ArduPilot dev environment on my PC in hope to modify code. I’m seeking advice from the community as to the entry point into the code to make the correct changes.

On the surfcae it would appear that all I need to do is to change the servo assignments between BOOST and Plane Throttle between flight modes. After reviewing the documentation online regarding RC_Channel, now I’m not so sure.

I’m keen to figure this out, I just need some guidance as to the correct entry points in the code and best approach.

regards

Fanman

realflight SITL is great for testing this stuff.

Boost motor is a sensible way to go, first thing to do is check that it works for quadplanes in hover. Then assign it to just be throttle pashtough for forward flight.

probably here would be a good place, something like:

SRV_Channels::set_output_scaled(SRV_Channel::k_boost, tilt.current_throttle);

there might be one or two other thing to do but that should be a good start

Hey thanks for the advice Peter I’ll give it a go. :grinning:

I plan to rig up an EDF and test booster first. I’m hoping there’s nil torque from the EDF to worry about so should work OK with the tricopter config.

The other thing I noticed in the code is that k_boost_throttle has a scale factor applied to it, so if I was to map it to k_throttle in forward flight, I’ll need to set scale factor = 1.

cheers

Fanman

the boost output in multiopter mode is done here,

ie the scaling is not inherent in the output function, you can pass it whatever you like.

My proposed changes in tiltrotor.cpp

/*
update motor tilt for continuous tilt servos
*/

 if (!hal.util->get_soft_armed()) {
        tilt.current_throttle = 0;
    } else {
        //
        // the motors are all the way forward, start using them for fwd thrust
        //
        uint8_t mask = is_zero(tilt.current_throttle)?0:(uint8_t)tilt.tilt_mask.get();
        //
        //Fanman - comment motor output as not needed
        //motors->output_motor_mask(tilt.current_throttle, mask, plane.rudder_dt);

        //Fanman - code for EDF throttle control when tilt
        SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, tilt.current_throttle);

        // prevent motor shutdown
        //Fanman - Is below required?
        tilt.motors_active = true;
    }
    return;
}

To the Dev Community,

I’m seeking advise on running my modified code using SITL within RF9. I’m planning on using Tridges Big Stik TiltRotorTri rev4_AV.RFX model with custom parameters.

My question is, can this model deal with the tilt mask for my configuration? i.e. I’m not tilting the tricopter motors, rather just the boost motor.

Any tips?

thanks

Fanman

you may be right, you need to set the tilt mask to something to enable the tilt rotor stuff, i suggest you enable it for motor 4 (that you don’t have on a tricopter)

You will have to add in the boost motor and tilt in realflight, should be fairly straightforward.

Thanks Peter.

Just checked out the edit function in RF9. Impressive stuff. I have a few questions about RF9;

  1. How is the main gas motor controlled? I can’t see this in the component list. Should I just ignore it?
  2. I see lift motors are assigned as per APM motor numbering so looks good. How can I assign the boost motor so it connects to APM?
  3. Once all this has been setup and assume to work, how can I monitor the booster motor output so i know its generating thrust?

cheers

Fanman

its not really there, the graphics don’t match the physics.

You would assign the motor a throttle servo and give the throttle servo a input channel in the servos tab

You can check that the motor throttles up in the physics model when you move the correct Chanel on the transmitter, the physics editor disconnects ardupilot however. Best thing do is check in the mission planner servo outputs tab that it’s doing the correct thing, or put it on the HUD as a user item.

You may be interested in this PR: https://github.com/ArduPilot/ardupilot/pull/11763
It uses an extra RC channel to control forward thrust of both front motors of the Convergence tilt-tri quadplane.
https://www.youtube.com/watch?v=mcReMZPdKDA

And an alternative approach which creates new flightmodes which mix throttle to forward thrust when above mid-stick: https://github.com/ArduPilot/ardupilot/pull/12857
https://www.youtube.com/watch?v=timf7x0q1jQ

Thanks Mark. I will look into it. I finally got my SITL model working and uploaded new code.

Only change was to scale the throttle output.

SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, tilt.current_throttle*1000);

I can successfully hover in QHover and if I’m careful, I can transition in FBWA. Monitoring the channels, I can see throttle and tilt servo outputs transition (although max throttle is limited so need to understand why).

The transition can be chaotic at times and I think it’s related to the Q_ASSIST options. As the Booster motor tilts, the tricopter motors seem to overcompensate or something along those lines and the model can flip, spin and crash. So I turned Q_ASSIST off. I also had to change some of the following parameters;

Q_TILT_MASK = 31 (i.e. non of the available lift motors to be on in FWD flight. Need this for Tilt servo to work)
Q_TILT_MAX = 80

Sometimes this works, but there are times when the lift motors won’t disengage after transition.

Maybe I need some code to shut down lift motors after transition?

thanx

Fanman

So been have a bit more fun with this. I have placed some code to manually switch off lift motors after transition (well its a bit crude, I’m commanding Motors 1, 2 & 4 to go to standby directly). With Q_ASSIST disabled, I can get reasonable transitions now without flipping, although there is a loss of altitude.

My question to the group, how does the algorithm deal with the assisted lift during the transition? I see that the lift motors start spooling down as the booster motor tilts but I’m not sure where that control is coming from?

I would like to have some Q_ASSIST applied somehow to allow a longer transition without the model flipping and spiraling out of control.

Do you have a github branch with your changes in? I think the code should handle transition fine. Maybe you could also PR your realflight model to the SITL models repo. We can then also have a play and see if we can get to the bottom of whats going on.

The aircraft just uses the assist motors to maintain altitude until your min airspeed has been reached, then it fades them out over 2 seconds or so. It may just be a case of your min air speed is set too low, ARSPD_FBW_MIN is the param.