aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/platforms/px4_includes.h49
1 files changed, 24 insertions, 25 deletions
diff --git a/src/platforms/px4_includes.h b/src/platforms/px4_includes.h
index bdb2b8de9..90ec78996 100644
--- a/src/platforms/px4_includes.h
+++ b/src/platforms/px4_includes.h
@@ -48,21 +48,20 @@
#ifdef __cplusplus
#include "ros/ros.h"
-#include "px4/rc_channels.h"
-#include "px4_rc_channels.h" //XXX
-#include "px4/vehicle_attitude.h"
-#include <px4/vehicle_attitude_setpoint.h>
-#include <px4/manual_control_setpoint.h>
-#include <px4/actuator_controls.h>
-#include <px4/actuator_controls_0.h>
-#include <px4/actuator_controls_virtual_mc.h>
-#include <px4/vehicle_rates_setpoint.h>
-#include <px4/mc_virtual_rates_setpoint.h>
-#include <px4/vehicle_attitude.h>
-#include <px4/vehicle_control_mode.h>
-#include <px4/actuator_armed.h>
-#include <px4/parameter_update.h>
-#include <px4/vehicle_status.h>
+#include <px4_rc_channels.h>
+#include <px4_vehicle_attitude.h>
+#include <px4_vehicle_attitude_setpoint.h>
+#include <px4_manual_control_setpoint.h>
+#include <px4_actuator_controls.h>
+#include <px4_actuator_controls_0.h>
+#include <px4_actuator_controls_virtual_mc.h>
+#include <px4_vehicle_rates_setpoint.h>
+#include <px4_mc_virtual_rates_setpoint.h>
+#include <px4_vehicle_attitude.h>
+#include <px4_vehicle_control_mode.h>
+#include <px4_actuator_armed.h>
+#include <px4_parameter_update.h>
+#include <px4_vehicle_status.h>
#endif
#else
@@ -73,17 +72,17 @@
#include <uORB/uORB.h>
#include <uORB/topics/rc_channels.h>
#ifdef __cplusplus
-#include <platforms/nuttx/px4_messages/px4_rc_channels.h> //XXX
+#include <platforms/nuttx/px4_messages/px4_rc_channels.h>
+#include <platforms/nuttx/px4_messages/px4_vehicle_attitude_setpoint.h>
+#include <platforms/nuttx/px4_messages/px4_manual_control_setpoint.h>
+#include <platforms/nuttx/px4_messages/px4_actuator_controls.h>
+#include <platforms/nuttx/px4_messages/px4_vehicle_rates_setpoint.h>
+#include <platforms/nuttx/px4_messages/px4_vehicle_attitude.h>
+#include <platforms/nuttx/px4_messages/px4_vehicle_control_mode.h>
+#include <platforms/nuttx/px4_messages/px4_actuator_armed.h>
+#include <platforms/nuttx/px4_messages/px4_parameter_update.h>
+#include <platforms/nuttx/px4_messages/px4_vehicle_status.h>
#endif
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_control_mode.h>
-#include <uORB/topics/actuator_armed.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/vehicle_status.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>