Fully articulated TVC bi-(or)-tandem copter.

So, it all starts as usual. It’s christmas and for whatever reason and you get the idea to build something weird.

As a short background, the last years I worked on coaxial TVC solutions, but never had the feeling (and the result) that I understood everything because…there is just too much wind blown, aerodynamic becomes manaic and really strange things happen. Flying yes, but good flying…no. Hence, I decided for myself to stick with thrust vector control, but to separate the coaxial props to a tandem- or bicopter arrangement. Make it easier! Yes…for sure…

Ok. each of the two rotor units can (thinking in chinhook configuration) rotated around the pich axis and roll axis, while yaw is motor differential and thrust is, thrust. I found on ardupilot discourse some Bi-Copters, some Bi-Copter with OAT (Oblique active Thrust) and Tandem helis, but no fully articulated like that one.

As you can imagine, it took some iterations to get to a somewhat decent, or acceptable build.

You may wonder why I use 2 actuators per axis. One one side I was interested if I could get them run simutanoulsy without blocking or additional load (yes, this was easy). This was also because I like redundancy. Moreover, I was really scared on the possible acting forces. Especially my very first build had a pain of oscilations which pretty much destroyed the servos, the gimbal frame and the linkage.

But it is all about learning. Ligher motor, lighter and better balanced props, stronger servos. Redesign everything. And testing.

When I was satisfied with the operation of one unit, I started to build the second propulsion unit.

And then, finally putting everything on a common frame.

It took me a little, but not much, to calibrate the two units together (ok. there is still a small missmatch, but, we’re talking about 0.05 to 0.15 degrees.).

What was my design mass? 8kg with batteries BEW. What did I achieve? 8.5kg, but with additional sensors, I did not take into account. My design is fully symetrically balanced…and the CoG is ALMOST where I targeted…just a tiny bit off because of stupid cables (…).

The Holybro 6x with the latest Arcuopter 4.5.6 loaded sits in the middle. The ESCs are VESCs 6.0 (I have good experience with them and they support UAVCAN).

.

Control works (it took me some nerves) to get all servos and the ESCs up and running…into the right direction. Always kind of funny that if you orientate the ardupilot into the right direction, the RC input does exactly what it is supposed to do, the AP corrects the roll correctly, but pitch corrections are reversed and I ask myself desperately…why? (unit I reversed the pitch on the RC side).

So, times to go into the wilderness.

And here I stop with my story and start to ask questions and suggestions, because it was not going sooo well. Not bad either (nothing burned down, nobody got hurt). But new rotorblades are need for sure.

I selected the COAX frame, because, instead of having flaps, I turn simply the the propulsion units. This should work. One little strange experience I have is, that the two motors should run up at the same time, but one is always slightly behind. If I change the nodes (CAN) it is visa versa, this indicates that it is not an ESC issue (I will verify). But my fault on the other side was that I selected “current control” (~torque] on the VESC instead of RPM control. This is something I can try, but I also saw this also already on the COAX I build (with RPM control turned on :wink: ). I am not sure if there is somewhere a native offset in the COAX config due to the assumed different rpm (or produced torque) of the upper and lower rotor blade.

It is NOT very stable, even though everything is very balanced and masses are somewhat distributed (I know false pendulum effect), but an equilibrium of inertia is good for balancing.

My question is, the dual-helicopter / tandem configuration would be an alternative frame. Since this is very simular to my configuration BUT not the swashplate and HENCE not a collective. Does anyone know if the collective could be set to unused and replaced with motor rpm instead?

Alternative would be bi-copter but then I either need to lock one servo axis or do some OAT approach.

6 Likes

Ok. I can’t find the edit function for my blog to correct some of my stupidities and (gramar, spelling) errors :smiley: , hence, I reply to myself.

First, some corrections: OAT = Oblique Active Tilting (not Thrust); second, obviously, after thinking more than 10secs about it, the COAX class is a good starting point, BUT since I’ve a tandem configuration, the mixing of thrust + yaw thrust (-yaw thrust), will immidiatelly cause a nose up/down pitch around the lateral axis.

    _thrust_yt_ccw = thrust_out + 0.5f * yaw_thrust;
    _thrust_yt_cw = thrust_out - 0.5f * yaw_thrust;

Two options here. Either I consider also pitch at the same time (which will be very tricky I guess, because a change in pitch will then cause a yaw moment…etc etc. ) or I leave for the beginning thrust as it is:

    _thrust_yt_ccw = thrust_out ;
    _thrust_yt_cw = thrust_out ;

My configuration would allow to use the pitch servo for pitch ( clear), and I could mix the yaw signal with the roll channel. This should look somehow like this:

_actuator_out[0] = (roll_thrust + yaw_thrust) / thrust_out_actuator;  // Left roll and yaw mixing servo
    _actuator_out[2] = (-roll_thrust + yaw_thrust) / thrust_out_actuator;  // Right roll and yaw mixing  servo
    _actuator_out[1] = pitch_thrust / thrust_out_actuator;  // Pitch servos
 _actuator_out[3] = -_actuator_out[1];

I guess the signs need to be checked, it does more or less what it is supposed to do, but I’ve not fully tested it yet.

What I think is a bit strange is, that the tilt is normalized with the thrust, and more thrust means more tilting of the servos. I am just wondering because my guts feeling (never trust the guts) would say, as more thrust, as less input I need. When x-checking with the tailsitter code, it appears to me (not a coding expert) that the tailsiter does not normalize with the thrust:

    // thrust vectoring
    _tilt_left  = pitch_thrust - yaw_thrust;
    _tilt_right = pitch_thrust + yaw_thrust;

Very intersting is actually the Dual Heli Tandem configuration:

// Differential cyclic roll is used for yaw and combined for roll
    const float swash1_roll = roll_input + _yaw_scaler * yaw_input;
    const float swash2_roll = roll_input - _yaw_scaler * yaw_input;

    // cyclic is not used for pitch control
    const float swash_pitch = 0.0;

    // Differential collective for pitch and combined for thrust
    const float swash1_coll =  0.45 * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective1_input;
    const float swash2_coll = -0.45 * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective2_input;

as starting point to think about. In this matter I found also ideas and asked if I couldn’t use the dual heli tandem configuration with no collective (fix pitch) as starting point as described here:

and

The VESCs work good. In the beginning the low RPM were a bit grumpy, especially my newer VESC has phase filters and they caused troubles (after switching them off, much less troubles during startup)… I installed now NTC resistors to compensate the temperature and installed AS5047d for rpm sensing (at low rpm during start up only up to 4000ERPM).

Now I’ll get rid of some play to reduce vibrations. Maybe someone gives me hint into which direction I should move with the software code :smiley:

Hi @tobiokanobi,
Dual heli would not support your frame. The problem is that it uses differential collective for pitch control. You could use it if you only need collective for thrust but since you need it for pitch then the mixer would not work. This would not be an easy fix either.

Hi @bnsgeyer,
I see what you mean. I actuatally assume that I do not need thrust for pitch (we all need thrust I know :slight_smile: , but what I mean is, that the vehicle would rather tilt the propulsion unit “forward” or “aft” or “left” and “right”). Basically it is a swashplate without collective. My current approach is to achieve the stability and directional control by pitch and mixed (roll/yaw) actuators. I already see some challenges when the tilt angles of the fwd and aft mixed (roll/yaw) ar e not identical and generate a different lift, but I move this in front of me… here is an older video to see it operating to illustrate the function of the propulsion unit gimbals. In this video I control it directly by RC signals, no autopilot (not flying).

Yes, using the pitch tilt rather than differential thrust may work. That would probably be an easy code change to use tilt instead. You would want to use the H1 swashplate since you are controlling swash pitch and roll directly.

Then you would use the throttle curve of the rotor speed controller to make the collective control throttle instead of collective blade pitch.

My quick thought was that it is definitely not a coax (FRAME_CLASS=9) but a bicopter (FRAME_CLASS=10).

If one has two counter-rotating propellers on the same shaft, controlled by different motors, and then you would gimbal them together in two axes - this would be nicely controllable by the coax frame. I did that twice, but a lot of engineering was improper in these projects, so I gave up for now.

But you seem to have two axes of gimbaling per each motor, and six degrees of control freedom in total, right? I am not sure that the coax frame does the right if you connect both “pitch” servos to say “motor 2” of coax, and both “roll” servos for say “motor 1” - solely because of how forces relate to the CoG and what they actually do.

And if they happen to do the right thing, we are in a different trouble, because the coax frame normalizes flap outputs to the total thrust of both motors, whereas in your case you probably need to do that separately for each motor, or nonzero pitch together will nonzero yaw would cause some extra yaw torque, the sign and strength of which depends on the sign and strength of pitch.

(The bicopter frame does not do flap normalization at all, as far as I remember, which ruined my experience with bicopters, but at least this is not that wild)

Thanks @bnsgeyer and @MaxBuzz for your replies. It seems like that I’ve two options and I’ll try both of them (one experiemental and one highly experimental :smiley: ).
@bnsgeyer I guess I select the servo outputs as described in the previous mentioned link

Blockquote
Servo #1: Aileron (in my case “Roll” actuator)
Servo #2: Elevator (in my case “Pitch” actuator)
Servo #3: Not Connected: Collective (which you’ll connect to throttle via the throttle curve)
Servo #4: Not Connected: Tailrotor (Rudder)
Servo #8: HeliRSC (throttle) This is controlled by the throttle curve.

And I believe you meant some code changes are necessary. A quick look into the AP_MotorosHeli_Dual.cpp

void AP_MotorsHeli_Dual::mix_tandem(float pitch_input......
.......
  // Differential collective for pitch and combined for thrust
    const float swash1_coll =  0.45 * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective1_input;
    const float swash2_coll = -0.45 * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective2_input;
.......

Seems that you mean to implement a change in code here to apply “tilt” instead of “differential thrust” via collective…hmmm…not sure @bnsgeyer but my first guess would be to simply calculate and apply the the average of collective1_input and collective2_input.

@MaxBuzz The Coax class was my baseline to some similarities in the setup. Which are technically identical to check function, but aerodynamically are’t, unfortunatelly. I’ve pretty much ereased and replaced all code in the COAX class for my use-case, but with the touch of, I’ve no f… clue what I am doing .
~Equal thrust on on both motors (not taking yaw, pitch (or roll) into account for the moment)
~Actuator 0, 2: Mixed roll and yaw input (scaling ~65% for roll and 35% for yaw) of the ~14° tilt I can do
~Actuator 1,3: Pitch
~No normalization of the thrust, because also as you said, I am a bit suspicious too that this is not a good idea when tiltting the propulsion unit as a whole.

If I am somewhere fully off, I hlighly appreciate your input!

Much less code lines in the COAX class now :smiley: ; if I figure out how, I’ll create a own class one day.

Here you are already sufficiently off, because, assuming you tuned your PID gains in hover:

  • you will have 2x more PIDs and oscillation if you push throttle to 2x of hover throttle;
  • you will have 2x less PIDs and a very sloppy vehicle on descent, if you set throttle to 0.5x of hover throttle.

I did not bother collecting opinions yet, but this kind of dependency may be one of the main reasons why Betaflight/INAV users don’t really build flap-controlled copters often - because both of these don’t have support for proper throttle-based flap output scaling.

For Ardupilot, this is kind of true as well, because in the current Single/Coax frames throttle is cropped from below at 0.5 - which means that only the high-power regime works adequately, and it’s very easy to crash if you descend quickly.

In my copters, I initially changed the (second) 0.5 to 0.1, so that a coax copter with a hover throttle of 0.2 does not suck, and now I’m rewriting the whole thing (as I am overloaded in the daytime job, I may not be quick enough to make it into 4.6, but who knows), single copters too. I have nicely working prototypes with hardcoded flap arrangements (like what’s in master now), but I also want to make this configurable too.

So I would not agree with this:

this is actually a very good idea, just needs to be executed properly.

No. This is not correct. You would set up the swashplates per the swashplate instructions in the Tradheli wiki. Use the H1 swashplate type. Then servo1 would be motor1 (front aileron), servo 2 would be motor 2(front elevator), servo 3 would be motor4 (rear aileron) and servo 4 would be motor 5 (rear elevator).

No. This is also incorrect. This is what the changed code would look like.

void AP_MotorsHeli_Dual::mix_tandem(float pitch_input......
.......

    // pitch control applied to both swashplates
    const float swash_pitch = pitch_input;

    // collective applied to both rotors
    const float swash1_coll = collective1_input;
    const float swash2_coll = collective2_input;
.......

That should work. Now pitch tilt is applied to both rotors and there is no diff collective pitch.

Dear @bnsgeyer ,
thanks a lot for the corrections and inputs. I’ll give it a try, with a bit of luck and spare time, maybe this weekend.First some dry tests.

Dear @MaxBuzz,
thanks to you too for your inputs. I believe I missunderstood your first reply about thrust normalization, because of the reference to the bi-copter (where no thrust normalization is implemented). I’ll take your thoughts into account and will try to implement them for my configuration (with two along the x-axis separated roll/pitch tiltable propulsion units).
Yes, I know the trouble with daytime jobs too ;-). Can’t wait to see how your code for coax will look like.

So, the story goes on. Most important, I tried to re-enforce some weak points (which were mainly the levers of the actuators) and to remove some play of the roll/pitch axis axles.

And yes, additionally I worked on the code. Going one road at the time, I continued to work on my modified COAX code (there is not much left from the original COAX code). Highly experimental, I swear.

Here are two videos. The first one shows a short test of the principal flight control. Since I try to stay safe, I mounted my toe-bees on roller boards. This is yaw control, mixed with the roll channel.

Yehaaa…and the second one shows the first take-off attempts. It works, I just increased P, I, D - a bit randomly, all the wrong way, but at least is 2bees not fully erratic when in the air :smiley: . There is light at the end of the tunnel. Sorry, it was already a bit dark for the video.

I added some “roll-over” rods, so my take-off weight is +1kg from expected. It works, but I also realize that the T-Motor + Propeller Thrust charts are, kindly said, a bit off. I need much more thrust as expected. However, sufficient power reserves available!

3 Likes

Congratulations, very impressive

Latest update. I got it stable and controllable, or at least to that point that someone like me ( with low piloting skills) can keep it in air, hover stable and re-land on the spot. But to get there from my last tests, I had to do some adjustments.

*) Checked mechanically that my CoM is at least near the center of the Holybro 6x IMU. I am within +/-4mm. Since the possible offset settings in ardupilot are 0.01m, I did not adjust.

  • Adjusted the tilting angles (roll (+yaw), pitch) to be equal (+/- 0.3°) in all directions; tricky due to the actuator backlash and to measure always on the exact same position.

  • Changed the control authority (mixing) of roll:yaw to 0.8:0.2

  • @MaxBuzz changed the thrust_out_actuator clipping from 0.5 to 0.35 (the second one)

// limit thrust out for calculation of actuator gains
    float thrust_out_actuator = constrain_float(MAX(_throttle_hover * 0.5f, thrust_out), 0.35f, 1.0f);
  • Set hover_thrust to 0.4
  • Tuned PID, starting with D, axis after axis.
    • and had a nice flip :-D, but no damage
  • Increased a bit P for each axis (and some slight random changes towards the end).
  • Put I-term on 50% of P
  • Freaked out because when I wanted to start testing on Sunday late afternoon, the ardupilot magnetometer suddenly decided to call out “Inconsistency” and magnetometer calibration in the field failed.
    • Funny as it is, when I rotated the aircraft 90°, everything was good.When I turned it back, I had again the warning (pre-flight check) raised.

So, it became late, foggy and dark. No better circumstances wanted, when tuning parameters and trying to fly is on the to/do list.

But who cares, that the reason why cars have headlights.

Here is a video, in almost good light condition.

Total tuning time to get it into stable and controllable: 15min, maybe. No static or dynamic notch filter yet, because vibrations seem to be really low. My next step:

  • Review captured log data, INS raw fast log
  • Check if altitude control works
  • Go for QuickTune lua script

A bit to go, but it seems like that ardupilot supports now also a thrust vector controlled dual fan configuration. :smile: My code is still a mess.

3 Likes

A week is almost over and I used the last hour to (try to) understand on how the notch filter setup is working. Luckily I was able to capture a few flights - in almost somewhat like hover - with INS_RAW_LOG_OPT enabled on all gyros. I had no time to look into the data yet. It took me a little to understand on how this very fine ardupilot ins-notch filter tool worked, but try and error, read in older posts etc etc. I guess I figured it out.

This is how my INS log looks like without notch filter:

Those are the settings I am going to apply on the next run:

And when applied, the notch filter should do this task:

I still need to figure out on how the attuniation is best identified.

Next in-flight-mag and altitude-hold calibration.

This is a nice autumn! Today we had a blue sky and a slight breeze. A perfect weather for testing.

Changes I did:

  1. Updated VESC to FW6.05 (arggg…all configurations gone afterwards…) and set erpm to 51500 (~3600rpm), this is way below the max I could ( ~4800), but sufficient to take off, hover and climb. I did this because when running without load at erpm >51500, the observer lost track and I did not want to risk a sudden rpm loss.
  2. The notch filter
  3. Prepared for Q-Tune
  4. Re-did mag calibration on ground. It seems just to go through if only the pixhawk, RF and GNSS is powered by USB, but not if I hook it up to the main batteries.

Summary: My first flight was just great with my manual guessed PIDs. I took off in stabilized mode, was able to maintain position with a very little drift and increased altitude. At about 3m I switched to altitute control, aircraft climbed a few meters, but controlable. Kept the altitude for 30 seconds and slowly returned in a half loop back to the landing spot. Finally a video in the sun.

Afterwards I did as planned the Q-Tune. Take off in alitutde mode, switch to loiter. Nice and smooth. Climbed up to 7m. Started Q-Tune, my son called out the stages. On the first test we interrupted right after yaw because we didn’t get that pitch and yaw was still missing. Anyhow. Good landing with roll tuned only.

After that, we did a complete Q-Tune. Check the Q-Tune Video. THAT WAS SCARY. But controlable.

Photo looks wild isn’t it? It’s all about to capture the right point when to pull throttle down…

Q-Tune of roll, again no problem, the values were different from the first time (quite a bit). Then, when pitch started, it never wanted to stop the oscillations. It was still controllable and somewhat stable in the air (which gives credit to the design :wink: ). After yaw, the oscillations around the lateral axis, were inceasing and it was a flight like riding a big swing. Not funny to fly. I was able to land safely.

I did a check flight, pitch tuning done with Q-Tune was fully off. I turned in my PIDs for pitch and it became better. I did a nice 5 minute flight in slow-mo hover testing controllability. It’s okay. What I experience is when flying forward, I get a yaw movment into it and “YAW inconsistency” is called out. I need to check on this one. Maybe someone has a clue for me?

I hope I colleced sufficient data for in-flight MagCal. I checked the webtool, but need to find out how to get the best result.

This means at the end of the day, that 2-bees design and the code works. There is a lot to improve and to test. I still have the heli configuration ahead for better comparision. But I spend until now only maybe 25minutes in air, and it flies pretty controlable and stable. This seems to be good and at least, it is something new. The idea works. Happy.

It is nice that quicktune offers tuning in loiter but just remember that if you start seeing growing oscillations, your immediate action should be to switch to stabilize. It may not have flown that great but it should have stopped the low frequency growing oscillation. The low frequency oscillation was probably due to the poor pitch tune interacting with the loiter controller.

Otherwise great to see that you got it flying

1 Like

You are right, but if you do it the first time it is difficult to judge if it is part of the tuning process or not. If I would not have completed it, someone else would have said “but you did not follow the Ardupilot Tuning process…” :smile:

Even so if it looks bad, it was somewhat flyable (or in other words…I’ve flown some worse configurations).

What would you guess - is the autotuning more succesful?

Otherwise great to see that you got it flying

Thanks a lot Bill!

I’d like to get rid of the yaw-inconsistency first before I continue any tuning.

My fault - it is “yaw unbalance” not “yaw inconsistency”.

Heyy, what is the update on this? I have somewhat similar design but I’m unsucessful into tuning? Could you elloborate more how to tune axis by axis?