From 85bc4f683a4a88cc19a35e1147d19ac5b1106019 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 19 Aug 2012 11:29:07 +0200 Subject: Cleaned up position control (WIP), moved PID structs (should become classes) to systemlib, added deamon app example --- apps/systemlib/pid/pid.h | 74 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100644 apps/systemlib/pid/pid.h (limited to 'apps/systemlib/pid/pid.h') diff --git a/apps/systemlib/pid/pid.h b/apps/systemlib/pid/pid.h new file mode 100644 index 000000000..d62843ed4 --- /dev/null +++ b/apps/systemlib/pid/pid.h @@ -0,0 +1,74 @@ +/**************************************************************************** + * + * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved. + * Author: @author Laurens Mackay + * @author Tobias Naegeli + * @author Martin Rutschmann + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file pid.h + * Definition of generic PID control interface + */ + +#ifndef PID_H_ +#define PID_H_ + +#include + +/* PID_MODE_DERIVATIV_CALC calculates discrete derivative from previous error + * val_dot in pid_calculate() will be ignored */ +#define PID_MODE_DERIVATIV_CALC 0 +/* Use PID_MODE_DERIVATIV_SET if you have the derivative already (Gyros, Kalman) */ +#define PID_MODE_DERIVATIV_SET 1 + +typedef struct { + float kp; + float ki; + float kd; + float intmax; + float sp; + float integral; + float error_previous; + uint8_t mode; + uint8_t plot_i; + uint8_t count; + uint8_t saturated; +} PID_t; + +void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax, uint8_t mode, uint8_t plot_i); +void pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax); +//void pid_set(PID_t *pid, float sp); +float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt); + + + +#endif /* PID_H_ */ -- cgit v1.2.3