From 1a0f613a0f18e93dcfff7acab0bfa221c599e5e0 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Mon, 21 Dec 2015 12:03:10 -0200 Subject: [PATCH] AP_Curve: remove unused library --- libraries/AP_Curve/AP_Curve.cpp | 104 -------------------------------- libraries/AP_Curve/AP_Curve.h | 55 ----------------- 2 files changed, 159 deletions(-) delete mode 100644 libraries/AP_Curve/AP_Curve.cpp delete mode 100644 libraries/AP_Curve/AP_Curve.h diff --git a/libraries/AP_Curve/AP_Curve.cpp b/libraries/AP_Curve/AP_Curve.cpp deleted file mode 100644 index 4b11f6e8bf..0000000000 --- a/libraries/AP_Curve/AP_Curve.cpp +++ /dev/null @@ -1,104 +0,0 @@ - -#include "AP_Curve.h" - - -// Constructor -template -AP_Curve::AP_Curve() : - _num_points(0) -{ - // clear the curve - clear(); -}; - -// clear the curve -template -void AP_Curve::clear() { - // clear the curve - for( uint8_t i=0; i -bool AP_Curve::add_point( T x, T y ) -{ - if( _num_points < SIZE ) { - _x[_num_points] = x; - _y[_num_points] = y; - - // increment the number of points - _num_points++; - - // if we have at least two points calculate the slope - if( _num_points > 1 ) { - _slope[_num_points-2] = (float)(_y[_num_points-1] - _y[_num_points-2]) / (float)(_x[_num_points-1] - _x[_num_points-2]); - _slope[_num_points-1] = _slope[_num_points-2]; // the final slope is for interpolation beyond the end of the curve - } - return true; - }else{ - // we do not have room for the new point - return false; - } -} - -// get_y - returns the y value on the curve for a given x value -template -T AP_Curve::get_y( T x ) -{ - uint8_t i; - T result; - - // deal with case where ther is no curve - if( _num_points == 0 ) { - return x; - } - - // when x value is lower than the first point's x value, return minimum y value - if( x <= _x[0] ) { - return _y[0]; - } - - // when x value is higher than the last point's x value, return maximum y value - if( x >= _x[_num_points-1] ) { - return _y[_num_points-1]; - } - - // deal with the normal case - for( i=0; i<_num_points-1; i++ ) { - if( x >= _x[i] && x <= _x[i+1] ) { - result = _y[i] + (x - _x[i]) * _slope[i]; - return result; - } - } - - // we should never get here - return x; -} -// displays the contents of the curve (for debugging) -template -void AP_Curve::dump_curve(AP_HAL::BetterStream* s) -{ - s->println("Curve:"); - for( uint8_t i = 0; i<_num_points; i++ ){ - s->print("x:"); - s->print(_x[i]); - s->print("\ty:"); - s->print(_y[i]); - s->print("\tslope:"); - s->print(_slope[i],4); - s->println(); - } -} - -template class AP_Curve; -template class AP_Curve; -template class AP_Curve; -template class AP_Curve; -template class AP_Curve; -template class AP_Curve; - diff --git a/libraries/AP_Curve/AP_Curve.h b/libraries/AP_Curve/AP_Curve.h deleted file mode 100644 index 5c9b1f6869..0000000000 --- a/libraries/AP_Curve/AP_Curve.h +++ /dev/null @@ -1,55 +0,0 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -/// @file AP_Curve.h -/// @brief used to transforms a pwm value to account for the non-linear pwm->thrust values of normal ESC+motors - -#ifndef __AP_CURVE_H__ -#define __AP_CURVE_H__ - -#include -#include // ArduPilot Mega Vector/Matrix math Library -#include - -/// @class AP_Curve -template -class AP_Curve { -public: - - // Constructor - AP_Curve(); - - // clear - removes all points from the curve - void clear(); - - // add_point - adds a point to the curve. returns TRUE if successfully added - bool add_point( T x, T y ); - - // get_y - returns the point on the curve at the given pwm_value (i.e. the new modified pwm_value) - T get_y( T x ); - - // displays the contents of the curve (for debugging) - void dump_curve(AP_HAL::BetterStream*); - -protected: - uint8_t _num_points; // number of points in the cruve - T _x[SIZE]; // x values of each point on the curve - T _y[SIZE]; // y values of each point on the curve - float _slope[SIZE]; // slope between any two points. i.e. slope[0] is the slope between points 0 and 1 - bool _constrained; // if true, first and last points added will constrain the y values returned by get_y function -}; - - -/* Typedefs for template instansations of AP_Curve. - * Only use the AP_Curve instances listed here! - * If you need a different one, you must first instantiate the template at the - * end of AP_Curve.cpp, then add a typedef here. - */ - -typedef AP_Curve AP_CurveInt16_Size3; -typedef AP_Curve AP_CurveInt16_Size4; -typedef AP_Curve AP_CurveInt16_Size5; -typedef AP_Curve AP_CurveUInt16_Size3; -typedef AP_Curve AP_CurveUInt16_Size4; -typedef AP_Curve AP_CurveUInt16_Size5; - -#endif // __AP_CURVE_H__