aboutsummaryrefslogtreecommitdiff
path: root/src/modules/systemlib/pid/pid.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/systemlib/pid/pid.h')
-rw-r--r--src/modules/systemlib/pid/pid.h31
1 files changed, 21 insertions, 10 deletions
diff --git a/src/modules/systemlib/pid/pid.h b/src/modules/systemlib/pid/pid.h
index eb9df96cc..5f2650f69 100644
--- a/src/modules/systemlib/pid/pid.h
+++ b/src/modules/systemlib/pid/pid.h
@@ -1,9 +1,11 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
+ * Author: Laurens Mackay <mackayl@student.ethz.ch>
+ * Tobias Naegeli <naegelit@student.ethz.ch>
+ * Martin Rutschmann <rutmarti@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ * Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,7 +38,14 @@
/**
* @file pid.h
- * Definition of generic PID control interface
+ *
+ * Definition of generic PID control interface.
+ *
+ * @author Laurens Mackay <mackayl@student.ethz.ch>
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Martin Rutschmann <rutmarti@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef PID_H_
@@ -44,6 +53,8 @@
#include <stdint.h>
+__BEGIN_DECLS
+
/* PID_MODE_DERIVATIV_CALC calculates discrete derivative from previous error
* val_dot in pid_calculate() will be ignored */
#define PID_MODE_DERIVATIV_CALC 0
@@ -62,22 +73,22 @@ typedef struct {
float intmax;
float sp;
float integral;
- float error_previous_filtered;
- float control_previous;
+ float error_previous;
float last_output;
float limit;
+ float dt_min;
uint8_t mode;
- float diff_filter_factor;
uint8_t count;
uint8_t saturated;
} PID_t;
-__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax, float limit, float diff_filter_factor, uint8_t mode);
-__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax, float limit, float diff_filter_factor);
+__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax, float limit, uint8_t mode, float dt_min);
+__EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float intmax, float limit);
//void pid_set(PID_t *pid, float sp);
__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt, float *ctrl_p, float *ctrl_i, float *ctrl_d);
__EXPORT void pid_reset_integral(PID_t *pid);
+__END_DECLS
#endif /* PID_H_ */