How to turn off the cyclic blade pitch and collective pitch when the helicopter is on the ground

Your reply is the best gift for my new year, haha. I am glad to receive your reply. I appreciate it.

As you said, judging the landing requires high reliability. Manually switching modes to turn off pids runs the risk of forgetting or misoperating. Yesterday, I added 70g counterweight to the damping plate of the flight controller. Vibes and ACC.x went down a bit more. So far the altitude holding seems acceptable, but the positioning accuracy is mediocre and the uav will wobble in the loiter mode. We also try to set PSC_ACCZ_FLTE from 20 to 10, and its effect is not obvious. Adjusting the Angle_P from your suggestion is helpful.

Thank you and Leonard for your contributions. Your work is great and worthy of expectation. Now the vibration of helicopter flight has been reduced a lot, but the problem of ground resonance is still difficult to optimize. Yes, ground resonance is mainly a mechanical problem, but it’s hard to avoid for oil powered helicopters. According to the current situation, excessive cyclic pitch and total pitch operation during resonance will aggravate the resonance situation and even bring the risk of uav rolloping. I have no good way to optimize it at the moment, and I look forward to your further suggestions and ideas.

Yesterday, we lowered the collective minimum pitch to -1 degree, which I think brings up the grip of the DRONE on the ground. It seems to have no good or bad effect on vibration. Now the hovering Aout is about 0.75. Is there any potential safety hazard? If the lowest collective total distance is -2 degrees, I estimate the hovering Aout to be 0.8. What is your main consideration about -2 degrees? Please advise.

Your suggestion to increase the rotational speed should be effective. But now we have a defined driveline, so for the internal combustion engine, the rotation speed is difficult to adjust. The speed at the rotor tip is now 0.5 Mach. Also, if I turn up the rotor speed, I worry that the engine will not be able to carry the current maximum collective total pitch.

@bnsgeyer @Leonardthall

The altitude controller responding to inputs when it is armed but landed with interlock disabled. We found that in 4.0.7, when the UAV was on the ground, the altitude control integral was a horizontal line, but in 4.1.2, the altitude control integral danced violently and was of great value. In fact, the Z vibration of 4.0.7 in the log is larger than that of 4.1.2. In addition, in 4.1.2, the desired height and climb speed are consistent with the actual measured height and climb speed. This is probably why 4.1.2 is in worse condition than 4.0.7.

Could this problem be optimized? Now I’m very disturbed. For this reason I dare not upgrade to 4.1. But in 4.0.7 when using GPS for yaw, there will be a bunch of alarms about compass.

@bnsgeyer @Leonardthall
The day before yesterday(2022.1.4), I flew auto mode in 4.0.7. After the helicopter lands, the initial collective pitch is the lowest (Aout 0). As the helicopter pulled out of cruise control, the collective pitch suddenly reached its maximum (Aout was 1) and the aircraft lifted off the ground again, threatening to roll over again.

This is the log:

A small piece of code I modified in AP_MotorsHeli_Dual. CPP in 4.0.7, I wonder if it is feasible? My logic is that when the helicopter is armed and has no cruise control (! Interlock), so that all rotor servos in the lowest collective picth position. So that when the helicopter idling or landing after the exit cruise, the helicopter is the lowest collective pitch, and not flips or rollover.

We’d like to hear your professional opinion. Thanks for your time.
Best wishes!

@Flying2015 This was not the fault of the autopilot. The pilot initiated the motor interlock (rotor spool down) and caused this problem. The autopilot still thought it was flying and is why it raised the collective. the pilot cannot interfere with the autonomous mode by switching off the motor interlock. the pilot has to let the autopilot initiate the shutdown process otherwise the pilot should switch to a manual throttle mode like Stabilize or Acro before switching off the motor interlock.

@Flying2015 Thank you for pointing this out. I agree that the two versions are handling the altitude controller on the ground differently. Adding more to your story, here is a plot of 4.0.7 on the ground. These plots are similar to yours but I added the PIDA.P signal also along with the CTUN.ThO which is the output collective. You can see that the I term is constant where the P term is pretty large but the collective out is low and not causing any problems.

Here is the same plot for 4.1.2. with this version, the P term is low and the I term is very high. The resulting collective output is high as well.

Overall I think there is merit to your concern. I was looking at the function that relaxes the altitude controller and it has changed quite a bit. I will discuss this with @Leonardthall. I am concerned with the I term building like it does when the altitude controller is supposedly in a relaxed state. These are extreme conditions that you provide but I think this still is valid for lower vibrations states. The integrator should not be allowed to build in this manner in a relaxed state.

Thanks again for your persistence in this matter.

That’s true, your observation is very careful, it is really our manual operation. Thank you very much for your reply, it is so crucial!

Yes, our situation is quite extreme. The vibration of a real drone is very high, which also bothers us. We want to make progress on this, but it is too difficult at the moment. Thank you for your patient reply. I am very happy to get your attention and look forward to it.

Update

//set servo positions when !interlock and armed  
if(!_flags.interlock && _flags.armed){
     _servo_out[CH_1] = ((float)(_collective_min - 1500))/500.0f;
     _servo_out[CH_2] = ((float)(_collective_min - 1500))/500.0f;
     _servo_out[CH_3] = ((float)(_collective_min - 1500))/500.0f;
     _servo_out[CH_4] = ((float)(_collective2_min - 1500))/500.0f;
     _servo_out[CH_5] = ((float)(_collective2_min - 1500))/500.0f;
     _servo_out[CH_6] = ((float)(_collective2_min - 1500))/500.0f;
}

@Flying2015 You DO NOT want to go about it like this. You are messing with the lower level parts of the code. I think I understand the issue as to why it is happening. Just need to get Leonard onboard and come up with a suitable solution. This won’t be an overnight fix but we will get to it.

Okay, I’m in a hurry. Thank you for your advice and attention. Your work is significant, and we are working together to make this automatic control system better.

I can show you what the issue is. You can help fix it the right way

That’s great. I’d appreciate your advice.

I submitted a PR for this here. I will have @Leonardthall look at it. This is my thought as the best way to fix this issue.

Wow, great, I’ll visit and learn it right away. I’m very grateful and touched that you stayed up late for this. Thanks againg.

Ok, so I have been able to look at this collective output problem. This is in two parts.

The first part is that your high noise levels mean your measured acceleration significantly exceeds your maximum acceleration limit so when the controller initialises the acceleration it does not initialise it to your measured acceleration (±3 g or 30m/s/s) but instead it is limited to 2.5m/s/s. Therefore the following loop sees a large acceleration error and this results in a significant collective command just due to the P term in the acceleration PID loop. This part is not a bug.

The second part is what Bill noticed. The I term relaxed by taking the previous output and reducing it. However this assumes that the previous output had no output due to the P term and is therefore constant apart from the slowly reducing I term. This is a bug in that we should not assume this output has no P term and instead it should be based on the previous I term.

I have a fix for the I term problem here with a cleaned up handling of the reset_I_smoothly using a new relax_integrator function. Here:

Now this does not fix your problem as it is fundamentally caused by stupidly large vibrations getting to the position controller. These changes will help reduce your problem a little but the real fix is to:

  1. Reduce the vibrations getting to your autopilot
  2. Reduce the magnitude of the vibrations getting to the controller

I can’t help you with 1 but I can help you with 2. Your current setting of the acceleration filter is very high:
INS_ACCEL_FILTER 20 Hz

It looks like your acceleration noise is approximately 5 Hz. You could reduce your INS_ACCEL_FILTER setting to 0.5 to 1 Hz to greatly reduce this noise at the controller level. However we need to ensure that the lower controller response does not make Alt_Hold unstable. If so we may need to reduce the PSC Z gains.

I am honored to receive your reply. I will study your suggestions carefully. Yes, I agree with you and Bill. The vibration of our helicopter is really high, especially when the ground resonates. This may have something to do with the fact that it is powered by an internal combustion engine. We’re trying to figure out how to optimize.

Thank you very much for your advice and attention. Your suggestion on filter frequency is very meaningful, I will try it out as soon as possible. After Bill put forward the suggestion about PSC_ACCZ_FLTE, I have also reduced the INS_ACCEL_FILTER to 10Hz. I will continue to reduce the frequency of INS_ACCEL_FILTER according to your suggestion. If the filtering frequency is too low, will there be a delay?

Best Wishes. Happy New Year!