mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 13:02:25 +08:00
Some gentle massaging to get things building again.
This commit is contained in:
+6
-2
@@ -1,12 +1,16 @@
|
||||
.built
|
||||
*.context
|
||||
*.bdat
|
||||
*.pdat
|
||||
.depend
|
||||
.updated
|
||||
.config
|
||||
.config-e
|
||||
.version
|
||||
.project
|
||||
.cproject
|
||||
apps/namedapp/namedapp_list.h
|
||||
apps/namedapp/namedapp_proto.h
|
||||
apps/builtin/builtin_list.h
|
||||
apps/builtin/builtin_proto.h
|
||||
Make.dep
|
||||
*.pyc
|
||||
*.o
|
||||
|
||||
+4
-1
@@ -49,7 +49,10 @@ APPDIR = ${shell pwd}
|
||||
# list can be extended by the .config file as well.
|
||||
|
||||
CONFIGURED_APPS =
|
||||
SUBDIRS = examples graphics interpreters modbus builtin nshlib netutils system
|
||||
|
||||
SUBDIRS = examples interpreters builtin nshlib system
|
||||
|
||||
#SUBDIRS = examples graphics interpreters modbus builtin nshlib netutils system
|
||||
|
||||
# There are two different mechanisms for obtaining the list of configured
|
||||
# directories:
|
||||
|
||||
@@ -293,7 +293,7 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
|
||||
int errcode;
|
||||
int ret;
|
||||
|
||||
DEBUGASSERT(path);
|
||||
// DEBUGASSERT(path);
|
||||
|
||||
svdbg("index=%d argv=%p redirfile=%s oflags=%04x\n",
|
||||
index, argv, redirfile, oflags);
|
||||
|
||||
+15
-9
@@ -37,12 +37,15 @@
|
||||
|
||||
# Sub-directories
|
||||
|
||||
SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc
|
||||
SUBDIRS += ftpd hello helloxx hidkbd igmp json keypadtest lcdrw mm modbus mount
|
||||
SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage
|
||||
SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm posix_spawn qencoder
|
||||
SUBDIRS += relays rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip
|
||||
SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson
|
||||
SUBDIRS = adc can cdcacm nsh
|
||||
SUBDIRS += math_demo control_demo kalman_demo px4_deamon_app
|
||||
|
||||
#SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc
|
||||
#SUBDIRS += ftpd hello helloxx hidkbd igmp json keypadtest lcdrw mm modbus mount
|
||||
#SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage
|
||||
#SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm posix_spawn qencoder
|
||||
#SUBDIRS += relays rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip
|
||||
#SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson
|
||||
|
||||
# Sub-directories that might need context setup. Directories may need
|
||||
# context setup for a variety of reasons, but the most common is because
|
||||
@@ -57,9 +60,12 @@ SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson
|
||||
CNTXTDIRS = pwm
|
||||
|
||||
ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
|
||||
CNTXTDIRS += adc can cdcacm composite cxxtest dhcpd discover ftpd hello json
|
||||
CNTXTDIRS += keypadtestmodbus nettest nxlines relays qencoder telnetd watchdog
|
||||
CNTXTDIRS += wgetjson
|
||||
|
||||
CNTXTDIRS += adc can cdcacm
|
||||
|
||||
#CNTXTDIRS += adc can cdcacm composite cxxtest dhcpd discover ftpd hello json
|
||||
#CNTXTDIRS += keypadtestmodbus nettest nxlines relays qencoder telnetd watchdog
|
||||
#CNTXTDIRS += wgetjson
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_EXAMPLES_HELLOXX_BUILTIN),y)
|
||||
|
||||
@@ -0,0 +1,42 @@
|
||||
/* List of application requirements, generated during make context. */
|
||||
{ "math_demo", SCHED_PRIORITY_DEFAULT, 8192, math_demo_main },
|
||||
{ "control_demo", SCHED_PRIORITY_DEFAULT, 2048, control_demo_main },
|
||||
{ "kalman_demo", SCHED_PRIORITY_MAX - 30, 2048, kalman_demo_main },
|
||||
{ "reboot", SCHED_PRIORITY_DEFAULT, 2048, reboot_main },
|
||||
{ "perf", SCHED_PRIORITY_DEFAULT, 2048, perf_main },
|
||||
{ "top", SCHED_PRIORITY_DEFAULT - 10, 3000, top_main },
|
||||
{ "boardinfo", SCHED_PRIORITY_DEFAULT, 2048, boardinfo_main },
|
||||
{ "mixer", SCHED_PRIORITY_DEFAULT, 4096, mixer_main },
|
||||
{ "eeprom", SCHED_PRIORITY_DEFAULT, 4096, eeprom_main },
|
||||
{ "param", SCHED_PRIORITY_DEFAULT, 4096, param_main },
|
||||
{ "bl_update", SCHED_PRIORITY_DEFAULT, 4096, bl_update_main },
|
||||
{ "preflight_check", SCHED_PRIORITY_DEFAULT, 2048, preflight_check_main },
|
||||
{ "delay_test", SCHED_PRIORITY_DEFAULT, 2048, delay_test_main },
|
||||
{ "uorb", SCHED_PRIORITY_DEFAULT, 4096, uorb_main },
|
||||
{ "mavlink", SCHED_PRIORITY_DEFAULT, 2048, mavlink_main },
|
||||
{ "mavlink_onboard", SCHED_PRIORITY_DEFAULT, 2048, mavlink_onboard_main },
|
||||
{ "gps", SCHED_PRIORITY_DEFAULT, 2048, gps_main },
|
||||
{ "commander", SCHED_PRIORITY_MAX - 30, 2048, commander_main },
|
||||
{ "sdlog", SCHED_PRIORITY_MAX - 30, 2048, sdlog_main },
|
||||
{ "sensors", SCHED_PRIORITY_MAX-5, 4096, sensors_main },
|
||||
{ "ardrone_interface", SCHED_PRIORITY_MAX - 15, 2048, ardrone_interface_main },
|
||||
{ "multirotor_att_control", SCHED_PRIORITY_MAX - 15, 2048, multirotor_att_control_main },
|
||||
{ "multirotor_pos_control", SCHED_PRIORITY_MAX - 25, 2048, multirotor_pos_control_main },
|
||||
{ "fixedwing_att_control", SCHED_PRIORITY_MAX - 30, 2048, fixedwing_att_control_main },
|
||||
{ "fixedwing_pos_control", SCHED_PRIORITY_MAX - 30, 2048, fixedwing_pos_control_main },
|
||||
{ "position_estimator", SCHED_PRIORITY_DEFAULT, 4096, position_estimator_main },
|
||||
{ "attitude_estimator_ekf", SCHED_PRIORITY_DEFAULT, 2048, attitude_estimator_ekf_main },
|
||||
{ "ms5611", SCHED_PRIORITY_DEFAULT, 2048, ms5611_main },
|
||||
{ "hmc5883", SCHED_PRIORITY_DEFAULT, 4096, hmc5883_main },
|
||||
{ "mpu6000", SCHED_PRIORITY_DEFAULT, 4096, mpu6000_main },
|
||||
{ "bma180", SCHED_PRIORITY_DEFAULT, 2048, bma180_main },
|
||||
{ "l3gd20", SCHED_PRIORITY_DEFAULT, 2048, l3gd20_main },
|
||||
{ "px4io", SCHED_PRIORITY_DEFAULT, 2048, px4io_main },
|
||||
{ "blinkm", SCHED_PRIORITY_DEFAULT, 2048, blinkm_main },
|
||||
{ "tone_alarm", SCHED_PRIORITY_DEFAULT, 2048, tone_alarm_main },
|
||||
{ "adc", SCHED_PRIORITY_DEFAULT, 2048, adc_main },
|
||||
{ "fmu", SCHED_PRIORITY_DEFAULT, 2048, fmu_main },
|
||||
{ "hil", SCHED_PRIORITY_DEFAULT, 2048, hil_main },
|
||||
{ "tests", SCHED_PRIORITY_DEFAULT, 12000, tests_main },
|
||||
{ "sercon", SCHED_PRIORITY_DEFAULT, 2048, sercon_main },
|
||||
{ "serdis", SCHED_PRIORITY_DEFAULT, 2048, serdis_main },
|
||||
@@ -0,0 +1,42 @@
|
||||
/* List of application entry points, generated during make context. */
|
||||
EXTERN int math_demo_main(int argc, char *argv[]);
|
||||
EXTERN int control_demo_main(int argc, char *argv[]);
|
||||
EXTERN int kalman_demo_main(int argc, char *argv[]);
|
||||
EXTERN int reboot_main(int argc, char *argv[]);
|
||||
EXTERN int perf_main(int argc, char *argv[]);
|
||||
EXTERN int top_main(int argc, char *argv[]);
|
||||
EXTERN int boardinfo_main(int argc, char *argv[]);
|
||||
EXTERN int mixer_main(int argc, char *argv[]);
|
||||
EXTERN int eeprom_main(int argc, char *argv[]);
|
||||
EXTERN int param_main(int argc, char *argv[]);
|
||||
EXTERN int bl_update_main(int argc, char *argv[]);
|
||||
EXTERN int preflight_check_main(int argc, char *argv[]);
|
||||
EXTERN int delay_test_main(int argc, char *argv[]);
|
||||
EXTERN int uorb_main(int argc, char *argv[]);
|
||||
EXTERN int mavlink_main(int argc, char *argv[]);
|
||||
EXTERN int mavlink_onboard_main(int argc, char *argv[]);
|
||||
EXTERN int gps_main(int argc, char *argv[]);
|
||||
EXTERN int commander_main(int argc, char *argv[]);
|
||||
EXTERN int sdlog_main(int argc, char *argv[]);
|
||||
EXTERN int sensors_main(int argc, char *argv[]);
|
||||
EXTERN int ardrone_interface_main(int argc, char *argv[]);
|
||||
EXTERN int multirotor_att_control_main(int argc, char *argv[]);
|
||||
EXTERN int multirotor_pos_control_main(int argc, char *argv[]);
|
||||
EXTERN int fixedwing_att_control_main(int argc, char *argv[]);
|
||||
EXTERN int fixedwing_pos_control_main(int argc, char *argv[]);
|
||||
EXTERN int position_estimator_main(int argc, char *argv[]);
|
||||
EXTERN int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||
EXTERN int ms5611_main(int argc, char *argv[]);
|
||||
EXTERN int hmc5883_main(int argc, char *argv[]);
|
||||
EXTERN int mpu6000_main(int argc, char *argv[]);
|
||||
EXTERN int bma180_main(int argc, char *argv[]);
|
||||
EXTERN int l3gd20_main(int argc, char *argv[]);
|
||||
EXTERN int px4io_main(int argc, char *argv[]);
|
||||
EXTERN int blinkm_main(int argc, char *argv[]);
|
||||
EXTERN int tone_alarm_main(int argc, char *argv[]);
|
||||
EXTERN int adc_main(int argc, char *argv[]);
|
||||
EXTERN int fmu_main(int argc, char *argv[]);
|
||||
EXTERN int hil_main(int argc, char *argv[]);
|
||||
EXTERN int tests_main(int argc, char *argv[]);
|
||||
EXTERN int sercon_main(int argc, char *argv[]);
|
||||
EXTERN int serdis_main(int argc, char *argv[]);
|
||||
@@ -940,6 +940,7 @@ CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6"
|
||||
# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors
|
||||
# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint
|
||||
#
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_STRERROR=y
|
||||
|
||||
Reference in New Issue
Block a user