aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/lib/geo_lookup/geo_mag_declination.h4
-rw-r--r--src/lib/mathlib/math/Limits.hpp2
-rw-r--r--src/lib/mathlib/math/Vector.hpp2
-rw-r--r--src/modules/uORB/topics/actuator_armed.h8
-rw-r--r--src/modules/uORB/topics/actuator_controls.h6
-rw-r--r--src/modules/uORB/topics/airspeed.h6
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h8
-rw-r--r--src/modules/uORB/topics/parameter_update.h8
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h6
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h6
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h6
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h7
-rw-r--r--src/modules/uORB/topics/vehicle_rates_setpoint.h6
-rw-r--r--src/modules/uORB/topics/vehicle_status.h6
-rw-r--r--src/platforms/px4_defines.h4
15 files changed, 22 insertions, 63 deletions
diff --git a/src/lib/geo_lookup/geo_mag_declination.h b/src/lib/geo_lookup/geo_mag_declination.h
index d79b78412..0ac062d6d 100644
--- a/src/lib/geo_lookup/geo_mag_declination.h
+++ b/src/lib/geo_lookup/geo_mag_declination.h
@@ -40,12 +40,8 @@
#pragma once
-#ifdef CONFIG_ARCH_ARM
__BEGIN_DECLS
__EXPORT float get_mag_declination(float lat, float lon);
__END_DECLS
-#else
-float get_mag_declination(float lat, float lon);
-#endif
diff --git a/src/lib/mathlib/math/Limits.hpp b/src/lib/mathlib/math/Limits.hpp
index 79e127fdd..fca4197b8 100644
--- a/src/lib/mathlib/math/Limits.hpp
+++ b/src/lib/mathlib/math/Limits.hpp
@@ -39,7 +39,7 @@
#pragma once
-#include <platforms/px4_config.h>
+#include <platforms/px4_defines.h>
#include <stdint.h>
namespace math {
diff --git a/src/lib/mathlib/math/Vector.hpp b/src/lib/mathlib/math/Vector.hpp
index b0b03980d..9accd0907 100644
--- a/src/lib/mathlib/math/Vector.hpp
+++ b/src/lib/mathlib/math/Vector.hpp
@@ -50,7 +50,7 @@
#include "../CMSIS/Include/arm_math.h"
#else
#include <math/eigen_math.h>
-#include <Eigen/Eigen>
+//#include <Eigen/Eigen>
#endif
namespace math
diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h
index 9ec9d10ab..1e10e0ad1 100644
--- a/src/modules/uORB/topics/actuator_armed.h
+++ b/src/modules/uORB/topics/actuator_armed.h
@@ -42,9 +42,8 @@
#define TOPIC_ACTUATOR_ARMED_H
#include <stdint.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
+
/**
* @addtogroup topics
* @{
@@ -65,7 +64,6 @@ struct actuator_armed_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(actuator_armed);
-#endif
+
#endif
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
index 6c641dbce..43f7a59ee 100644
--- a/src/modules/uORB/topics/actuator_controls.h
+++ b/src/modules/uORB/topics/actuator_controls.h
@@ -47,9 +47,7 @@
#define TOPIC_ACTUATOR_CONTROLS_H
#include <stdint.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
#define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
@@ -72,11 +70,9 @@ struct actuator_controls_s {
*/
/* actuator control sets; this list can be expanded as more controllers emerge */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(actuator_controls_0);
ORB_DECLARE(actuator_controls_1);
ORB_DECLARE(actuator_controls_2);
ORB_DECLARE(actuator_controls_3);
-#endif
#endif
diff --git a/src/modules/uORB/topics/airspeed.h b/src/modules/uORB/topics/airspeed.h
index 4c115a811..676c37c77 100644
--- a/src/modules/uORB/topics/airspeed.h
+++ b/src/modules/uORB/topics/airspeed.h
@@ -40,9 +40,7 @@
#ifndef TOPIC_AIRSPEED_H_
#define TOPIC_AIRSPEED_H_
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
#include <stdint.h>
/**
@@ -65,8 +63,6 @@ struct airspeed_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(airspeed);
-#endif
#endif
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index af5df6979..15b55648d 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -41,9 +41,8 @@
#define TOPIC_MANUAL_CONTROL_SETPOINT_H_
#include <stdint.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
+
/**
* Switch position
*/
@@ -107,7 +106,6 @@ struct manual_control_setpoint_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(manual_control_setpoint);
-#endif
+
#endif
diff --git a/src/modules/uORB/topics/parameter_update.h b/src/modules/uORB/topics/parameter_update.h
index 7afb78d49..fe9c9070f 100644
--- a/src/modules/uORB/topics/parameter_update.h
+++ b/src/modules/uORB/topics/parameter_update.h
@@ -40,9 +40,7 @@
#define TOPIC_PARAMETER_UPDATE_H
#include <stdint.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
@@ -58,8 +56,6 @@ struct parameter_update_s {
* @}
*/
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(parameter_update);
-#endif
-#endif
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
index 7780988c8..1df1433ac 100755
--- a/src/modules/uORB/topics/vehicle_attitude.h
+++ b/src/modules/uORB/topics/vehicle_attitude.h
@@ -44,9 +44,7 @@
#include <stdint.h>
#include <stdbool.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
@@ -89,8 +87,6 @@ struct vehicle_attitude_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(vehicle_attitude);
-#endif
#endif
diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
index 8b5a76143..a503aa0c6 100644
--- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
@@ -42,9 +42,7 @@
#include <stdint.h>
#include <stdbool.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
@@ -84,8 +82,6 @@ struct vehicle_attitude_setpoint_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(vehicle_attitude_setpoint);
-#endif
#endif /* TOPIC_ARDRONE_CONTROL_H_ */
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 78de55b7d..2dd8550bc 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -48,9 +48,7 @@
#include <stdint.h>
#include <stdbool.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
#include "vehicle_status.h"
/**
@@ -92,8 +90,6 @@ struct vehicle_control_mode_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(vehicle_control_mode);
-#endif
#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index e8f010924..f7a432495 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -45,9 +45,7 @@
#include <stdint.h>
#include <stdbool.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
@@ -83,7 +81,6 @@ struct vehicle_global_position_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(vehicle_global_position);
-#endif
+
#endif
diff --git a/src/modules/uORB/topics/vehicle_rates_setpoint.h b/src/modules/uORB/topics/vehicle_rates_setpoint.h
index cbfab89d6..e5cecf02b 100644
--- a/src/modules/uORB/topics/vehicle_rates_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_rates_setpoint.h
@@ -41,9 +41,7 @@
#define TOPIC_VEHICLE_RATES_SETPOINT_H_
#include <stdint.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
@@ -64,8 +62,6 @@ struct vehicle_rates_setpoint_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(vehicle_rates_setpoint);
-#endif
#endif
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 6bd156ccd..8e85b4835 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -53,9 +53,7 @@
#include <stdint.h>
#include <stdbool.h>
-#ifdef CONFIG_ARCH_ARM
-#include "../uORB.h"
-#endif
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics @{
@@ -252,8 +250,6 @@ struct vehicle_status_s {
*/
/* register this as object request broker structure */
-#ifdef CONFIG_ARCH_ARM
ORB_DECLARE(vehicle_status);
-#endif
#endif
diff --git a/src/platforms/px4_defines.h b/src/platforms/px4_defines.h
index 8d8fd5f3c..327d0bea1 100644
--- a/src/platforms/px4_defines.h
+++ b/src/platforms/px4_defines.h
@@ -36,7 +36,6 @@
*
* Generally used magic defines
*/
-
#pragma once
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
@@ -45,6 +44,7 @@
*/
#define __EXPORT
//#define PX4_MAIN_FUNCTION(_prefix)
+#define ORB_DECLARE(x)
#else
#include <nuttx/config.h>
//#define PX4_MAIN_FUNCTION(_prefix) __EXPORT int _prefix##main(int argc, char **argv)() { return main(argc, argv); }
@@ -53,4 +53,6 @@
#include "drv_orb_dev.h"
#define ACCEL_DEVICE_PATH "/dev/accel"
+#include <modules/uORB/uORB.h>
+
#endif