Skip to content

Commit

Permalink
src/platforms/common: move to platforms/common
Browse files Browse the repository at this point in the history
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
  • Loading branch information
bkueng committed Aug 30, 2019
1 parent 5d0e720 commit f8e0441
Show file tree
Hide file tree
Showing 124 changed files with 91 additions and 91 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
1 change: 0 additions & 1 deletion cmake/px4_add_common_flags.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
1 change: 1 addition & 0 deletions src/platforms/CMakeLists.txt → platforms/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,3 +33,4 @@

add_subdirectory(common)


File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
*
****************************************************************************/

#include "ScheduledWorkItem.hpp"
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>

namespace px4
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
2 changes: 1 addition & 1 deletion platforms/nuttx/src/px4/common/px4_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion platforms/posix/src/px4/common/px4_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
2 changes: 1 addition & 1 deletion platforms/qurt/src/px4/common/px4_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/adc/adc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/bmp280/bmp280.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/lps22hb/LPS22HB.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/lps25h/lps25h.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/mpl3115a2/mpl3115a2.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/ms5611/ms5611.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/batt_smbus/batt_smbus.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/camera_capture/camera_capture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/camera_trigger/camera_trigger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/cm8jl65/cm8jl65.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/leddar_one/leddar_one.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/ll40ls/LidarLiteI2C.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/ll40ls/LidarLitePWM.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/mappydot/MappyDot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/mb12xx/mb12xx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/sf0x/sf0x.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/sf1xx/sf1xx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/srf02/srf02.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/teraranger/teraranger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/tfmini/tfmini.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/ulanding/ulanding.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/vl53lxx/vl53lxx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/heater/heater.h
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/adis16448/ADIS16448.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/adis16477/ADIS16477.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/adis16497/ADIS16497.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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[] = {
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/imu/bma180/bma180.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand All @@ -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"

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi055/BMI055.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi088/BMI088.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/imu/bmi160/bmi160.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading

0 comments on commit f8e0441

Please sign in to comment.