mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
cmake don't build param "c" files and remove param defines
- these aren't actual source code
This commit is contained in:
parent
f984c4e450
commit
1c4e854f93
@ -40,7 +40,6 @@ px4_add_module(
|
||||
syslink_main.cpp
|
||||
syslink_bridge.cpp
|
||||
syslink_memory.cpp
|
||||
syslink_params.c
|
||||
syslink.c
|
||||
DEPENDS
|
||||
battery
|
||||
|
||||
@ -39,10 +39,6 @@
|
||||
* @author Dennis Shtatnov <densht@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
|
||||
/**
|
||||
* Operating channel of the NRF51
|
||||
*
|
||||
|
||||
@ -35,7 +35,7 @@ set(SRCS)
|
||||
|
||||
if (NOT "${PX4_PLATFORM}" MATCHES "qurt" AND NOT "${PX4_BOARD}" MATCHES "io-v2")
|
||||
list(APPEND SRCS
|
||||
px4_log.c
|
||||
px4_log.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
|
||||
@ -49,22 +49,9 @@
|
||||
* Defines for all platforms.
|
||||
****************************************************************************/
|
||||
|
||||
/* Get the name of the default value fiven the param name */
|
||||
#define PX4_PARAM_DEFAULT_VALUE_NAME(_name) PARAM_##_name##_DEFAULT
|
||||
|
||||
/* Shortcuts to define parameters when the default value is defined according to PX4_PARAM_DEFAULT_VALUE_NAME */
|
||||
#define PX4_PARAM_DEFINE_INT32(_name) PARAM_DEFINE_INT32(_name, PX4_PARAM_DEFAULT_VALUE_NAME(_name))
|
||||
#define PX4_PARAM_DEFINE_FLOAT(_name) PARAM_DEFINE_FLOAT(_name, PX4_PARAM_DEFAULT_VALUE_NAME(_name))
|
||||
|
||||
#define PX4_ERROR (-1)
|
||||
#define PX4_OK 0
|
||||
|
||||
/* Wrapper for 2d matrices */
|
||||
#define PX4_ARRAY2D(_array, _ncols, _x, _y) (_array[_x * _ncols + _y])
|
||||
|
||||
/* Wrapper for rotation matrices stored in arrays */
|
||||
#define PX4_R(_array, _x, _y) PX4_ARRAY2D(_array, 3, _x, _y)
|
||||
|
||||
/* Define PX4_ISFINITE */
|
||||
#ifdef __cplusplus
|
||||
constexpr bool PX4_ISFINITE(float x) { return __builtin_isfinite(x); }
|
||||
@ -79,13 +66,6 @@ constexpr bool PX4_ISFINITE(double x) { return __builtin_isfinite(x); }
|
||||
/* Main entry point */
|
||||
#define PX4_MAIN_FUNCTION(_prefix) int _prefix##_task_main(int argc, char *argv[])
|
||||
|
||||
/* Parameter handle datatype */
|
||||
#include <parameters/param.h>
|
||||
typedef param_t px4_param_t;
|
||||
|
||||
/* Get value of parameter by name */
|
||||
#define PX4_PARAM_GET_BYNAME(_name, _destpt) param_get(param_find(_name), _destpt)
|
||||
|
||||
#else // defined(__PX4_NUTTX) || defined(__PX4_POSIX)
|
||||
/****************************************************************************/
|
||||
#error "No target OS defined"
|
||||
|
||||
@ -49,7 +49,7 @@
|
||||
#include <uORB/topics/log_message.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
static orb_advert_t orb_log_message_pub = NULL;
|
||||
static orb_advert_t orb_log_message_pub = nullptr;
|
||||
|
||||
__EXPORT const char *__px4_log_level_str[_PX4_LOG_LEVEL_PANIC + 1] = { "DEBUG", "INFO", "WARN", "ERROR", "PANIC" };
|
||||
__EXPORT const char *__px4_log_level_color[_PX4_LOG_LEVEL_PANIC + 1] =
|
||||
@ -58,7 +58,7 @@ __EXPORT const char *__px4_log_level_color[_PX4_LOG_LEVEL_PANIC + 1] =
|
||||
|
||||
void px4_log_initialize(void)
|
||||
{
|
||||
assert(orb_log_message_pub == NULL);
|
||||
assert(orb_log_message_pub == nullptr);
|
||||
|
||||
/* we need to advertise with a valid message */
|
||||
struct log_message_s log_message;
|
||||
@ -35,6 +35,8 @@
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
testing::InitGoogleTest(&argc, argv);
|
||||
|
||||
@ -43,6 +43,8 @@
|
||||
|
||||
#include "batt_smbus.h"
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]);
|
||||
|
||||
BATT_SMBUS::BATT_SMBUS(SMBus *interface, const char *path) :
|
||||
|
||||
@ -63,6 +63,7 @@
|
||||
#include <drivers/drv_range_finder.h>
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
|
||||
@ -61,6 +61,7 @@
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
@ -39,6 +39,7 @@
|
||||
*/
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
|
||||
@ -48,7 +48,7 @@
|
||||
#include <unistd.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
|
||||
@ -50,7 +50,7 @@
|
||||
#include <unistd.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
|
||||
@ -52,7 +52,7 @@
|
||||
#include <errno.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
|
||||
|
||||
@ -50,6 +50,7 @@
|
||||
#include <errno.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
|
||||
|
||||
@ -50,7 +50,7 @@
|
||||
#include <unistd.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
|
||||
@ -47,6 +47,7 @@
|
||||
|
||||
#include <termios.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <matrix/math.hpp>
|
||||
#include <px4_platform_common/cli.h>
|
||||
|
||||
@ -44,6 +44,7 @@
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <lib/led/led.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
@ -43,6 +43,7 @@
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <lib/led/led.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
@ -36,7 +36,6 @@ px4_add_module(
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
mkblctrl.cpp
|
||||
mkblctrl_params.c
|
||||
DEPENDS
|
||||
mixer
|
||||
)
|
||||
|
||||
@ -44,6 +44,7 @@
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
@ -51,7 +51,6 @@ px4_add_module(
|
||||
${FC_ADDON}/flight_controller/hexagon/inc
|
||||
SRCS
|
||||
mpu9x50_main.cpp
|
||||
mpu9x50_params.c
|
||||
DEPENDS
|
||||
)
|
||||
target_link_libraries(platforms__qurt__fc_addon__mpu_spi PRIVATE mpu9x50)
|
||||
|
||||
@ -51,6 +51,5 @@ px4_add_module(
|
||||
${FC_ADDON}/flight_controller/hexagon/inc
|
||||
SRCS
|
||||
rc_receiver_main.cpp
|
||||
rc_receiver_params.c
|
||||
)
|
||||
target_link_libraries(platforms__qurt__fc_addon__rc_receiver PRIVATE rc_receiver)
|
||||
|
||||
@ -51,7 +51,6 @@ px4_add_module(
|
||||
${FC_ADDON}/flight_controller/hexagon/inc
|
||||
SRCS
|
||||
uart_esc_main.cpp
|
||||
uart_esc_params.c
|
||||
DEPENDS
|
||||
)
|
||||
target_link_libraries(platforms__qurt__fc_addon__uart_esc PRIVATE uart_esc)
|
||||
|
||||
@ -46,6 +46,7 @@
|
||||
#include <poll.h>
|
||||
#include <stdio.h>
|
||||
#include <termios.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <uORB/SubscriptionPollable.hpp>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/wheel_encoders.h>
|
||||
|
||||
@ -37,7 +37,6 @@ px4_add_module(
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
IridiumSBD.cpp
|
||||
iridiumsbd_params.c
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
|
||||
@ -1,4 +1,3 @@
|
||||
#include <parameters/param.h>
|
||||
|
||||
/**
|
||||
* Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call.
|
||||
|
||||
@ -111,7 +111,6 @@ px4_add_module(
|
||||
# Main
|
||||
uavcan_main.cpp
|
||||
uavcan_servers.cpp
|
||||
uavcan_params.c
|
||||
|
||||
# Actuators
|
||||
actuators/esc.cpp
|
||||
|
||||
@ -35,9 +35,6 @@
|
||||
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
/**
|
||||
* UAVCAN mode
|
||||
*
|
||||
|
||||
@ -81,7 +81,6 @@ px4_add_module(
|
||||
uavcanesc_main.cpp
|
||||
indication_controller.cpp
|
||||
led.cpp
|
||||
uavcanesc_params.c
|
||||
DEPENDS
|
||||
drivers_bootloaders
|
||||
git_uavcan
|
||||
|
||||
@ -81,7 +81,6 @@ px4_add_module(
|
||||
sim_controller.cpp
|
||||
led.cpp
|
||||
resources.cpp
|
||||
uavcannode_params.c
|
||||
DEPENDS
|
||||
drivers_bootloaders
|
||||
git_uavcan
|
||||
|
||||
@ -46,12 +46,13 @@
|
||||
|
||||
#include <stdint.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
bool circuit_breaker_enabled(const char *breaker, int32_t magic)
|
||||
{
|
||||
int32_t val = -1;
|
||||
|
||||
return (PX4_PARAM_GET_BYNAME(breaker, &val) == 0) && (val == magic);
|
||||
return (param_get(param_find(breaker), &val) == 0) && (val == magic);
|
||||
}
|
||||
|
||||
bool circuit_breaker_enabled_by_val(int32_t breaker_val, int32_t magic)
|
||||
|
||||
@ -410,27 +410,6 @@ __EXPORT void param_print_status(void);
|
||||
*/
|
||||
__EXPORT void param_control_autosave(bool enable);
|
||||
|
||||
/*
|
||||
* Macros creating static parameter definitions.
|
||||
*
|
||||
* Note that these structures are not known by name; they are
|
||||
* collected into a section that is iterated by the parameter
|
||||
* code.
|
||||
*
|
||||
* Note that these macros cannot be used in C++ code due to
|
||||
* their use of designated initializers. They should probably
|
||||
* be refactored to avoid the use of a union for param_value_u.
|
||||
*/
|
||||
|
||||
/** define an int32 parameter */
|
||||
#define PARAM_DEFINE_INT32(_name, _default)
|
||||
|
||||
/** define a float parameter */
|
||||
#define PARAM_DEFINE_FLOAT(_name, _default)
|
||||
|
||||
/** define a parameter that points to a structure */
|
||||
#define PARAM_DEFINE_STRUCT(_name, _default)
|
||||
|
||||
/**
|
||||
* Parameter value union.
|
||||
*/
|
||||
|
||||
@ -37,7 +37,7 @@
|
||||
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <uORB/PublicationQueued.hpp>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
|
||||
@ -39,6 +39,7 @@
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <HealthFlags.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/subsystem_info.h>
|
||||
|
||||
@ -35,6 +35,7 @@
|
||||
|
||||
#include <HealthFlags.h>
|
||||
#include <math.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
|
||||
@ -34,6 +34,8 @@
|
||||
#include "../PreFlightCheck.hpp"
|
||||
|
||||
#include <HealthFlags.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/sensor_preflight.h>
|
||||
|
||||
@ -34,6 +34,8 @@
|
||||
#include "../PreFlightCheck.hpp"
|
||||
|
||||
#include <HealthFlags.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
|
||||
@ -42,6 +42,7 @@
|
||||
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
#include "polyfit.hpp"
|
||||
|
||||
|
||||
@ -46,6 +46,7 @@
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/time.h>
|
||||
#include <px4_platform_common/shutdown.h>
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
#include <cstring>
|
||||
#include <float.h>
|
||||
|
||||
@ -44,7 +44,7 @@
|
||||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <lib/parameters/param.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <errno.h>
|
||||
|
||||
@ -52,6 +52,7 @@
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
|
||||
|
||||
@ -39,6 +39,7 @@
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user