aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp2
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp2
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp2
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
5 files changed, 5 insertions, 5 deletions
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index db6773b8a..c0b1bb404 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -83,7 +83,7 @@
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
#include <mavlink/mavlink_log.h>
-#include <px4_defines.h>
+#include <platforms/px4_defines.h>
#include "estimator_23states.h"
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 83fe25571..57c1e72f3 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -75,7 +75,7 @@
#include <ecl/attitude_fw/ecl_pitch_controller.h>
#include <ecl/attitude_fw/ecl_roll_controller.h>
#include <ecl/attitude_fw/ecl_yaw_controller.h>
-#include <px4_defines.h>
+#include <platforms/px4_defines.h>
/**
* Fixedwing attitude control app start / stop handling function
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 f441c4a91..e07bcc225 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
@@ -90,7 +90,7 @@
#include <external_lgpl/tecs/tecs.h>
#include "landingslope.h"
#include "mtecs/mTecs.h"
-#include <px4_defines.h>
+#include <platforms/px4_defines.h>
static int _control_task = -1; /**< task handle for sensor task */
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 6682a9c89..cea847603 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -73,7 +73,7 @@
#include <mathlib/mathlib.h>
#include <lib/geo/geo.h>
#include <mavlink/mavlink_log.h>
-#include <px4_defines.h>
+#include <platforms/px4_defines.h>
#define TILT_COS_MAX 0.7f
#define SIGMA 0.000001f
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 2a601b630..de6357d31 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -68,7 +68,7 @@
#include <geo/geo.h>
#include <systemlib/systemlib.h>
#include <drivers/drv_hrt.h>
-#include <px4_defines.h>
+#include <platforms/px4_defines.h>
#include "position_estimator_inav_params.h"
#include "inertial_filter.h"