spline5.cpp 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  1. /*
  2. * spline5.cpp
  3. *
  4. * Created by William Geyer and Chris Olson modified for ardupilot
  5. * Original work by Ryan Muller
  6. * https://gist.github.com/ryanthejuggler/4132103
  7. * released under the Creative Commons CC0 License
  8. * http://creativecommons.org/publicdomain/zero/1.0/
  9. *
  10. * This file is free software: you can redistribute it and/or modify it
  11. * under the terms of the GNU General Public License as published by the
  12. * Free Software Foundation, either version 3 of the License, or
  13. * (at your option) any later version.
  14. *
  15. * This file is distributed in the hope that it will be useful, but
  16. * WITHOUT ANY WARRANTY; without even the implied warranty of
  17. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  18. * See the GNU General Public License for more details.
  19. *
  20. * You should have received a copy of the GNU General Public License along
  21. * with this program. If not, see <http://www.gnu.org/licenses/>.
  22. */
  23. #include <stdint.h>
  24. #include "spline5.h"
  25. void splinterp5(const float x[5], float out[4][4])
  26. {
  27. // number of spline points
  28. const uint8_t n = 5;
  29. // working variables
  30. float u[n] {};
  31. // second derivative
  32. // additional element in array necessary for back substitution loop.
  33. float z[n+1] {};
  34. // set the second derivative to 0 at the ends
  35. z[0] = u[0] = 0;
  36. z[n-1] = 0;
  37. // decomposition loop
  38. for (uint8_t i=1; i<n-1; i++) {
  39. float p = 0.5f * z[i-1] + 2.0f;
  40. // keep p from ever becoming zero
  41. if (p < 0.01f && p >= 0.0f) {
  42. p = 0.01f;
  43. } else if (p > -0.01f && p < 0.0f) {
  44. p = -0.01f;
  45. }
  46. const float p_inv = 1.0f / p;
  47. z[i] = -0.5f * p_inv;
  48. u[i] = x[i+1] + x[i-1] - 2.0f * x[i];
  49. u[i] = (3.0f * u[i] - 0.5f * u[i-1]) * p_inv;
  50. }
  51. // back-substitution loop
  52. for (uint8_t i=n-1; i>0; i--) {
  53. z[i] = z[i] * z[i+1] + u[i];
  54. }
  55. for (uint8_t i=0; i<n-1; i++) {
  56. out[i][0] = x[i+1];
  57. out[i][1] = x[i];
  58. out[i][2] = z[i+1];
  59. out[i][3] = z[i];
  60. }
  61. }