aboutsummaryrefslogtreecommitdiff
path: root/apps/multirotor_att_control
diff options
context:
space:
mode:
authorJulian Oes <joes@student.ethz.ch>2012-11-19 16:17:52 -0800
committerJulian Oes <joes@student.ethz.ch>2012-11-19 16:17:52 -0800
commit129e6d73debca5653911867e9db54990c02591bb (patch)
treed570eb77b836b977ed0a8db59da712435bb12099 /apps/multirotor_att_control
parent2652b16d37f2221dc9dabfa1a278651c2931e5ce (diff)
downloadpx4-firmware-129e6d73debca5653911867e9db54990c02591bb.tar.gz
px4-firmware-129e6d73debca5653911867e9db54990c02591bb.tar.bz2
px4-firmware-129e6d73debca5653911867e9db54990c02591bb.zip
Changed yaw position control to yaw speed control for multirotors, tested with ardrone
Diffstat (limited to 'apps/multirotor_att_control')
-rw-r--r--apps/multirotor_att_control/multirotor_att_control_main.c14
-rw-r--r--apps/multirotor_att_control/multirotor_attitude_control.c12
2 files changed, 21 insertions, 5 deletions
diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c
index 337a45215..91439d36d 100644
--- a/apps/multirotor_att_control/multirotor_att_control_main.c
+++ b/apps/multirotor_att_control/multirotor_att_control_main.c
@@ -155,6 +155,9 @@ mc_thread_main(int argc, char *argv[])
/* store if yaw position or yaw speed has been changed */
bool control_yaw_position = true;
+ /* store if we stopped a yaw movement */
+ bool first_time_after_yaw_speed_control = true;
+
/* prepare the handle for the failsafe throttle */
param_t failsafe_throttle_handle = param_find("MC_RCLOSS_THR");
float failsafe_throttle = 0.0f;
@@ -249,7 +252,7 @@ mc_thread_main(int argc, char *argv[])
if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
state.flag_control_manual_enabled != flag_control_manual_enabled ||
state.flag_system_armed != flag_system_armed) {
- att_sp.yaw_body = att.yaw;
+ att_sp.yaw_tait_bryan = att.yaw;
}
static bool rc_loss_first_time = true;
@@ -294,16 +297,19 @@ mc_thread_main(int argc, char *argv[])
if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
rates_sp.yaw = manual.yaw;
control_yaw_position = false;
+ first_time_after_yaw_speed_control = true;
} else {
- att_sp.yaw_body = 0.0f;
+ rates_sp.yaw = 0.0f;
+ if(first_time_after_yaw_speed_control) {
+ att_sp.yaw_tait_bryan = att.yaw;
+ first_time_after_yaw_speed_control = false;
+ }
control_yaw_position = true;
}
}
att_sp.thrust = manual.throttle;
att_sp.timestamp = hrt_absolute_time();
-
- //rates_sp.yaw = manual.yaw;
}
}
/* STEP 2: publish the result to the vehicle actuators */
diff --git a/apps/multirotor_att_control/multirotor_attitude_control.c b/apps/multirotor_att_control/multirotor_attitude_control.c
index bf908c6dd..87eeaced5 100644
--- a/apps/multirotor_att_control/multirotor_attitude_control.c
+++ b/apps/multirotor_att_control/multirotor_attitude_control.c
@@ -181,6 +181,8 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
static bool initialized = false;
+ static float yaw_error;
+
/* initialize the pid controllers when the function is called for the first time */
if (initialized == false) {
parameters_init(&h);
@@ -218,7 +220,15 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
if(control_yaw_position) {
/* control yaw rate */
- rates_sp->yaw = p.yaw_p * atan2f(cosf(att->yaw - att_sp->yaw_body), sinf(att->yaw - att_sp->yaw_body)) - (p.yaw_d * att->yawspeed);
+ //rates_sp->yaw = p.yaw_p * atan2f(cosf(att->yaw - att_sp->yaw_tait_bryan), sinf(att->yaw - att_sp->yaw_tait_bryan)) - (p.yaw_d * att->yawspeed);
+ yaw_error = att->yaw - att_sp->yaw_tait_bryan;
+ if ((double)yaw_error > M_PI) {
+ yaw_error -= M_PI;
+ } else if ((double)yaw_error < -M_PI) {
+ yaw_error += M_PI;
+ }
+
+ rates_sp->yaw = - p.yaw_p * (yaw_error) - (p.yaw_d * att->yawspeed);
}
rates_sp->thrust = att_sp->thrust;