spline_functions.h
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2010 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * spline_functions.h
20  *
21  * Created on: 20.12.2010
22  * Author: Martin Günther <mguenthe@uos.de>
23  */
24 
25 #ifndef SPLINE_FUNCTIONS_H_
26 #define SPLINE_FUNCTIONS_H_
27 
28 #include <boost/numeric/ublas/lu.hpp>
29 
30 namespace katana
31 {
32 // These functions are pulled from the spline_smoother package.
33 // They've been moved here to avoid depending on packages that aren't
34 // mature yet.
35 inline void generatePowers(int n, double x, double* powers);
36 
40 void sampleCubicSpline(const std::vector<double>& coefficients, double time, double& position, double& velocity,
41  double& acceleration);
42 
43 void getCubicSplineCoefficients(double start_pos, double start_vel, double end_pos, double end_vel, double time,
44  std::vector<double>& coefficients);
45 
65 void splineCoefficients(int steps, double *timearray, double *encoderarray, double *arr_p1, double *arr_p2,
66  double *arr_p3, double *arr_p4);
67 
73 void sampleSplineWithTimeBounds(const std::vector<double>& coefficients, double duration, double time,
74  double& position, double& velocity, double& acceleration);
75 
76 } // namespace katana
77 
78 #endif /* SPLINE_FUNCTIONS_H_ */
void sampleCubicSpline(const std::vector< double > &coefficients, double time, double &position, double &velocity, double &acceleration)
Samples a cubic spline segment at a particular time.
void getCubicSplineCoefficients(double start_pos, double start_vel, double end_pos, double end_vel, double time, std::vector< double > &coefficients)
void splineCoefficients(int steps, double *timearray, double *encoderarray, double *arr_p1, double *arr_p2, double *arr_p3, double *arr_p4)
void generatePowers(int n, double x, double *powers)
void sampleSplineWithTimeBounds(const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)


katana
Author(s): Martin Günther
autogenerated on Fri Jan 3 2020 04:01:25