aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mc_att_control
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-05-15 10:23:14 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-05-15 10:23:14 +0200
commit7ef3c2463721aa1382a686fb23f7451c7d47abb8 (patch)
tree697e1fbd2759e59f2a6f2f05a555893dde3e245e /src/modules/mc_att_control
parent8e43db7bc0c1d1f7525401c3df9e0227781ab454 (diff)
parent91b67d3f4aff0686638828ed2629793cc04b8be4 (diff)
downloadpx4-firmware-7ef3c2463721aa1382a686fb23f7451c7d47abb8.tar.gz
px4-firmware-7ef3c2463721aa1382a686fb23f7451c7d47abb8.tar.bz2
px4-firmware-7ef3c2463721aa1382a686fb23f7451c7d47abb8.zip
Merge branch 'master' into yaw_offset_limit
Diffstat (limited to 'src/modules/mc_att_control')
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp11
-rw-r--r--src/modules/mc_att_control/mc_att_control_params.c7
2 files changed, 10 insertions, 8 deletions
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index ee457c120..b23166a5e 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,9 +32,13 @@
****************************************************************************/
/**
- * @file mc_att_control_main.c
+ * @file mc_att_control_main.cpp
* Multicopter attitude controller.
*
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
* The controller has two loops: P loop for angular error and PD loop for angular rate error.
* Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch.
* For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw,
@@ -825,7 +826,7 @@ MulticopterAttitudeControl::start()
_control_task = task_spawn_cmd("mc_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&MulticopterAttitudeControl::task_main_trampoline,
nullptr);
diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c
index 19134c7b4..ad38a0a03 100644
--- a/src/modules/mc_att_control/mc_att_control_params.c
+++ b/src/modules/mc_att_control/mc_att_control_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,10 @@
/**
* @file mc_att_control_params.c
* Parameters for multicopter attitude controller.
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <systemlib/param/param.h>