aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mc_pos_control/mc_pos_control_main.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-02 12:19:24 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-02 12:19:24 +0100
commite28e8c11bba0779386fc16ee47deac4db39b51c0 (patch)
treee86866463bd88c5d1c11bbd0db14152a26e0e05c /src/modules/mc_pos_control/mc_pos_control_main.cpp
parent141dda209222a7dd5afad6b844735fd9a44756a6 (diff)
downloadpx4-firmware-e28e8c11bba0779386fc16ee47deac4db39b51c0.tar.gz
px4-firmware-e28e8c11bba0779386fc16ee47deac4db39b51c0.tar.bz2
px4-firmware-e28e8c11bba0779386fc16ee47deac4db39b51c0.zip
make default apps compatible with autogenerated attitude and rc_channels message
Diffstat (limited to 'src/modules/mc_pos_control/mc_pos_control_main.cpp')
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp9
1 files changed, 5 insertions, 4 deletions
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 5918d6bc5..6682a9c89 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -73,6 +73,7 @@
#include <mathlib/mathlib.h>
#include <lib/geo/geo.h>
#include <mavlink/mavlink_log.h>
+#include <px4_defines.h>
#define TILT_COS_MAX 0.7f
#define SIGMA 0.000001f
@@ -1147,11 +1148,11 @@ MulticopterPositionControl::task_main()
/* thrust compensation for altitude only control mode */
float att_comp;
- if (_att.R[2][2] > TILT_COS_MAX) {
- att_comp = 1.0f / _att.R[2][2];
+ if (PX4_R(_att.R, 2, 2) > TILT_COS_MAX) {
+ att_comp = 1.0f / PX4_R(_att.R, 2, 2);
- } else if (_att.R[2][2] > 0.0f) {
- att_comp = ((1.0f / TILT_COS_MAX - 1.0f) / TILT_COS_MAX) * _att.R[2][2] + 1.0f;
+ } else if (PX4_R(_att.R, 2, 2) > 0.0f) {
+ att_comp = ((1.0f / TILT_COS_MAX - 1.0f) / TILT_COS_MAX) * PX4_R(_att.R, 2, 2) + 1.0f;
saturation_z = true;
} else {