Browse Source

px4_includes cleanup incomplete list

sbg
Daniel Agar 8 years ago committed by Lorenz Meier
parent
commit
b70b8288b9
  1. 2
      src/drivers/aerofc_adc/aerofc_adc.cpp
  2. 1
      src/drivers/bst/bst.cpp
  3. 5
      src/drivers/device/cdev.cpp
  4. 1
      src/drivers/linux_pwm_out/linux_pwm_out.cpp
  5. 2
      src/drivers/rgbled/rgbled.cpp
  6. 3
      src/drivers/sf0x/sf0x_tests/SF0XTest.cpp
  7. 1
      src/examples/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
  8. 1
      src/modules/ekf2/ekf2_main.cpp
  9. 2
      src/modules/ekf2_replay/ekf2_replay_main.cpp
  10. 8
      src/modules/land_detector/LandDetector.cpp
  11. 1
      src/modules/mavlink/mavlink_messages.cpp
  12. 2
      src/modules/mc_pos_control/mc_pos_control_main.cpp
  13. 2
      src/modules/micrortps_bridge/micrortps_client/microRTPS_client_dummy.cpp
  14. 1
      src/modules/navigator/navigator.h
  15. 1
      src/modules/position_estimator_inav/position_estimator_inav_main.cpp
  16. 1
      src/modules/sensors/rc_update.h
  17. 1
      src/modules/simulator/simulator_mavlink.cpp
  18. 84
      src/platforms/px4_includes.h
  19. 1
      src/systemcmds/motor_ramp/motor_ramp.cpp

2
src/drivers/aerofc_adc/aerofc_adc.cpp

@ -34,6 +34,8 @@ @@ -34,6 +34,8 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <cstring>
#include <arch/board/board.h>
#include <nuttx/arch.h>

1
src/drivers/bst/bst.cpp

@ -49,6 +49,7 @@ @@ -49,6 +49,7 @@
#include <math.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/vehicle_attitude.h>
#include <mathlib/math/Quaternion.hpp>
using namespace matrix;

5
src/drivers/device/cdev.cpp

@ -43,8 +43,9 @@ @@ -43,8 +43,9 @@
#include <sys/ioctl.h>
#include <arch/irq.h>
#include <stdlib.h>
#include <stdio.h>
#include <cstdlib>
#include <cstdio>
#include <cstring>
#ifdef CONFIG_DISABLE_POLL
# error This driver is not compatible with CONFIG_DISABLE_POLL

1
src/drivers/linux_pwm_out/linux_pwm_out.cpp

@ -43,6 +43,7 @@ @@ -43,6 +43,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/rc_channels.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>

2
src/drivers/rgbled/rgbled.cpp

@ -66,6 +66,8 @@ @@ -66,6 +66,8 @@
#include <drivers/drv_led.h>
#include <lib/led/led.h>
#include "uORB/topics/parameter_update.h"
#define RGBLED_ONTIME 120
#define RGBLED_OFFTIME 120

3
src/drivers/sf0x/sf0x_tests/SF0XTest.cpp

@ -4,7 +4,8 @@ @@ -4,7 +4,8 @@
#include <systemlib/err.h>
#include <stdio.h>
#include <cstdio>
#include <cstring>
#include <unistd.h>
extern "C" __EXPORT int sf0x_tests_main(int argc, char *argv[]);

1
src/examples/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp

@ -67,6 +67,7 @@ @@ -67,6 +67,7 @@
#include <mathlib/mathlib.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <platforms/px4_defines.h>
#include <uORB/topics/parameter_update.h>
static uint64_t IMUusec = 0;

1
src/modules/ekf2/ekf2_main.cpp

@ -83,6 +83,7 @@ @@ -83,6 +83,7 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/sensor_selection.h>
#include <uORB/topics/sensor_baro.h>
#include <uORB/topics/parameter_update.h>
#include <ecl/EKF/ekf.h>

2
src/modules/ekf2_replay/ekf2_replay_main.cpp

@ -70,6 +70,8 @@ @@ -70,6 +70,8 @@
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_status.h>
#include <sdlog2/sdlog2_messages.h>

8
src/modules/land_detector/LandDetector.cpp

@ -38,12 +38,14 @@ @@ -38,12 +38,14 @@
* @author Julian Oes <julian@oes.ch>
*/
#include "LandDetector.h"
#include <cfloat>
#include <px4_config.h>
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <float.h>
#include "LandDetector.h"
#include "uORB/topics/parameter_update.h"
namespace land_detector

1
src/modules/mavlink/mavlink_messages.cpp

@ -81,6 +81,7 @@ @@ -81,6 +81,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_land_detected.h>

2
src/modules/mc_pos_control/mc_pos_control_main.cpp

@ -60,10 +60,12 @@ @@ -60,10 +60,12 @@
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_land_detected.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <float.h>
#include <lib/geo/geo.h>

2
src/modules/micrortps_bridge/micrortps_client/microRTPS_client_dummy.cpp

@ -34,6 +34,8 @@ @@ -34,6 +34,8 @@
#include <px4_posix.h>
#include <px4_tasks.h>
#include <cstring>
extern "C" __EXPORT int micrortps_client_main(int argc, char *argv[]);

1
src/modules/navigator/navigator.h

@ -68,6 +68,7 @@ @@ -68,6 +68,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_land_detected.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/uORB.h>
/**

1
src/modules/position_estimator_inav/position_estimator_inav_main.cpp

@ -59,6 +59,7 @@ @@ -59,6 +59,7 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/att_pos_mocap.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/distance_sensor.h>

1
src/modules/sensors/rc_update.h

@ -44,6 +44,7 @@ @@ -44,6 +44,7 @@
#include <drivers/drv_hrt.h>
#include <mathlib/mathlib.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <uORB/topics/rc_channels.h>
namespace sensors
{

1
src/modules/simulator/simulator_mavlink.cpp

@ -45,6 +45,7 @@ @@ -45,6 +45,7 @@
#include <pthread.h>
#include <conversion/rotation.h>
#include <mathlib/mathlib.h>
#include <uORB/topics/vehicle_local_position.h>
extern "C" __EXPORT hrt_abstime hrt_reset(void);

84
src/platforms/px4_includes.h

@ -39,116 +39,50 @@ @@ -39,116 +39,50 @@
#pragma once
#include <stdbool.h>
#if defined(__PX4_ROS)
/*
* Building for running within the ROS environment
*/
#ifdef __cplusplus
#include "ros/ros.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_vehicle_rates_setpoint.h>
#include <px4_mc_virtual_rates_setpoint.h>
#include <px4_vehicle_attitude.h>
#include <px4_control_state.h>
#include <px4_vehicle_control_mode.h>
#include <px4_actuator_armed.h>
#include <px4_parameter_update.h>
#include <px4_vehicle_status.h>
#include <px4_vehicle_local_position_setpoint.h>
#include <px4_vehicle_local_position.h>
#include <px4_position_setpoint_triplet.h>
#include <px4_offboard_control_mode.h>
#include <px4_vehicle_force_setpoint.h>
#endif
#elif defined(__PX4_NUTTX)
/*
* Building for NuttX
*/
#include <nuttx/config.h>
#include <uORB/uORB.h>
#ifdef __cplusplus
#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_control_state.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>
#include <platforms/nuttx/px4_messages/px4_vehicle_local_position_setpoint.h>
#include <platforms/nuttx/px4_messages/px4_vehicle_local_position.h>
#include <platforms/nuttx/px4_messages/px4_position_setpoint_triplet.h>
#include <platforms/nuttx/px4_messages/px4_offboard_control_mode.h>
#include <platforms/nuttx/px4_messages/px4_vehicle_force_setpoint.h>
#include <platforms/nuttx/px4_messages/px4_camera_trigger.h>
#endif
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#elif defined(__PX4_POSIX) && !defined(__PX4_QURT)
/*
* Building for Posix
*/
#include <string.h>
#include <assert.h>
#include <uORB/uORB.h>
#define ASSERT(x) assert(x)
#ifdef __cplusplus
#include <platforms/posix/px4_messages/px4_rc_channels.h>
#include <platforms/posix/px4_messages/px4_vehicle_attitude_setpoint.h>
#include <platforms/posix/px4_messages/px4_manual_control_setpoint.h>
#include <platforms/posix/px4_messages/px4_actuator_controls.h>
#include <platforms/posix/px4_messages/px4_vehicle_rates_setpoint.h>
#include <platforms/posix/px4_messages/px4_vehicle_attitude.h>
#include <platforms/posix/px4_messages/px4_control_state.h>
#include <platforms/posix/px4_messages/px4_vehicle_control_mode.h>
#include <platforms/posix/px4_messages/px4_actuator_armed.h>
#include <platforms/posix/px4_messages/px4_parameter_update.h>
#include <platforms/posix/px4_messages/px4_vehicle_status.h>
#include <platforms/posix/px4_messages/px4_vehicle_local_position_setpoint.h>
#include <platforms/posix/px4_messages/px4_vehicle_local_position.h>
#include <platforms/posix/px4_messages/px4_position_setpoint_triplet.h>
#endif
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#elif defined(__PX4_QURT)
/*
* Building for QuRT
*/
#include <string.h>
#include <assert.h>
#include <uORB/uORB.h>
#define ASSERT(x) assert(x)
#ifdef __cplusplus
#include <platforms/qurt/px4_messages/px4_rc_channels.h>
#include <platforms/qurt/px4_messages/px4_vehicle_attitude_setpoint.h>
#include <platforms/qurt/px4_messages/px4_manual_control_setpoint.h>
#include <platforms/qurt/px4_messages/px4_actuator_controls.h>
#include <platforms/qurt/px4_messages/px4_vehicle_rates_setpoint.h>
#include <platforms/qurt/px4_messages/px4_vehicle_attitude.h>
#include <platforms/qurt/px4_messages/px4_control_state.h>
#include <platforms/qurt/px4_messages/px4_vehicle_control_mode.h>
#include <platforms/qurt/px4_messages/px4_actuator_armed.h>
#include <platforms/qurt/px4_messages/px4_parameter_update.h>
#include <platforms/qurt/px4_messages/px4_vehicle_status.h>
#include <platforms/qurt/px4_messages/px4_vehicle_local_position_setpoint.h>
#include <platforms/qurt/px4_messages/px4_vehicle_local_position.h>
#include <platforms/qurt/px4_messages/px4_position_setpoint_triplet.h>
#endif
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#else
#error "No target platform defined"
#endif

1
src/systemcmds/motor_ramp/motor_ramp.cpp

@ -58,6 +58,7 @@ @@ -58,6 +58,7 @@
#include "systemlib/systemlib.h"
#include "systemlib/err.h"
#include "uORB/topics/actuator_controls.h"
enum RampState {
RAMP_INIT,

Loading…
Cancel
Save