aboutsummaryrefslogtreecommitdiff
path: root/apps/multirotor_att_control
diff options
context:
space:
mode:
authorDoug Weibel <deweibel@gmail.com>2012-10-07 14:46:26 -0600
committerDoug Weibel <deweibel@gmail.com>2012-10-07 14:46:26 -0600
commit2bb1d17c7e312e6f60bcd6e8f1ac6698fe623060 (patch)
treeb5084f8eeff47c6acd6eaf49aa66d38c9630fc4b /apps/multirotor_att_control
parent2fa0dec36954b0f3c99da0a443a9c51a7a0479c5 (diff)
downloadpx4-firmware-2bb1d17c7e312e6f60bcd6e8f1ac6698fe623060.tar.gz
px4-firmware-2bb1d17c7e312e6f60bcd6e8f1ac6698fe623060.tar.bz2
px4-firmware-2bb1d17c7e312e6f60bcd6e8f1ac6698fe623060.zip
Changes to the PID controller. Adds "limit" to the parameter set. Implements an output limit where the output magnitude is limited by the parameter value "limit". Also changes the integrator saturation such that the integrator is not updated (added to) if either updating it will cause the integrator values magnitude to exceed "intmax" or if the output magnitude would exceed "limit" with an updated integrator value.
Arbitrary large limit values were hard coded into multirotor_attitude_control.c. These should be changed to parametric values or something sensible. This commit will temporarily break fixedwing_control.c. A following commit will repair it along with significant changes to the inner loop control. This commit has been tested to compile with fixedwing_control.c temporarily removed. No other testing has been completed.
Diffstat (limited to 'apps/multirotor_att_control')
-rw-r--r--apps/multirotor_att_control/multirotor_attitude_control.c16
1 files changed, 8 insertions, 8 deletions
diff --git a/apps/multirotor_att_control/multirotor_attitude_control.c b/apps/multirotor_att_control/multirotor_attitude_control.c
index 2129915d1..cb34209b1 100644
--- a/apps/multirotor_att_control/multirotor_attitude_control.c
+++ b/apps/multirotor_att_control/multirotor_attitude_control.c
@@ -212,13 +212,13 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
parameters_update(&h, &p);
// pid_init(&yaw_pos_controller, p.yaw_p, p.yaw_i, p.yaw_d, p.yaw_awu,
- // PID_MODE_DERIVATIV_SET, 154);
+ // 90.0f, PID_MODE_DERIVATIV_SET, 154); // Arbitrarily large limit added
pid_init(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu,
- PID_MODE_DERIVATIV_SET);
+ 90.0f, PID_MODE_DERIVATIV_SET); // Arbitrarily large limit added
pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
- PID_MODE_DERIVATIV_SET);
+ 90.0f, PID_MODE_DERIVATIV_SET); // Arbitrarily large limit added
pid_init(&roll_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
- PID_MODE_DERIVATIV_SET);
+ 90.0f, PID_MODE_DERIVATIV_SET); // Arbitrarily large limit added
initialized = true;
}
@@ -228,10 +228,10 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
/* update parameters from storage */
parameters_update(&h, &p);
/* apply parameters */
- // pid_set_parameters(&yaw_pos_controller, p.yaw_p, p.yaw_i, p.yaw_d, p.yaw_awu);
- pid_set_parameters(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu);
- pid_set_parameters(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu);
- pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, p.att_awu);
+ // pid_set_parameters(&yaw_pos_controller, p.yaw_p, p.yaw_i, p.yaw_d, p.yaw_awu, 90.0f);
+ pid_set_parameters(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu, 90.0f);
+ pid_set_parameters(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu, 90.0f);
+ pid_set_parameters(&roll_controller, p.att_p, p.att_i, p.att_d, p.att_awu, 90.0f);
}
/* calculate current control outputs */