aboutsummaryrefslogtreecommitdiff
path: root/apps/multirotor_att_control/multirotor_attitude_control.c
diff options
context:
space:
mode:
authordaregger <daregger@student.ethz.ch>2012-10-16 18:02:28 +0200
committerdaregger <daregger@student.ethz.ch>2012-10-16 18:02:28 +0200
commit32e586d4b7561d1018e29aa59f572c3bac625024 (patch)
tree24f12b6012b581e58fab687015d637417b88c4d6 /apps/multirotor_att_control/multirotor_attitude_control.c
parentb50bc7798ac463de3e0c3147df46a3f7227df8c3 (diff)
downloadpx4-firmware-32e586d4b7561d1018e29aa59f572c3bac625024.tar.gz
px4-firmware-32e586d4b7561d1018e29aa59f572c3bac625024.tar.bz2
px4-firmware-32e586d4b7561d1018e29aa59f572c3bac625024.zip
Controller and estimator updates
Diffstat (limited to 'apps/multirotor_att_control/multirotor_attitude_control.c')
-rw-r--r--[-rwxr-xr-x]apps/multirotor_att_control/multirotor_attitude_control.c217
1 files changed, 76 insertions, 141 deletions
diff --git a/apps/multirotor_att_control/multirotor_attitude_control.c b/apps/multirotor_att_control/multirotor_attitude_control.c
index 458b86057..00b759d73 100755..100644
--- a/apps/multirotor_att_control/multirotor_attitude_control.c
+++ b/apps/multirotor_att_control/multirotor_attitude_control.c
@@ -54,17 +54,13 @@
#include <systemlib/param/param.h>
#include <arch/board/up_hrt.h>
-// PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
-// PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
-// PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
-// PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
-// PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
-
-PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.08f); /* same on Flamewheel */
-PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.02f);
-PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
-PARAM_DEFINE_FLOAT(MC_YAWRATE_AWU, 0.02f);
-PARAM_DEFINE_FLOAT(MC_YAWRATE_LIM, 0.1f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_P, 0.3f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_I, 0.15f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_D, 0.0f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_AWU, 1.0f);
+PARAM_DEFINE_FLOAT(MC_YAWPOS_LIM, 3.0f);
+
+
PARAM_DEFINE_FLOAT(MC_ATT_P, 0.2f); /* 0.15 F405 Flamewheel */
PARAM_DEFINE_FLOAT(MC_ATT_I, 0.0f);
@@ -76,17 +72,17 @@ PARAM_DEFINE_FLOAT(MC_ATT_XOFF, 0.0f);
PARAM_DEFINE_FLOAT(MC_ATT_YOFF, 0.0f);
struct mc_att_control_params {
- // float yaw_p;
- // float yaw_i;
- // float yaw_d;
- // float yaw_awu;
- // float yaw_lim;
-
- float yawrate_p;
- float yawrate_i;
- float yawrate_d;
- float yawrate_awu;
- float yawrate_lim;
+ float yaw_p;
+ float yaw_i;
+ float yaw_d;
+ float yaw_awu;
+ float yaw_lim;
+
+ // float yawrate_p;
+ // float yawrate_i;
+ // float yawrate_d;
+ // float yawrate_awu;
+ // float yawrate_lim;
float att_p;
float att_i;
@@ -99,17 +95,17 @@ struct mc_att_control_params {
};
struct mc_att_control_param_handles {
- // param_t yaw_p;
- // param_t yaw_i;
- // param_t yaw_d;
- // param_t yaw_awu;
- // param_t yaw_lim;
-
- param_t yawrate_p;
- param_t yawrate_i;
- param_t yawrate_d;
- param_t yawrate_awu;
- param_t yawrate_lim;
+ param_t yaw_p;
+ param_t yaw_i;
+ param_t yaw_d;
+ param_t yaw_awu;
+ param_t yaw_lim;
+
+ // param_t yawrate_p;
+ // param_t yawrate_i;
+ // param_t yawrate_d;
+ // param_t yawrate_awu;
+ // param_t yawrate_lim;
param_t att_p;
param_t att_i;
@@ -137,17 +133,17 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
static int parameters_init(struct mc_att_control_param_handles *h)
{
/* PID parameters */
- // h->yaw_p = param_find("MC_YAWPOS_P");
- // h->yaw_i = param_find("MC_YAWPOS_I");
- // h->yaw_d = param_find("MC_YAWPOS_D");
- // h->yaw_awu = param_find("MC_YAWPOS_AWU");
- // h->yaw_lim = param_find("MC_YAWPOS_LIM");
-
- h->yawrate_p = param_find("MC_YAWRATE_P");
- h->yawrate_i = param_find("MC_YAWRATE_I");
- h->yawrate_d = param_find("MC_YAWRATE_D");
- h->yawrate_awu = param_find("MC_YAWRATE_AWU");
- h->yawrate_lim = param_find("MC_YAWRATE_LIM");
+ h->yaw_p = param_find("MC_YAWPOS_P");
+ h->yaw_i = param_find("MC_YAWPOS_I");
+ h->yaw_d = param_find("MC_YAWPOS_D");
+ h->yaw_awu = param_find("MC_YAWPOS_AWU");
+ h->yaw_lim = param_find("MC_YAWPOS_LIM");
+
+ // h->yawrate_p = param_find("MC_YAWRATE_P");
+ // h->yawrate_i = param_find("MC_YAWRATE_I");
+ // h->yawrate_d = param_find("MC_YAWRATE_D");
+ // h->yawrate_awu = param_find("MC_YAWRATE_AWU");
+ // h->yawrate_lim = param_find("MC_YAWRATE_LIM");
h->att_p = param_find("MC_ATT_P");
h->att_i = param_find("MC_ATT_I");
@@ -163,17 +159,17 @@ static int parameters_init(struct mc_att_control_param_handles *h)
static int parameters_update(const struct mc_att_control_param_handles *h, struct mc_att_control_params *p)
{
- // param_get(h->yaw_p, &(p->yaw_p));
- // param_get(h->yaw_i, &(p->yaw_i));
- // param_get(h->yaw_d, &(p->yaw_d));
- // param_get(h->yaw_awu, &(p->yaw_awu));
- // param_get(h->yaw_lim, &(p->yaw_lim));
-
- param_get(h->yawrate_p, &(p->yawrate_p));
- param_get(h->yawrate_i, &(p->yawrate_i));
- param_get(h->yawrate_d, &(p->yawrate_d));
- param_get(h->yawrate_awu, &(p->yawrate_awu));
- param_get(h->yawrate_lim, &(p->yawrate_lim));
+ param_get(h->yaw_p, &(p->yaw_p));
+ param_get(h->yaw_i, &(p->yaw_i));
+ param_get(h->yaw_d, &(p->yaw_d));
+ param_get(h->yaw_awu, &(p->yaw_awu));
+ param_get(h->yaw_lim, &(p->yaw_lim));
+
+ // param_get(h->yawrate_p, &(p->yawrate_p));
+ // param_get(h->yawrate_i, &(p->yawrate_i));
+ // param_get(h->yawrate_d, &(p->yawrate_d));
+ // param_get(h->yawrate_awu, &(p->yawrate_awu));
+ // param_get(h->yawrate_lim, &(p->yawrate_lim));
param_get(h->att_p, &(p->att_p));
param_get(h->att_i, &(p->att_i));
@@ -188,16 +184,23 @@ static int parameters_update(const struct mc_att_control_param_handles *h, struc
}
void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators)
+ const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp, struct actuator_controls_s *actuators)
{
static uint64_t last_run = 0;
- const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ static uint64_t last_input = 0;
+ float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ float dT_input = (hrt_absolute_time() - last_input) / 1000000.0f;
last_run = hrt_absolute_time();
+ if (last_input != att_sp->timestamp) {
+ last_input = att_sp->timestamp;
+ }
+ static int sensor_delay;
+ sensor_delay = hrt_absolute_time() - att->timestamp;
static int motor_skip_counter = 0;
// static PID_t yaw_pos_controller;
- static PID_t yaw_speed_controller;
+// static PID_t yaw_speed_controller;
static PID_t pitch_controller;
static PID_t roll_controller;
@@ -213,112 +216,44 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
// pid_init(&yaw_pos_controller, p.yaw_p, p.yaw_i, p.yaw_d, p.yaw_awu,
// PID_MODE_DERIVATIV_SET, 154);
- pid_init(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu,
- PID_MODE_DERIVATIV_SET);
+ // pid_init(&yaw_speed_controller, p.yawrate_p, p.yawrate_i, p.yawrate_d, p.yawrate_awu,
+ // PID_MODE_DERIVATIV_SET);
pid_init(&pitch_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
- PID_MODE_DERIVATIV_SET);
+ PID_MODE_DERIVATIV_SET);
pid_init(&roll_controller, p.att_p, p.att_i, p.att_d, p.att_awu,
- PID_MODE_DERIVATIV_SET);
+ PID_MODE_DERIVATIV_SET);
initialized = true;
}
/* load new parameters with lower rate */
- if (motor_skip_counter % 50 == 0) {
+ if (motor_skip_counter % 1000 == 0) {
/* 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(&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);
+ printf("delays: %d us sens->ctrl, rate: %d Hz, input: %d Hz\n", sensor_delay, (int)(1.0f/deltaT), (int)(1.0f/dT_input));
}
/* calculate current control outputs */
-
+
/* control pitch (forward) output */
- float pitch_control = pid_calculate(&pitch_controller, att_sp->pitch_body + p.att_xoff,
- att->pitch, att->pitchspeed, deltaT)*1/10.0f;
+ rates_sp->pitch = pid_calculate(&pitch_controller, att_sp->pitch_body + p.att_xoff,
+ att->pitch, att->pitchspeed, deltaT)*1/10.0f;
/* control roll (left/right) output */
- float roll_control = pid_calculate(&roll_controller, att_sp->roll_body + p.att_yoff,
- att->roll, att->rollspeed, deltaT)*1/10.0f;
+ rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body + p.att_yoff,
+ att->roll, att->rollspeed, deltaT)*1/10.0f;
/* control yaw rate */
- float yaw_rate_control = pid_calculate(&yaw_speed_controller, att_sp->yaw_body, att->yawspeed, 0.0f, deltaT)*1/10.0f;
-
- /*
- * compensate the vertical loss of thrust
- * when thrust plane has an angle.
- * start with a factor of 1.0 (no change)
- */
- float zcompensation = 1.0f;
-
- if (fabsf(att->roll) > 0.3f) {
- zcompensation *= 1.04675160154f;
-
- } else {
- zcompensation *= 1.0f / cosf(att->roll);
- }
-
- if (fabsf(att->pitch) > 0.3f) {
- zcompensation *= 1.04675160154f;
-
- } else {
- zcompensation *= 1.0f / cosf(att->pitch);
- }
+ //float yaw_rate_control = pid_calculate(&yaw_speed_controller, att_sp->yaw_body, att->yawspeed, 0.0f, deltaT)*1/10.0f;
+ rates_sp->yaw= deltaT*p.yaw_p*atan2f(sinf(att->yaw-att_sp->yaw_body),cos(att->yaw-att_sp->yaw_body));
- float motor_thrust = 0.0f;
- motor_thrust = att_sp->thrust;
- /* compensate thrust vector for roll / pitch contributions */
- motor_thrust *= zcompensation;
+ rates_sp->thrust = att_sp->thrust;
- /* limit yaw rate output */
- if (yaw_rate_control > p.yawrate_lim) {
- yaw_rate_control = p.yawrate_lim;
- yaw_speed_controller.saturated = 1;
- }
-
- if (yaw_rate_control < -p.yawrate_lim) {
- yaw_rate_control = -p.yawrate_lim;
- yaw_speed_controller.saturated = 1;
- }
-
- if (pitch_control > p.att_lim) {
- pitch_control = p.att_lim;
- pitch_controller.saturated = 1;
- }
-
- if (pitch_control < -p.att_lim) {
- pitch_control = -p.att_lim;
- pitch_controller.saturated = 1;
- }
-
-
- if (roll_control > p.att_lim) {
- roll_control = p.att_lim;
- roll_controller.saturated = 1;
- }
-
- if (roll_control < -p.att_lim) {
- roll_control = -p.att_lim;
- roll_controller.saturated = 1;
- }
-
- if (actuators) {
- actuators->control[0] = roll_control;
- actuators->control[1] = pitch_control;
- actuators->control[2] = yaw_rate_control;
- actuators->control[3] = motor_thrust;
- }
-
- // XXX change yaw rate to yaw pos controller
- if (rates_sp) {
- rates_sp->roll = roll_control;
- rates_sp->pitch = pitch_control;
- rates_sp->yaw = yaw_rate_control;
- rates_sp->thrust = motor_thrust;
- }
motor_skip_counter++;
}