src/platforms/common: move to platforms/common

Script to update include paths:
for i in $(grep -rl 'include <px4_work_queue' src platforms); do sed -i 's/#include <px4_work_queue/#include <px4_platform_common\/px4_work_queue/' $i; done
This commit is contained in:
Beat Küng 2019-08-27 10:57:38 +02:00
parent 5d0e72040c
commit f8e0441e7b
124 changed files with 91 additions and 91 deletions

View File

@ -463,7 +463,7 @@ include(px4_add_library)
add_subdirectory(src/lib EXCLUDE_FROM_ALL)
add_subdirectory(platforms/${PX4_PLATFORM}/src/px4)
add_subdirectory(src/platforms EXCLUDE_FROM_ALL)
add_subdirectory(platforms EXCLUDE_FROM_ALL)
add_subdirectory(src/modules/uORB EXCLUDE_FROM_ALL) # TODO: platform layer
add_subdirectory(src/drivers/boards EXCLUDE_FROM_ALL)

View File

@ -184,7 +184,6 @@ function(px4_add_common_flags)
${PX4_SOURCE_DIR}/src/lib/matrix
${PX4_SOURCE_DIR}/src/modules
${PX4_SOURCE_DIR}/src/platforms
${PX4_SOURCE_DIR}/src/platforms/common
)
add_definitions(

View File

@ -33,3 +33,4 @@
add_subdirectory(common)

View File

@ -31,7 +31,7 @@
*
****************************************************************************/
#include "ScheduledWorkItem.hpp"
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
namespace px4
{

View File

@ -31,10 +31,10 @@
*
****************************************************************************/
#include "WorkItem.hpp"
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include "WorkQueue.hpp"
#include "WorkQueueManager.hpp"
#include <px4_platform_common/px4_work_queue/WorkQueue.hpp>
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
#include <px4_log.h>
#include <drivers/drv_hrt.h>

View File

@ -31,8 +31,8 @@
*
****************************************************************************/
#include "WorkQueue.hpp"
#include "WorkItem.hpp"
#include <px4_platform_common/px4_work_queue/WorkQueue.hpp>
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include <string.h>

View File

@ -31,9 +31,9 @@
*
****************************************************************************/
#include "WorkQueueManager.hpp"
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
#include "WorkQueue.hpp"
#include <px4_platform_common/px4_work_queue/WorkQueue.hpp>
#include <drivers/drv_hrt.h>
#include <px4_posix.h>

View File

@ -34,7 +34,7 @@
#pragma once
#include <px4_app.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <string.h>
using namespace px4;

View File

@ -34,7 +34,7 @@
#pragma once
#include <px4_app.h>
#include <px4_work_queue/WorkItem.hpp>
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include <string.h>
using namespace px4;

View File

@ -38,7 +38,7 @@
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <px4_work_queue/WorkQueueManager.hpp>
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
#include <systemlib/cpuload.h>
#include <fcntl.h>

View File

@ -37,7 +37,7 @@
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <px4_work_queue/WorkQueueManager.hpp>
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
int px4_platform_init(void)
{

View File

@ -37,7 +37,7 @@
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <px4_work_queue/WorkQueueManager.hpp>
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
int px4_platform_init(void)
{

View File

@ -45,7 +45,7 @@
#include <px4_arch/adc.h>
#include <px4_config.h>
#include <px4_log.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/adc_report.h>
#include <uORB/topics/system_power.h>

View File

@ -50,7 +50,7 @@
#include <perf/perf_counter.h>
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include "board_config.h"

View File

@ -42,7 +42,7 @@
#include <lib/cdev/CDev.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>

View File

@ -49,7 +49,7 @@
#include <lib/cdev/CDev.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>

View File

@ -68,7 +68,7 @@
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_log.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include "board_config.h"

View File

@ -49,7 +49,7 @@
#include <lib/cdev/CDev.hpp>
#include <lib/perf/perf_counter.h>
#include <platforms/px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>

View File

@ -49,7 +49,7 @@
#include <perf/perf_counter.h>
#include <platforms/px4_module.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/battery_status.h>
#include "board_config.h"

View File

@ -48,7 +48,7 @@
#include <px4_module.h>
#include <px4_tasks.h>
#include <px4_workqueue.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>

View File

@ -50,7 +50,7 @@
#include <poll.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <systemlib/mavlink_log.h>

View File

@ -45,7 +45,7 @@
#include <px4_cli.h>
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <stdbool.h>
#include <stdint.h>
#include <stdio.h>

View File

@ -32,7 +32,7 @@
****************************************************************************/
#include <px4_config.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_getopt.h>
#include <px4_defines.h>
#include <px4_module.h>

View File

@ -42,7 +42,7 @@
#include "LidarLite.h"
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <drivers/device/i2c.h>

View File

@ -45,7 +45,7 @@
#include "LidarLite.h"
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/pwm_input.h>
class LidarLitePWM : public LidarLite, public px4::ScheduledWorkItem

View File

@ -47,7 +47,7 @@
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_module_params.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/distance_sensor.h>
/* MappyDot Registers */

View File

@ -63,7 +63,7 @@
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_module_params.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/uORB.h>
#include <uORB/topics/distance_sensor.h>

View File

@ -41,7 +41,7 @@
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <sys/types.h>
#include <stdint.h>

View File

@ -44,7 +44,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_module.h>
#include <drivers/device/i2c.h>

View File

@ -40,7 +40,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <containers/Array.hpp>
#include <drivers/device/i2c.h>

View File

@ -41,7 +41,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_module.h>
#include <drivers/device/i2c.h>

View File

@ -66,7 +66,7 @@
#include <px4_config.h>
#include <px4_getopt.h>
#include <px4_module.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/distance_sensor.h>

View File

@ -63,7 +63,7 @@
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/uORB.h>

View File

@ -48,7 +48,7 @@
#include <drivers/drv_range_finder.h>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/distance_sensor.h>
/* Configuration Constants */

View File

@ -45,7 +45,7 @@
#include <px4_getopt.h>
#include <px4_module.h>
#include <px4_module_params.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_accel.h>

View File

@ -50,7 +50,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#include <perf/perf_counter.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
using namespace time_literals;

View File

@ -45,7 +45,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
class ADIS16477 : public device::SPI, public px4::ScheduledWorkItem
{

View File

@ -45,7 +45,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
// TODO : This is a copy of the NuttX CRC32 table
static constexpr uint32_t crc32_tab[] = {

View File

@ -57,7 +57,7 @@
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <nuttx/arch.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
@ -66,7 +66,7 @@
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
#include <drivers/device/ringbuffer.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#define ACCEL_DEVICE_PATH "/dev/bma180"

View File

@ -37,7 +37,7 @@
#include <ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#define DIR_READ 0x80
#define DIR_WRITE 0x00

View File

@ -38,7 +38,7 @@
#include <lib/conversion/rotation.h>
#include <lib/perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#define DIR_READ 0x80
#define DIR_WRITE 0x00

View File

@ -40,7 +40,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/conversions.h>
#define DIR_READ 0x80

View File

@ -43,7 +43,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
class FXAS21002C : public device::SPI, public px4::ScheduledWorkItem

View File

@ -46,7 +46,7 @@
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)

View File

@ -44,7 +44,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/conversion/rotation.h>
#include <systemlib/err.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/uORB.h>

View File

@ -44,7 +44,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#define L3GD20_DEVICE_PATH "/dev/l3gd20"

View File

@ -41,7 +41,7 @@
#include <drivers/device/spi.h>
#include <ecl/geo/geo.h>
#include <perf/perf_counter.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>

View File

@ -63,7 +63,7 @@
#include <lib/ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/conversions.h>
#include <systemlib/px4_macros.h>

View File

@ -35,7 +35,7 @@
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/conversions.h>
#include <systemlib/px4_macros.h>

View File

@ -46,7 +46,7 @@
#include <drivers/device/ringbuffer.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>

View File

@ -99,7 +99,7 @@
#include <drivers/device/i2c.h>
#include <drivers/drv_blinkm.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/battery_status.h>

View File

@ -47,7 +47,7 @@
#include <drivers/drv_oreoled.h>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#define OREOLED_NUM_LEDS 4 ///< maximum number of LEDs the oreo led driver can support

View File

@ -46,7 +46,7 @@
#include <drivers/device/i2c.h>
#include <drivers/drv_io_expander.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>

View File

@ -45,7 +45,7 @@
#include <drivers/device/i2c.h>
#include <lib/led/led.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/parameter_update.h>

View File

@ -44,7 +44,7 @@
#include <drivers/device/i2c.h>
#include <lib/led/led.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/parameter_update.h>

View File

@ -44,7 +44,7 @@
#include <drivers/device/device.h>
#include <lib/led/led.h>
#include <px4_getopt.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
class RGBLED_PWM : public device::CDev, public px4::ScheduledWorkItem
{

View File

@ -48,7 +48,7 @@
#include <asm-generic/termbits.h>
#include <errno.h>
#include <px4_config.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>

View File

@ -39,7 +39,7 @@
#include <systemlib/conversions.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/i2c.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#define AK09916_DEVICE_PATH_MAG "/dev/ak09916_i2c_int"

View File

@ -20,7 +20,7 @@
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/conversions.h>
#include <nuttx/arch.h>

View File

@ -57,7 +57,7 @@
#include <unistd.h>
#include <nuttx/arch.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <nuttx/clock.h>
#include <board_config.h>

View File

@ -76,7 +76,7 @@
#include <float.h>
#include <lib/conversion/rotation.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
/*
* IST8310 internal constants and data structures.

View File

@ -48,7 +48,7 @@
#include <lib/conversion/rotation.h>
#include <systemlib/err.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <perf/perf_counter.h>
#include <px4_defines.h>

View File

@ -42,7 +42,7 @@
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#include <perf/perf_counter.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
// Register mapping

Some files were not shown because too many files have changed in this diff Show More