9
$\begingroup$

I am currently implementing an autonomous quadcopter which I recently got flying and which was stable, but is unable to correct itself in the presence of significant external disturbances. I assume this is because of insufficiently tuned PID gains which have to be further tweaked inflight.

Current progress:

  • I ruled out a barometer since the scope of my research is only indoor flight and the barometer has a deviation of +-5 meters according to my colleague.
  • I am currently using an ultrasonic sensor (HC-SR04) for the altitude estimation which has a resolution of 0.3cm. However I found that the ultrasonic sensor's refresh rate of 20Hz is too slow to get a fast enough response for altitude correction.
  • I tried to use the accelerations on the Z axis from the accelerometer to get height data by integrating the acceleration to get velocity to be used for the rate PID in a cascaded pid controller scheme. The current implementation for the altitude PID controller is a single loop pid controller using a P controller with the position input from the ultrasonic sensor.
  • I had taken into account the negative acceleration measurements due to gravity but no matter how much I compute the offset, there is still the existence of a negative acceleration (eg. -0.0034). I computed the gravitational offset by setting the quadcopter to be still on a flat surface then collecting 20,000 samples from the accelerometer z axis to be averaged to get the "offset" which is stored as a constant variable. This variable is then subtracted from the accelerometer z-axis output to remove the offset and get it to "zero" if it is not accelerating. As said in the question, there is still the existence of a negative acceleration (eg. -0.0034). My quad then proceeds to just constantly climb in altitude. With only the ultrasonic sensor P controller, my quad oscillates by 50 cm.

How can this consistent negative acceleration reading be effectively dealt with?

Possible Solution: I am planning to do a cascading PID contoller for the altitude hold with the innerloop (PID controller) using the accelerometer and the outer loop (P controller) using the sonar sensor. My adviser said that even a single loop P controller is enough to make the quadcopter hold its altitude even with a slow sensor. Is this enough? I noticed that with only the P gain, the quadcopter would overshoot its altitude.

enter image description here

  • Leaky Integrator: I found this article explaining how he dealt with the negative accelerations using a leaky integrator however I have a bit of trouble understanding why would it work since I think the negative error would just turn to a positive error not solving the problem. I'm not quite sure. http://diydrones.com/forum/topics/multi-rotors-the-altitude-yoyo-effect-and-how-to-deal-with-it

  • Single loop PD controller with the ultrasonic sensor only: Is this feasible using feedback from a slow sensor?

Sources:

$\endgroup$
6
  • $\begingroup$ How are you computing the gravitational offset? What accelerometer is it? Can you link a datasheet? $\endgroup$
    – Chuck
    Mar 22, 2016 at 19:36
  • 1
    $\begingroup$ oscillation means you need damping!!! $\endgroup$
    – holmeski
    Mar 23, 2016 at 1:17
  • 1
    $\begingroup$ Remember that on stack exchange, it is better to edit your question to add information requested in comments, rather than adding more comments. Comments are for helping to improve questions and answers, and are distracting, so we try to keep them to a minimum. If all of the information needed to answer the question is contained within it, the comments can be tidied up (deleted). $\endgroup$
    – Mark Booth
    Mar 23, 2016 at 8:59
  • $\begingroup$ @Chuck I have edited the post with the relevant information :) $\endgroup$ Mar 24, 2016 at 1:19
  • $\begingroup$ I'm working on the same project, currently, I implementing Cascade PID Controller for stabilizing the attitude of the quadcopter using Arduino, I want to work on altitude right now. Do you implementing it without velocity estimate ?, and I have a question do I need to estimate earth to body frame transformation or can I implementing it without the transformation $\endgroup$ Apr 6, 2019 at 12:51

1 Answer 1

10
$\begingroup$

The barometer carried on the pixhawk has an altitude resolution of 10 cm. If that isn't enough, you could write a kalman filter that uses the accelerometer data in the prediction step and the ultrasonic sensor and/or the barometer in the correction step.

But I don't see this solving your problem. An accurate measurement of altitude at 20hz should be plenty if all you're trying to do is hold altitude.

What is the time constant / natural frequency and damping on your controller?

I guess I hadn't finished reading your question this morning ( it was before my coffee). The acceleration from the imu is the measurement of acceleration plus gravity. To get the inertial acceleration of the imu, subtract the gravity vector from the measurement. You'll never be able to control on integrated acceleration measurements. The measurements are corrupted by noise and you have no way to correct for this.

--- answer to control portion of the question

Lets assume that all you are trying to do is hold an altitude and are not concerned about holding a position for now ( though this approach will work for that as well). And assuming that you can command whatever thrust you want ( within reason), then this becomes an easy problem.

A first pass at the system dynamics looks like

$\ddot z = \frac{u}{m} - g$

where positive $z$ is up. Lets add a hover component to our throttle that deals with gravity. So

$ u = u_{fb} + u_{hover}$

Our new dynamics look like

$\ddot z = \frac{u_{fb} + u_{hover}}{m} - g = \frac{u_{fb}}{m}$

Cool! Now we design a control law so we can tack a desired altitude.

Our control system is going to be a virtual spring and damper between our quad and desired altitude ( this is a pd controller).

$ \ddot z = k_p(z_{des} - z) + k_d(\dot z_{des} - \dot z)$

The system should now behave like a second order system. $k_p$ and $k_d$ can be chosen to achieve the damping ratio and natural frequency you're looking for.

At this point I would like to reiterate that integrating accelerometer data is not an okay way to generate state estimates. If you really want to hack something together fast, feed the sonar measurements through a lowpass filter with an appropriate dropoff frequency. Your vehicle isn't going to be oscillating at 20hz so controlling off just the sonar data will be fine.

$\endgroup$
2
  • 1
    $\begingroup$ Thank you, I just finished implementing this 4 days ago and it worked with very minute oscillations +-2cm $\endgroup$ Mar 27, 2016 at 17:35
  • $\begingroup$ glad to hear it! you should be able to kill the oscillations by increasing kd assuming you have a good estimate of velocity :) $\endgroup$
    – holmeski
    Mar 27, 2016 at 19:59

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.