mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-18 07:17:35 +08:00
cmake remove circular linking and reorganize
- px4_add_module now requires MAIN - px4_add_library doesn't automatically link
This commit is contained in:
@@ -38,6 +38,5 @@ px4_add_module(
|
||||
SRCS
|
||||
bottle_drop.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
|
||||
@@ -61,7 +61,7 @@
|
||||
#include <uORB/topics/wind_estimate.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
/**
|
||||
* Ground drag property
|
||||
|
||||
@@ -38,6 +38,4 @@ px4_add_module(
|
||||
SRCS
|
||||
main.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -52,8 +52,8 @@
|
||||
#include <px4_config.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
@@ -38,7 +38,7 @@
|
||||
* Definition of parameters for fixedwing example
|
||||
*/
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
struct params {
|
||||
float hdng_p;
|
||||
|
||||
@@ -37,6 +37,4 @@ px4_add_module(
|
||||
SRCS
|
||||
hwtest.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -37,6 +37,4 @@ px4_add_module(
|
||||
SRCS
|
||||
matlab_csv_serial.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -58,7 +58,7 @@
|
||||
#include <uORB/uORB.h>
|
||||
#include <drivers/drv_accel.h>
|
||||
#include <drivers/drv_gyro.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <poll.h>
|
||||
|
||||
@@ -39,6 +39,4 @@ px4_add_module(
|
||||
publisher_start_nuttx.cpp
|
||||
publisher_example.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -37,6 +37,4 @@ px4_add_module(
|
||||
SRCS
|
||||
px4_mavlink_debug.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -37,6 +37,4 @@ px4_add_module(
|
||||
SRCS
|
||||
px4_simple_app.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -38,6 +38,4 @@ px4_add_module(
|
||||
SRCS
|
||||
main.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -61,10 +61,10 @@
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
|
||||
@@ -38,6 +38,6 @@
|
||||
* Definition of parameters for fixedwing example
|
||||
*/
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
|
||||
|
||||
@@ -40,6 +40,5 @@ px4_add_module(
|
||||
segway_main.cpp
|
||||
BlockSegwayController.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
// 16 is max name length
|
||||
PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage
|
||||
|
||||
@@ -45,7 +45,7 @@
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <math.h>
|
||||
|
||||
@@ -40,6 +40,4 @@ px4_add_module(
|
||||
subscriber_example.cpp
|
||||
subscriber_params.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -37,6 +37,4 @@ px4_add_module(
|
||||
SRCS
|
||||
uuv_example_app.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
@@ -51,9 +51,9 @@
|
||||
#include <math.h>
|
||||
|
||||
// system libraries
|
||||
#include <systemlib/param/param.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/circuit_breaker.h>
|
||||
// internal libraries
|
||||
|
||||
Reference in New Issue
Block a user