WIP: px4log

This commit is contained in:
Daniel Agar 2023-03-10 15:00:35 -05:00
parent 0ae296bfe2
commit b4555db0e7
No known key found for this signature in database
GPG Key ID: FD3CBA98017A69DE
245 changed files with 573 additions and 1185 deletions

View File

@ -79,7 +79,7 @@ get_property(romfs_cmake_files GLOBAL PROPERTY PX4_ROMFS_CMAKE_FILES)
get_property(romfs_copy_files GLOBAL PROPERTY PX4_ROMFS_FILES)
get_property(module_config_files GLOBAL PROPERTY PX4_MODULE_CONFIG_FILES)
file(GLOB jinja_templates ${PX4_SOURCE_DIR}/Tools/serial/*.jinja)
if (px4_constrained_flash_build)
if(px4_constrained_flash_build)
set(added_arguments --constrained-flash)
endif()
if(PX4_ETHERNET)

View File

@ -51,7 +51,7 @@ fi
set BOARD_ARCH_RC_DEFAULTS ${R}etc/init.d/rc.board_arch_defaults
if [ -f $BOARD_ARCH_RC_DEFAULTS ]
then
echo "Board architecture defaults: ${BOARD_ARCH_RC_DEFAULTS}"
px4log "Board architecture defaults: ${BOARD_ARCH_RC_DEFAULTS}"
. $BOARD_ARCH_RC_DEFAULTS
fi
unset BOARD_ARCH_RC_DEFAULTS
@ -62,7 +62,7 @@ unset BOARD_ARCH_RC_DEFAULTS
set BOARD_RC_DEFAULTS ${R}etc/init.d/rc.board_defaults
if [ -f $BOARD_RC_DEFAULTS ]
then
echo "Board defaults: ${BOARD_RC_DEFAULTS}"
px4log "Board defaults: ${BOARD_RC_DEFAULTS}"
. $BOARD_RC_DEFAULTS
fi
unset BOARD_RC_DEFAULTS
@ -79,7 +79,7 @@ rgbled_ncp5623c start -X -q
set BOARD_RC_SENSORS ${R}etc/init.d/rc.board_sensors
if [ -f $BOARD_RC_SENSORS ]
then
echo "Board sensors: ${BOARD_RC_SENSORS}"
px4log "Board sensors: ${BOARD_RC_SENSORS}"
. $BOARD_RC_SENSORS
fi
unset BOARD_RC_SENSORS

View File

@ -0,0 +1,8 @@
#!/bin/sh
px4log_tail &
#
# Print full system version.
#
ver all

View File

@ -31,6 +31,8 @@
#
############################################################################
px4_add_romfs_files(.nshrc)
add_subdirectory(init.d)
# TODO: make this configurable from the board config, or better combine
if("${PX4_BOARD}" MATCHES "sitl")

View File

@ -6,7 +6,7 @@ param set-default IMU_INTEG_RATE 250
if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0" ]; then
echo "INFO [init] SIH simulator"
px4log "INFO [init] SIH simulator"
if [ -n "${PX4_HOME_LAT}" ]; then
param set SIH_LOC_LAT0 ${PX4_HOME_LAT}
@ -32,7 +32,7 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
fi
else
echo "ERROR [init] simulator_sih failed to start"
px4log "ERROR [init] simulator_sih failed to start"
exit 1
fi
@ -54,7 +54,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
gz_command="gz"
gz_sub_command="sim"
else
echo "ERROR [init] Gazebo gz please install gz-garden"
px4log "ERROR [init] Gazebo gz please install gz-garden"
exit 1
fi
@ -64,7 +64,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
# shellcheck disable=SC2153
if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLDS}" ] && [ -n "${PX4_GZ_WORLD}" ]; then
echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
px4log "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
@ -74,7 +74,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
fi
else
echo "INFO [init] gazebo already running world: ${gz_world}"
px4log "INFO [init] gazebo already running world: ${gz_world}"
PX4_GZ_WORLD=${gz_world}
fi
@ -85,10 +85,10 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
if [ -n "${PX4_GZ_MODEL_POSE}" ]; then
# Clean potential input line formatting.
model_pose="$( echo "${PX4_GZ_MODEL_POSE}" | sed -e 's/^[ \t]*//; s/[ \t]*$//; s/,/ /g; s/ / /g; s/ /,/g' )"
echo "INFO [init] PX4_GZ_MODEL_POSE set, spawning at: ${model_pose}"
px4log "INFO [init] PX4_GZ_MODEL_POSE set, spawning at: ${model_pose}"
else
echo "WARN [init] PX4_GZ_MODEL_POSE not set, spawning at origin."
px4log "WARN [init] PX4_GZ_MODEL_POSE not set, spawning at origin."
model_pose="0,0,0,0,0,0"
fi
@ -112,7 +112,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
fi
else
echo "ERROR [init] gz_bridge failed to start"
px4log "ERROR [init] gz_bridge failed to start"
exit 1
fi
@ -138,13 +138,13 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
fi
else
echo "ERROR [init] gz_bridge failed to start"
px4log "ERROR [init] gz_bridge failed to start"
exit 1
fi
elif [ -n "${PX4_SIM_MODEL}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ] && [ -z "${PX4_GZ_MODEL}" ]; then
echo "WARN [init] PX4_GZ_MODEL_NAME or PX4_GZ_MODEL not set using PX4_SIM_MODEL."
px4log "WARN [init] PX4_GZ_MODEL_NAME or PX4_GZ_MODEL not set using PX4_SIM_MODEL."
if gz_bridge start -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
if param compare -s SENS_EN_BAROSIM 1
@ -165,18 +165,18 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
fi
else
echo "ERROR [init] gz_bridge failed to start"
px4log "ERROR [init] gz_bridge failed to start"
exit 1
fi
else
echo "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_GZ_MODEL"
px4log "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_GZ_MODEL"
exit 1
fi
elif [ "$PX4_SIM_MODEL" = "jmavsim_iris" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "10017" ]; then
echo "INFO [init] jMAVSim simulator"
px4log "INFO [init] jMAVSim simulator"
if jps | grep -i jmavsim; then
kill "$(jps | grep -i jmavsim | awk '{print $1}')" || true
@ -198,15 +198,15 @@ else
if [ -z "${PX4_SIM_HOSTNAME}" ]; then
if [ -z "${PX4_SIM_HOST_ADDR}" ]; then
echo "INFO [init] PX4_SIM_HOSTNAME: localhost"
px4log "INFO [init] PX4_SIM_HOSTNAME: localhost"
simulator_mavlink start -c $simulator_tcp_port
else
echo "INFO [init] PX4_SIM_HOSTNAME: ${PX4_SIM_HOST_ADDR}"
px4log "INFO [init] PX4_SIM_HOSTNAME: ${PX4_SIM_HOST_ADDR}"
simulator_mavlink start -t "${PX4_SIM_HOST_ADDR}" "${simulator_tcp_port}"
fi
else
echo "INFO [init] PX4_SIM_HOSTNAME: ${PX4_SIM_HOSTNAME}"
px4log "INFO [init] PX4_SIM_HOSTNAME: ${PX4_SIM_HOSTNAME}"
simulator_mavlink start -h "${PX4_SIM_HOSTNAME}" "${simulator_tcp_port}"
fi

View File

@ -4,12 +4,12 @@
# shellcheck disable=SC2154
if [ ! -f ${replay} ]; then
echo "Invalid replay log file ${replay}"
px4log "Invalid replay log file ${replay}"
exit 1
fi
if [ ! -f replay_params.txt ]; then
echo "Creating $(pwd)/replay_params.txt"
px4log "Creating $(pwd)/replay_params.txt"
ulog_params -i "${replay}" -l ' ' | grep -e '^EKF2' > replay_params.txt
fi

View File

@ -13,6 +13,8 @@ set +e
#search path for sourcing px4-rc.*
PATH="$PATH:${R}etc/init.d-posix"
px4log_tail &
#
# Main SITL startup script
#
@ -40,7 +42,7 @@ then
elif [ -n "$PX4_SYS_AUTOSTART" ]
then
echo "env SYS_AUTOSTART: ${PX4_SYS_AUTOSTART}"
px4log "env SYS_AUTOSTART: ${PX4_SYS_AUTOSTART}"
SYS_AUTOSTART=${PX4_SYS_AUTOSTART}
elif [ "$PX4_SIM_MODEL" = "none" ] || [ -z $PX4_SIM_MODEL ]
@ -55,11 +57,11 @@ then
# shellcheck disable=SC2012
REQUESTED_AUTOSTART=$(ls "${R}etc/init.d-posix/airframes" | sed -n 's/^\([0-9][0-9]*\)_'${PX4_SIM_MODEL}'$/\1/p')
if [ -z "$REQUESTED_AUTOSTART" ]; then
echo "ERROR [init] Unknown model $PX4_SIM_MODEL (not found by name on ${R}etc/init.d-posix/airframes)"
px4log "ERROR [init] Unknown model $PX4_SIM_MODEL (not found by name on ${R}etc/init.d-posix/airframes)"
exit 1
else
SYS_AUTOSTART=$REQUESTED_AUTOSTART
echo "INFO [init] found model autostart file as SYS_AUTOSTART=$REQUESTED_AUTOSTART"
px4log "INFO [init] found model autostart file as SYS_AUTOSTART=$REQUESTED_AUTOSTART"
fi
fi
@ -72,7 +74,7 @@ if [ -f $PARAM_FILE ]; then
if ! param import
then
echo "ERROR [init] param import failed"
px4log "ERROR [init] param import failed"
bsondump $PARAM_FILE
@ -82,7 +84,7 @@ if [ -f $PARAM_FILE ]; then
# try importing from backup file
if [ -f $PARAM_BACKUP_FILE ]
then
echo "[init] importing from parameter backup"
px4log "[init] importing from parameter backup"
# dump current backup file contents for comparison
bsondump $PARAM_BACKUP_FILE
@ -97,7 +99,7 @@ if [ -f $PARAM_FILE ]; then
fi
elif [ -f $PARAM_BACKUP_FILE ]; then
echo "ERROR [init] primary param file $PARAM_FILE unavailable, using backup $PARAM_BACKUP_FILE"
px4log "ERROR [init] primary param file $PARAM_FILE unavailable, using backup $PARAM_BACKUP_FILE"
param import $PARAM_BACKUP_FILE
fi
@ -191,19 +193,19 @@ param set-default COM_LOW_BAT_ACT 2
# Adapt timeout parameters if simulation runs faster or slower than realtime.
if [ -n "$PX4_SIM_SPEED_FACTOR" ]; then
COM_DL_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 10" | bc)
echo "COM_DL_LOSS_T set to $COM_DL_LOSS_T_LONGER"
px4log "COM_DL_LOSS_T set to $COM_DL_LOSS_T_LONGER"
param set COM_DL_LOSS_T $COM_DL_LOSS_T_LONGER
COM_RC_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 0.5" | bc)
echo "COM_RC_LOSS_T set to $COM_RC_LOSS_T_LONGER"
px4log "COM_RC_LOSS_T set to $COM_RC_LOSS_T_LONGER"
param set COM_RC_LOSS_T $COM_RC_LOSS_T_LONGER
COM_OF_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 0.5" | bc)
echo "COM_OF_LOSS_T set to $COM_OF_LOSS_T_LONGER"
px4log "COM_OF_LOSS_T set to $COM_OF_LOSS_T_LONGER"
param set COM_OF_LOSS_T $COM_OF_LOSS_T_LONGER
COM_OBC_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 5.0" | bc)
echo "COM_OBC_LOSS_T set to $COM_OBC_LOSS_T_LONGER"
px4log "COM_OBC_LOSS_T set to $COM_OBC_LOSS_T_LONGER"
param set COM_OBC_LOSS_T $COM_OBC_LOSS_T_LONGER
fi
@ -229,7 +231,7 @@ then
elif [ ! -e "$autostart_file" ] && [ "$SYS_AUTOSTART" -ne "0" ]
then
echo "Error: no autostart file found ($autostart_file)"
px4log "Error: no autostart file found ($autostart_file)"
exit 1
fi

View File

@ -46,6 +46,7 @@ px4_add_romfs_files(
rc.logging
rc.mc_apps
rc.mc_defaults
rc.sysinit
rcS
rc.sensors
rc.thermal_cal

View File

@ -20,10 +20,10 @@ then
#
if attitude_estimator_q start
then
echo "WARN [init] Estimator LPE unsupported, EKF2 recommended."
px4log "WARN [init] Estimator LPE unsupported, EKF2 recommended."
local_position_estimator start
else
echo "ERROR [init] Estimator LPE not available. Using EKF2"
px4log "ERROR [init] Estimator LPE not available. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
reboot

View File

@ -7,5 +7,5 @@ if [ -e ${SDCARD_EXT_PATH}/rc.autostart ]
then
. ${SDCARD_EXT_PATH}/rc.autostart
else
echo "Error: ${SDCARD_EXT_PATH}/rc.autostart does not exist"
px4log "Error: ${SDCARD_EXT_PATH}/rc.autostart does not exist"
fi

View File

@ -17,10 +17,10 @@ then
#
if attitude_estimator_q start
then
echo "WARN [init] Estimator LPE unsupported, EKF2 recommended."
px4log "WARN [init] Estimator LPE unsupported, EKF2 recommended."
local_position_estimator start
else
echo "ERROR [init] Estimator LPE not available. Using EKF2"
px4log "ERROR [init] Estimator LPE not available. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
reboot

View File

@ -20,10 +20,10 @@ then
#
if attitude_estimator_q start
then
echo "WARN [init] Estimator LPE unsupported, EKF2 recommended."
px4log "WARN [init] Estimator LPE unsupported, EKF2 recommended."
local_position_estimator start
else
echo "ERROR [init] Estimator LPE not available. Using EKF2"
px4log "ERROR [init] Estimator LPE not available. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
reboot

View File

@ -0,0 +1,3 @@
#!/bin/sh
# Un comment and use set +e to ignore and set -e to enable 'exit on error control'
set +e

View File

@ -66,6 +66,6 @@ fi
#
if [ $VEHICLE_TYPE = none ]
then
echo "No autostart ID found"
px4log "No autostart ID found"
ekf2 start &
fi

View File

@ -36,11 +36,6 @@ set SDCARD_FORMAT no
set STARTUP_TUNE 1
set VEHICLE_TYPE none
#
# Print full system version.
#
ver all
#
# Try to mount the microSD card.
#
@ -50,7 +45,7 @@ then
then
if [ -f "/fs/microsd/.format" ]
then
echo "INFO [init] format /dev/mmcsd0 requested (/fs/microsd/.format)"
px4log "INFO [init] format /dev/mmcsd0 requested (/fs/microsd/.format)"
set SDCARD_FORMAT yes
rm /fs/microsd/.format
umount /fs/microsd
@ -62,22 +57,22 @@ then
if [ $SDCARD_AVAILABLE = no -o $SDCARD_FORMAT = yes ]
then
echo "INFO [init] formatting /dev/mmcsd0"
px4log "INFO [init] formatting /dev/mmcsd0"
set STARTUP_TUNE 15 # tune 15 = SD_ERROR (overridden to SD_INIT if format + mount succeeds)
if mkfatfs -F 32 /dev/mmcsd0
then
echo "INFO [init] card formatted"
px4log "INFO [init] card formatted"
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
set SDCARD_AVAILABLE yes
set STARTUP_TUNE 14 # tune 14 = SD_INIT
else
echo "ERROR [init] card mount failed"
px4log "ERROR [init] card mount failed"
fi
else
echo "ERROR [init] format failed"
px4log "ERROR [init] format failed"
fi
fi
@ -127,7 +122,7 @@ else
param select $PARAM_FILE
if ! param import
then
echo "ERROR [init] param import failed"
px4log "ERROR [init] param import failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
bsondump $PARAM_FILE
@ -140,7 +135,7 @@ else
# try importing from backup file
if [ -f $PARAM_BACKUP_FILE ]
then
echo "[init] importing from parameter backup"
px4log "[init] importing from parameter backup"
# dump current backup file contents for comparison
bsondump $PARAM_BACKUP_FILE
@ -182,7 +177,7 @@ else
set BOARD_ARCH_RC_DEFAULTS ${R}etc/init.d/rc.board_arch_defaults
if [ -f $BOARD_ARCH_RC_DEFAULTS ]
then
echo "Board architecture defaults: ${BOARD_ARCH_RC_DEFAULTS}"
px4log "Board architecture defaults: ${BOARD_ARCH_RC_DEFAULTS}"
. $BOARD_ARCH_RC_DEFAULTS
fi
unset BOARD_ARCH_RC_DEFAULTS
@ -193,7 +188,7 @@ else
set BOARD_RC_DEFAULTS ${R}etc/init.d/rc.board_defaults
if [ -f $BOARD_RC_DEFAULTS ]
then
echo "Board defaults: ${BOARD_RC_DEFAULTS}"
px4log "Board defaults: ${BOARD_RC_DEFAULTS}"
. $BOARD_RC_DEFAULTS
fi
unset BOARD_RC_DEFAULTS
@ -211,7 +206,7 @@ else
then
set AUTOSTART_PATH etc/init.d/rc.autostart_ext
else
echo "ERROR [init] SD card not mounted - trying to load airframe from ROMFS"
px4log "ERROR [init] SD card not mounted - trying to load airframe from ROMFS"
fi
fi
. ${R}$AUTOSTART_PATH
@ -260,7 +255,7 @@ else
#
if [ -f $FCONFIG ]
then
echo "Custom: ${FCONFIG}"
px4log "Custom: ${FCONFIG}"
. $FCONFIG
fi
@ -295,7 +290,7 @@ else
if ! px4io start
then
echo "PX4IO start failed"
px4log "PX4IO start failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
fi
fi
@ -360,7 +355,7 @@ else
set BOARD_RC_SENSORS ${R}etc/init.d/rc.board_sensors
if [ -f $BOARD_RC_SENSORS ]
then
echo "Board sensors: ${BOARD_RC_SENSORS}"
px4log "Board sensors: ${BOARD_RC_SENSORS}"
. $BOARD_RC_SENSORS
fi
unset BOARD_RC_SENSORS
@ -401,7 +396,7 @@ else
set BOARD_RC_MAVLINK ${R}etc/init.d/rc.board_mavlink
if [ -f $BOARD_RC_MAVLINK ]
then
echo "Board mavlink: ${BOARD_RC_MAVLINK}"
px4log "Board mavlink: ${BOARD_RC_MAVLINK}"
. $BOARD_RC_MAVLINK
fi
unset BOARD_RC_MAVLINK
@ -476,7 +471,7 @@ else
set BOARD_RC_EXTRAS ${R}etc/init.d/rc.board_extras
if [ -f $BOARD_RC_EXTRAS ]
then
echo "Board extras: ${BOARD_RC_EXTRAS}"
px4log "Board extras: ${BOARD_RC_EXTRAS}"
. $BOARD_RC_EXTRAS
fi
unset BOARD_RC_EXTRAS
@ -486,7 +481,7 @@ else
#
if [ -f $FEXTRAS ]
then
echo "Addons script: ${FEXTRAS}"
px4log "Addons script: ${FEXTRAS}"
. $FEXTRAS
fi

View File

@ -19,11 +19,11 @@ fi
mount -t vfat /dev/mmcsd0 /fs/microsd
if [ $? = 0 ]
then
echo "[i] card mounted at /fs/microsd"
px4log "[i] card mounted at /fs/microsd"
# Start playing the startup tune
tune_control play -t 1 # tune 1 = STARTUP
else
echo "[i] no microSD card found"
px4log "[i] no microSD card found"
tune_control play error
fi
@ -43,9 +43,9 @@ fi
param select $PARAM_FILE
if param load
then
echo "[param] Loaded: $PARAM_FILE"
px4log "[param] Loaded: $PARAM_FILE"
else
echo "[param] FAILED loading $PARAM_FILE"
px4log "[param] FAILED loading $PARAM_FILE"
fi
#
@ -53,7 +53,7 @@ fi
#
if [ -f $BOARD_RC ]
then
echo "Board init: ${BOARD_RC}"
px4log "Board init: ${BOARD_RC}"
. $BOARD_RC
fi
@ -64,24 +64,24 @@ fi
if px4io checkcrc $io_file
then
echo "PX4IO CRC OK"
px4log "PX4IO CRC OK"
else
echo "PX4IO CRC failure"
px4log "PX4IO CRC failure"
tune_control play -t 16 # tune 16 = PROG_PX4IO
if px4io update $io_file
then
if px4io start
then
echo "PX4IO restart OK"
px4log "PX4IO restart OK"
tune_control play-t 17 # tune 17 = PROG_PX4IO_OK
else
echo "PX4IO restart failed"
px4log "PX4IO restart failed"
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
set unit_test_failure 1
set unit_test_failure_list "${unit_test_failure_list} px4io_flash"
fi
else
echo "PX4IO update failed"
px4log "PX4IO update failed"
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
set unit_test_failure 1
set unit_test_failure_list "${unit_test_failure_list} px4io_flash"
@ -90,7 +90,7 @@ fi
if px4io start
then
echo "PX4IO OK"
px4log "PX4IO OK"
else
set unit_test_failure 1
set unit_test_failure_list "${unit_test_failure_list} px4io_start"
@ -117,11 +117,11 @@ ver all
if tests all
then
echo
echo "All Unit Tests PASSED"
px4log "All Unit Tests PASSED"
led_control on -c green
else
echo
echo "Some Unit Tests FAILED"
px4log "Some Unit Tests FAILED"
led_control on -c red
fi

View File

@ -77,11 +77,11 @@ class RCOutput():
result += "\n"
result += "if [ ${AIRFRAME} != none ]\n"
result += "then\n"
result += "\techo \"Loading airframe: /etc/init.d/airframes/${AIRFRAME}\"\n"
result += "\tpx4log \"Loading airframe: /etc/init.d/airframes/${AIRFRAME}\"\n"
result += "\t. /etc/init.d/airframes/${AIRFRAME}\n"
if not post_start:
result += "else\n"
result += "\techo \"ERROR [init] No file matches SYS_AUTOSTART value found in : /etc/init.d/airframes\"\n"
result += "\tpx4log \"ERROR [init] No file matches SYS_AUTOSTART value found in : /etc/init.d/airframes\"\n"
# Reset the configuration
result += "\tparam set SYS_AUTOSTART 0\n"
result += "\ttone_alarm ${TUNE_ERR}\n"

View File

@ -69,7 +69,7 @@ def main():
file_path = os.path.join(root, file)
# delete hidden files
if file.startswith("."):
if file.startswith(".") and not ".nshrc" in file:
os.remove(file_path)
continue

View File

@ -14,7 +14,7 @@ set i {{ command.instance }}
. $PRT_F
if [ $SERIAL_DEV != none ]; then
{% if not constrained_flash -%}
echo "Starting {{ command.label }} on $SERIAL_DEV"
px4log "Starting {{ command.label }} on $SERIAL_DEV"
{% endif -%}
{{ command.command }}
fi

View File

@ -11,7 +11,7 @@ if param compare "$PRT" {{ serial_device.index }}; then
set PRT_{{ serial_device.tag }}_ 1
{% if not constrained_flash -%}
else
echo "Conflicting config for {{ serial_device.device }}"
px4log "Conflicting config for {{ serial_device.device }}"
{% endif -%}
fi
fi

View File

@ -86,6 +86,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y

View File

@ -132,6 +132,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -24,6 +24,8 @@ CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_MAGNETOMETER is not set
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y

View File

@ -107,6 +107,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -28,6 +28,8 @@ CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -109,6 +109,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -29,6 +29,8 @@ CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -109,6 +109,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -44,6 +44,8 @@ CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y

View File

@ -109,6 +109,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -78,6 +78,8 @@ CONFIG_SYSTEMCMDS_NETMAN=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y

View File

@ -178,6 +178,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_TELNET=y

View File

@ -489,7 +489,6 @@
GPIO_SPIX_SYNC \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_I2C_BUS_MTD 4,5

View File

@ -40,6 +40,8 @@ CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y

View File

@ -138,6 +138,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -191,7 +191,6 @@
GPIO_OTGFS_VBUS \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 1

View File

@ -83,6 +83,8 @@ CONFIG_SYSTEMCMDS_NETMAN=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y

View File

@ -167,6 +167,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_TELNET=y

View File

@ -146,7 +146,6 @@
GPIO_CAN1_TX, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 6

View File

@ -66,6 +66,8 @@ CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y

View File

@ -38,6 +38,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -130,6 +130,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -155,8 +155,7 @@
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*3)
__BEGIN_DECLS

View File

@ -37,6 +37,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y

View File

@ -131,6 +131,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -156,8 +156,7 @@
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*3)
__BEGIN_DECLS

View File

@ -27,6 +27,8 @@ CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -111,6 +111,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -87,6 +87,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -138,6 +138,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -200,7 +200,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \

View File

@ -88,6 +88,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y

View File

@ -138,6 +138,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -138,6 +138,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -200,7 +200,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \

View File

@ -80,6 +80,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -139,6 +139,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -139,6 +139,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -150,7 +150,6 @@
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \

View File

@ -80,6 +80,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -139,6 +139,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -139,6 +139,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -160,7 +160,6 @@
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \

View File

@ -87,6 +87,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y

View File

@ -138,6 +138,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -145,7 +145,6 @@
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \

View File

@ -40,5 +40,7 @@ CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_VER=y

View File

@ -97,6 +97,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=2
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_READLINE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -154,9 +154,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*2)
__BEGIN_DECLS

View File

@ -68,6 +68,8 @@ CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y

View File

@ -32,6 +32,8 @@ CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y

View File

@ -130,6 +130,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=2
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -156,8 +156,7 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*3)
__BEGIN_DECLS

View File

@ -30,6 +30,8 @@ CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -123,6 +123,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -57,7 +57,6 @@
#define HRT_TIMER 2 /* use timer 2 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
#define BOARD_ENABLE_CONSOLE_BUFFER
__BEGIN_DECLS

View File

@ -28,6 +28,8 @@ CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -112,6 +112,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -79,6 +79,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y

View File

@ -140,6 +140,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -320,7 +320,6 @@
GPIO_SAFETY_SWITCH_IN, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
__BEGIN_DECLS

View File

@ -34,3 +34,5 @@ CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y

View File

@ -141,6 +141,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -76,6 +76,8 @@ CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y

View File

@ -140,6 +140,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -180,7 +180,6 @@
GPIO_RF_SWITCH, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define FLASH_BASED_PARAMS

View File

@ -73,6 +73,8 @@ CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y

View File

@ -139,6 +139,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -184,7 +184,6 @@
GPIO_VTX_ON, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define FLASH_BASED_PARAMS

View File

@ -75,6 +75,8 @@ CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y

View File

@ -139,6 +139,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=1
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -183,7 +183,6 @@
GPIO_VTX_ON, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define FLASH_BASED_PARAMS

View File

@ -91,6 +91,8 @@ CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y

View File

@ -138,6 +138,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -428,7 +428,6 @@
GPIO_nARMED_INIT \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 5

View File

@ -30,6 +30,8 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SERIAL_PASSTHRU=y
CONFIG_SERIAL_PASSTHRU_UBLOX=y

View File

@ -129,6 +129,7 @@ CONFIG_NSH_MMCSDSPIPORTNO=3
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

View File

@ -83,7 +83,6 @@
#define HRT_TIMER 3 /* use timer 3 as HRT */
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
#define BOARD_ENABLE_CONSOLE_BUFFER
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120

View File

@ -58,6 +58,8 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PX4LOG=y
CONFIG_SYSTEMCMDS_PX4LOG_TAIL=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y

View File

@ -133,6 +133,7 @@ CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSRC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y

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