7
$\begingroup$

I'm currently developing an EKF to estimate the position and orientation of a quadcopter. My state vector is comprised of 3D position, 3D velocity, 3 euler angles and the angular velocity vector.

Right now I'm looking into the measurement equation for the accelerometer.

If I understood correctly, an accelerometer measures "proper acceleration", instead of coordinate acceleration, that is, it measures the acceleration of the body w.r.t to a free-falling coordinate system.

If this is the case, and supposing the only forces acting on the body are the upward thrust given by the propellers, $\vec{T}$, and earth's gravitational force, $m\vec{g}$, then I understand that the only acceleration that would be measured by the accelerometer is the one caused by $\vec{T}$ (since the free-falling frame has no way of measuring the acceleration caused by $m\vec{g}$, because it is also being accelerated by it).

If this also the case, then I note that the vector $\vec{T}$, when expressed in the body coordinate frame (i.e. a coordinate frame fixed at the center of mass of the body, and always aligned with the body's orientation) does not depend on any of the states whatsoever. For example, if the propellers are assembled such that $\vec{T}$ is always perpendicular to the plane where the propellers are, then $\vec{T}$ in the body frame is specified as $(0,0,\alpha)^T$, where $\alpha$ is the magnitude of the thrust given.

Which leads me to conclude that (since the measured acceleration doesn't depend on the states) I can't use accelerometer measurements to obtain more information about any of my states (??). This conclusion seems paradoxical to me, and that's why I ask this here. Could someone please point the mistake in my reasoning, or elucidate why this is not a paradox?

$\endgroup$
1
  • $\begingroup$ Comments are not for extended discussion; this conversation has been moved to chat. $\endgroup$
    – Mark Booth
    Commented Dec 2, 2016 at 17:20

3 Answers 3

4
$\begingroup$

I encountered the same puzzle. I had a clue at the beginning that the gravity information is contained within accelerometer measurements due to aerodynamic drag. Then I found a paper The True Role of Accelerometer Feedback in Quadrotor Control, which had proved the idea.

My simulation also revealed the process of stabilization. As long as a quadcopter produces a thrust not counteracting gravity and therefore has a non-zero velocity, the acceleration measured by IMU is more or less different from the acceleration caused by the thrust because of aerodynamic drag, inclining to the inverse of gravity vector. That difference makes the controller aware of the instability and try to correct. After correction, the thrust gets closer to the inverse of gravity and is less able to counteract the aerodynamic drag, which result in a stronger effect of drag force on accelerometer measurements.

Note that the aerodynamic drag is so slight at low speed that a quadcopter knows little about gravity and thus depends mostly on gyro as well as human control or additional velocity/position information.

$\endgroup$
6
$\begingroup$

If the drone is not falling (holding height in the sky), and it's not accelerating in any particular direction, then the accelerometer should be reading:

$$ a = \left[ \begin{array}{} g_x \\ g_y \\ g_z \end{array}\right] $$

where $g_N$ is the component of gravity along each axis. If the drone is upright and stationary, and the accelerometer is oriented such that the z-axis points up, then the accelerometer would read:

$$ a = \left[ \begin{array}{} 0 \\ 0 \\ g \end{array}\right] $$

However, if the drone is tilted and not accelerating, then the gravity vector will appear in portions along the axes not orthogonal to gravity.

The Madgwick filter (which works pretty awesome by the way) utilizes this to determine the orientation of the accelerometer. The accelerometer is normalized and the component of acceleration on each axis gives the orientation.

Given the orientation, subtract out gravity, you're left with the acceleration along each axis. Double integrate those accelerations and you get position.

There are of course issues if you're accelerating in a particular direction that isn't in-line with gravity, because normalizing the acceleration will cause the "gravity vector" to skew towards the axis of motion. However, this is generally overcome by including gyroscope measurements with the orientation estimate.

It's important to remember too that these are all estimates. Unless you have a position measurement or an orientation measurement device, you'll never actually get measurements; the best you can do is generate pose estimates because there's no way to correct any accumulated errors.

Gyroscope readings are generally very accurate as a short-term orientation estimate and very poor as a long-term orientation estimate because of gyroscope drift. The accelerometer's gravitational orientation result, because it is affected by the motion of the sensor, generally results in poor short-term orientation measurements but very accurate long-term measurements.

So, between the accelerometer and gyroscope, you should be able to get very good orientation estimates (did I mention the Madgwick filter is really good? Don't kill yourself reinventing the wheel; the filter is open-source!). Again, once you have the orientation, subtract the gravity vector and you're left with only the accelerations caused by motion of the device.

Accelerometers suffer from drift too, though, so you're not going to get any high-precision position estimates from an accelerometer over any significant period of time.

$\endgroup$
2
  • $\begingroup$ Comments are not for extended discussion; this conversation has been moved to chat. $\endgroup$
    – Mark Booth
    Commented Dec 2, 2016 at 17:17
  • $\begingroup$ On stack exchange, comments are not intended for extended discussions, for that use Robotics Chat. Comments are for helping to improve questions and answers, and are distracting, so we try to keep them to a minimum. Comments should be considered ephemeral, any comment which no longer actively helps to improve a question or answer may be deleted at any time to tidy up a post. $\endgroup$
    – Mark Booth
    Commented Dec 2, 2016 at 17:18
3
$\begingroup$

Accelerometers measure kinematic acceleration with the addition of gravity. So for an accel to measure 0, the vehicle would need to be accelerating downward at $g$. To get inertial acceleration out of an accel measurement one simply needs to subtract the acceleration measured by the IMU when the IMU is static.

So, assuming the coordinate system of the drone is in line with the inertial coordinate system

\begin{equation} \ddot r = z_{acc} - g \end{equation}

where $\ddot r$ is acceleration of the drone in inertial space, $z_{accel}$ is the vector of accelerations measured by the IMU, and $g$ is the vector of accelerations experienced when the vehicle is not accelerating relative to the inertial frame.

Transformations need to get involved once the vehicle is not longer level but it's about the same.

$\endgroup$
2
  • $\begingroup$ Thank you for your time, but you neither addressed my argument nor explained the paradox. $\endgroup$
    – JLagana
    Commented Nov 30, 2016 at 21:56
  • $\begingroup$ "one simply needs to subtract the acceleration measured by the IMU when the IMU is static", unfortunately no, because orientation can change, for example the frame can be inverted and accelerating upwards at 2G. this would appear as though it were upright and stationary. $\endgroup$
    – Octopus
    Commented Nov 30, 2016 at 23:20

Your Answer

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

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