aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_pos_control_l1
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/fw_pos_control_l1')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp4
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs.cpp2
2 files changed, 4 insertions, 2 deletions
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index dbf15d98a..74249c9c5 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -77,6 +77,7 @@
#include <uORB/topics/navigation_capabilities.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_status.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/pid/pid.h>
@@ -90,6 +91,7 @@
#include <external_lgpl/tecs/tecs.h>
#include "landingslope.h"
#include "mtecs/mTecs.h"
+#include <platforms/px4_defines.h>
static int _control_task = -1; /**< task handle for sensor task */
@@ -735,7 +737,7 @@ FixedwingPositionControl::vehicle_attitude_poll()
/* set rotation matrix */
for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
- _R_nb(i, j) = _att.R[i][j];
+ _R_nb(i, j) = PX4_R(_att.R, i, j);
}
}
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
index bffeefc1f..ecdab2936 100644
--- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
@@ -52,7 +52,7 @@ mTecs::mTecs() :
_mTecsEnabled(this, "ENABLED"),
_airspeedMin(this, "FW_AIRSPD_MIN", false),
/* Publications */
- _status(&getPublications(), ORB_ID(tecs_status)),
+ _status(ORB_ID(tecs_status), &getPublications()),
/* control blocks */
_controlTotalEnergy(this, "THR"),
_controlEnergyDistribution(this, "PIT", true),