diff --git a/libraries/AP_Common/AP_Curve.h b/libraries/AP_Curve/AP_Curve.h similarity index 89% rename from libraries/AP_Common/AP_Curve.h rename to libraries/AP_Curve/AP_Curve.h index ae5c8b8e9a..e295f14043 100644 --- a/libraries/AP_Common/AP_Curve.h +++ b/libraries/AP_Curve/AP_Curve.h @@ -3,12 +3,12 @@ /// @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 -#define AP_CURVE +#ifndef __AP_CURVE_H__ +#define __AP_CURVE_H__ -#include #include #include // ArduPilot Mega Vector/Matrix math Library +#include /// @class AP_Curve template @@ -28,7 +28,7 @@ public: virtual T get_y( T x ); // displays the contents of the curve (for debugging) - virtual void dump_curve(); + virtual void dump_curve(AP_HAL::BetterStream*); protected: uint8_t _num_points; // number of points in the cruve @@ -127,18 +127,18 @@ T AP_Curve::get_y( T x ) // displays the contents of the curve (for debugging) template -void AP_Curve::dump_curve() +void AP_Curve::dump_curve(AP_HAL::BetterStream* s) { - Serial.println_P(PSTR("Curve:")); + s->println_P(PSTR("Curve:")); for( uint8_t i = 0; i<_num_points; i++ ){ - Serial.print_P(PSTR("x:")); - Serial.print(_x[i]); - Serial.print_P(PSTR("\ty:")); - Serial.print(_y[i]); - Serial.print_P(PSTR("\tslope:")); - Serial.print(_slope[i],4); - Serial.println(); + s->print_P(PSTR("x:")); + s->print(_x[i]); + s->print_P(PSTR("\ty:")); + s->print(_y[i]); + s->print_P(PSTR("\tslope:")); + s->print(_slope[i],4); + s->println(); } } -#endif // AP_CURVE \ No newline at end of file +#endif // __AP_CURVE_H__