mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-25 04:27:35 +08:00
Compare commits
2 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 5e64e9e08e | |||
| 984467b83b |
@@ -88,6 +88,7 @@ pipeline {
|
||||
"nxp_fmuk66-e_socketcan",
|
||||
"nxp_fmuk66-v3_default",
|
||||
"nxp_fmuk66-v3_socketcan",
|
||||
"nxp_fmurt1062-v1_default",
|
||||
"nxp_mr-canhubk3_default",
|
||||
"nxp_ucans32k146_canbootloader",
|
||||
"nxp_ucans32k146_default",
|
||||
@@ -110,16 +111,13 @@ pipeline {
|
||||
"px4_fmu-v6c_default",
|
||||
"px4_fmu-v6u_default",
|
||||
"px4_fmu-v6x_default",
|
||||
"px4_fmu-v6xrt_bootloader",
|
||||
"px4_fmu-v6xrt_default",
|
||||
"px4_io-v2_default",
|
||||
"raspberrypi_pico_default",
|
||||
"sky-drones_smartap-airlink_default",
|
||||
"spracing_h7extreme_default",
|
||||
"thepeach_k1_default",
|
||||
"thepeach_r1_default",
|
||||
"uvify_core_default",
|
||||
"siyi_n7_default"
|
||||
"uvify_core_default"
|
||||
],
|
||||
image: docker_images.nuttx,
|
||||
archive: true
|
||||
|
||||
@@ -29,8 +29,7 @@
|
||||
"twxs.cmake",
|
||||
"uavcan.dsdl",
|
||||
"wholroyd.jinja",
|
||||
"zixuanwang.linkerscript",
|
||||
"ms-vscode.makefile-tools"
|
||||
"zixuanwang.linkerscript"
|
||||
],
|
||||
|
||||
"containerUser": "user",
|
||||
|
||||
@@ -18,11 +18,6 @@ jobs:
|
||||
px4_sitl
|
||||
]
|
||||
steps:
|
||||
- name: install Python 3.10
|
||||
uses: actions/setup-python@v4
|
||||
with:
|
||||
python-version: "3.10"
|
||||
|
||||
- uses: actions/checkout@v1
|
||||
with:
|
||||
token: ${{secrets.ACCESS_TOKEN}}
|
||||
|
||||
@@ -57,6 +57,7 @@ jobs:
|
||||
mro_x21-777,
|
||||
nxp_fmuk66-e,
|
||||
nxp_fmuk66-v3,
|
||||
nxp_fmurt1062-v1,
|
||||
nxp_mr-canhubk3,
|
||||
nxp_ucans32k146,
|
||||
omnibus_f4sd,
|
||||
@@ -69,12 +70,10 @@ jobs:
|
||||
px4_fmu-v6c,
|
||||
px4_fmu-v6u,
|
||||
px4_fmu-v6x,
|
||||
px4_fmu-v6xrt,
|
||||
raspberrypi_pico,
|
||||
sky-drones_smartap-airlink,
|
||||
spracing_h7extreme,
|
||||
uvify_core,
|
||||
siyi_n7
|
||||
uvify_core
|
||||
]
|
||||
steps:
|
||||
- uses: actions/checkout@v1
|
||||
|
||||
@@ -128,6 +128,4 @@ jobs:
|
||||
run: |
|
||||
git clone https://github.com/PX4/px4_msgs.git
|
||||
rm px4_msgs/msg/*.msg
|
||||
rm px4_msgs/srv/*.srv
|
||||
cp msg/*.msg px4_msgs/msg/
|
||||
cp srv/*.srv px4_msgs/srv/
|
||||
|
||||
@@ -1,32 +0,0 @@
|
||||
name: Nuttx Target with extra env config
|
||||
|
||||
on:
|
||||
push:
|
||||
branches:
|
||||
- 'main'
|
||||
pull_request:
|
||||
branches:
|
||||
- '*'
|
||||
|
||||
jobs:
|
||||
build:
|
||||
runs-on: ubuntu-latest
|
||||
container: px4io/px4-dev-nuttx-focal:2022-08-12
|
||||
strategy:
|
||||
matrix:
|
||||
config: [
|
||||
px4_fmu-v5,
|
||||
]
|
||||
steps:
|
||||
- uses: actions/checkout@v1
|
||||
with:
|
||||
token: ${{secrets.ACCESS_TOKEN}}
|
||||
|
||||
- name: make ${{matrix.config}}
|
||||
env:
|
||||
PX4_EXTRA_NUTTX_CONFIG: "CONFIG_NSH_LOGIN_PASSWORD=\"test\";CONFIG_NSH_CONSOLE_LOGIN=y"
|
||||
run: |
|
||||
echo "PX4_EXTRA_NUTTX_CONFIG: $PX4_EXTRA_NUTTX_CONFIG"
|
||||
make ${{matrix.config}} nuttx_context
|
||||
# Check that the config option is set
|
||||
grep CONFIG_NSH_LOGIN_PASSWORD build/${{matrix.config}}_default/NuttX/nuttx/.config
|
||||
-14
@@ -62,17 +62,3 @@
|
||||
path = src/modules/uxrce_dds_client/Micro-XRCE-DDS-Client
|
||||
url = https://github.com/PX4/Micro-XRCE-DDS-Client.git
|
||||
branch = px4
|
||||
[submodule "src/lib/cdrstream/cyclonedds"]
|
||||
path = src/lib/cdrstream/cyclonedds
|
||||
url = https://github.com/px4/cyclonedds
|
||||
[submodule "src/lib/cdrstream/rosidl"]
|
||||
path = src/lib/cdrstream/rosidl
|
||||
url = https://github.com/px4/rosidl
|
||||
[submodule "src/modules/zenoh/zenoh-pico"]
|
||||
path = src/modules/zenoh/zenoh-pico
|
||||
url = https://github.com/px4/zenoh-pico
|
||||
branch = pr-zubf-werror-fix
|
||||
[submodule "src/lib/heatshrink/heatshrink"]
|
||||
path = src/lib/heatshrink/heatshrink
|
||||
url = https://github.com/PX4/heatshrink.git
|
||||
branch = px4
|
||||
|
||||
Vendored
-15
@@ -81,16 +81,6 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: px4_fmu-v6x_bootloader
|
||||
px4_fmu-v6xrt_default:
|
||||
short: px4_fmu-v6xrt
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: px4_fmu-v6xrt_default
|
||||
px4_fmu-v6xrt_bootloader:
|
||||
short: px4_fmu-v6xrt_bootloader
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: px4_fmu-v6xrt_bootloader
|
||||
airmind_mindpx-v2_default:
|
||||
short: airmind_mindpx-v2
|
||||
buildType: MinSizeRel
|
||||
@@ -191,11 +181,6 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: cubepilot_cubeorange_test
|
||||
cubepilot_cubeorangeplus_test:
|
||||
short: cubepilot_cubeorangeplus
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: cubepilot_cubeorangeplus_test
|
||||
emlid_navio2_default:
|
||||
short: emlid_navio2
|
||||
buildType: MinSizeRel
|
||||
|
||||
Vendored
+1
-2
@@ -18,7 +18,6 @@
|
||||
"twxs.cmake",
|
||||
"uavcan.dsdl",
|
||||
"wholroyd.jinja",
|
||||
"zixuanwang.linkerscript",
|
||||
"ms-vscode.makefile-tools"
|
||||
"zixuanwang.linkerscript"
|
||||
]
|
||||
}
|
||||
|
||||
Vendored
+1
-2
@@ -127,6 +127,5 @@
|
||||
"terminal.integrated.scrollback": 15000,
|
||||
"yaml.schemas": {
|
||||
"${workspaceFolder}/validation/module_schema.yaml": "${workspaceFolder}/src/modules/*/module.yaml"
|
||||
},
|
||||
"ros.distro": "humble"
|
||||
}
|
||||
}
|
||||
|
||||
@@ -414,8 +414,6 @@ endif()
|
||||
#
|
||||
add_library(parameters_interface INTERFACE)
|
||||
add_library(kernel_parameters_interface INTERFACE)
|
||||
add_library(events_interface INTERFACE)
|
||||
add_library(kernel_events_interface INTERFACE)
|
||||
|
||||
include(px4_add_library)
|
||||
add_subdirectory(src/lib EXCLUDE_FROM_ALL)
|
||||
@@ -442,11 +440,8 @@ add_subdirectory(src/lib/parameters EXCLUDE_FROM_ALL)
|
||||
if(${PX4_PLATFORM} STREQUAL "nuttx" AND NOT CONFIG_BUILD_FLAT)
|
||||
target_link_libraries(parameters_interface INTERFACE usr_parameters)
|
||||
target_link_libraries(kernel_parameters_interface INTERFACE parameters)
|
||||
target_link_libraries(events_interface INTERFACE usr_events)
|
||||
target_link_libraries(kernel_events_interface INTERFACE events)
|
||||
else()
|
||||
target_link_libraries(parameters_interface INTERFACE parameters)
|
||||
target_link_libraries(events_interface INTERFACE events)
|
||||
endif()
|
||||
|
||||
# firmware added last to generate the builtin for included modules
|
||||
|
||||
Vendored
-3
@@ -105,7 +105,6 @@ pipeline {
|
||||
./emsdk activate latest;
|
||||
cd ..;
|
||||
. ./_emscripten_sdk/emsdk_env.sh;
|
||||
git fetch --all --tags;
|
||||
make failsafe_web;
|
||||
cd build/px4_sitl_default_failsafe_web;
|
||||
mkdir -p failsafe_sim;
|
||||
@@ -231,9 +230,7 @@ pipeline {
|
||||
sh("git clone https://${GIT_USER}:${GIT_PASS}@github.com/PX4/px4_msgs.git")
|
||||
// 'main' branch
|
||||
sh('rm -f px4_msgs/msg/*.msg')
|
||||
sh('rm -f px4_msgs/srv/*.srv')
|
||||
sh('cp msg/*.msg px4_msgs/msg/')
|
||||
sh('cp srv/*.srv px4_msgs/srv/')
|
||||
sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true')
|
||||
sh('cd px4_msgs; git push origin main || true')
|
||||
sh('rm -rf px4_msgs')
|
||||
|
||||
@@ -205,5 +205,3 @@ menu "platforms"
|
||||
depends on PLATFORM_QURT || PLATFORM_POSIX
|
||||
source "platforms/common/Kconfig"
|
||||
endmenu
|
||||
|
||||
source "src/lib/*/Kconfig"
|
||||
|
||||
@@ -266,6 +266,7 @@ px4fmu_firmware: \
|
||||
|
||||
misc_qgc_extra_firmware: \
|
||||
check_nxp_fmuk66-v3_default \
|
||||
check_nxp_fmurt1062-v1_default \
|
||||
check_mro_x21_default \
|
||||
check_bitcraze_crazyflie_default \
|
||||
check_bitcraze_crazyflie21_default \
|
||||
@@ -483,9 +484,7 @@ validate_module_configs:
|
||||
@find "$(SRC_DIR)"/src/modules "$(SRC_DIR)"/src/drivers "$(SRC_DIR)"/src/lib -name *.yaml -type f \
|
||||
-not -path "$(SRC_DIR)/src/lib/mixer_module/*" \
|
||||
-not -path "$(SRC_DIR)/src/modules/uxrce_dds_client/dds_topics.yaml" \
|
||||
-not -path "$(SRC_DIR)/src/modules/zenoh/zenoh-pico/*" \
|
||||
-not -path "$(SRC_DIR)/src/lib/events/libevents/*" \
|
||||
-not -path "$(SRC_DIR)/src/lib/cdrstream/*" \
|
||||
-not -path "$(SRC_DIR)/src/lib/crypto/libtommath/*" -print0 | \
|
||||
xargs -0 "$(SRC_DIR)"/Tools/validate_yaml.py --schema-file "$(SRC_DIR)"/validation/module_schema.yaml
|
||||
|
||||
|
||||
@@ -114,7 +114,7 @@ These boards are maintained to be compatible with PX4-Autopilot by the Manufactu
|
||||
|
||||
### Community supported
|
||||
|
||||
These boards don't fully comply industry standards, and thus is solely maintained by the PX4 public community members.
|
||||
These boards don't fully comply industry standards, and thus is solely maintained by the PX4 publc community members.
|
||||
|
||||
### Experimental
|
||||
|
||||
|
||||
@@ -31,7 +31,6 @@ param set-default PWM_MAIN_FUNC4 104
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
param set-default EKF2_HGT_REF 0
|
||||
param set-default EKF2_EVP_NOISE 0.05
|
||||
param set-default EKF2_EVA_NOISE 0.05
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
@@ -40,9 +39,6 @@ param set-default EKF2_OF_CTRL 1
|
||||
param set-default LPE_FUSION 242
|
||||
param set-default LPE_FAKE_ORIGIN 1
|
||||
|
||||
# Commander
|
||||
# param set-default COM_HOME_EN 0 # Disable setting of home position
|
||||
|
||||
param set-default MPC_ALT_MODE 2
|
||||
|
||||
param set-default SENS_FLOW_ROT 6
|
||||
|
||||
@@ -1,8 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor with a depth camera (forward-facing)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10015_gazebo-classic_iris
|
||||
-8
@@ -1,8 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name 3DR Iris Quadrotor with a depth camera (downward-facing)
|
||||
#
|
||||
# @type Quadrotor Wide
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/10015_gazebo-classic_iris
|
||||
@@ -7,7 +7,6 @@
|
||||
|
||||
param set-default FW_LAUN_DETCN_ON 1
|
||||
param set-default FW_THR_IDLE 0.1 # needs to be running before throw as that's how gazebo detects arming
|
||||
param set-default FW_LAUN_AC_THLD 10
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
|
||||
|
||||
@@ -8,6 +8,7 @@
|
||||
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
param set-default FW_THR_LND_MAX 0
|
||||
|
||||
param set-default NPFG_PERIOD 12
|
||||
|
||||
@@ -35,6 +36,7 @@ param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
#param set-default SYS_CTRL_ALLOC 1
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
@@ -59,3 +61,7 @@ param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
param set-default PWM_MAIN_FUNC9 206
|
||||
param set-default PWM_MAIN_REV 256
|
||||
|
||||
|
||||
set MIXER_FILE etc/mixers-sitl/plane_sitl.main.mix
|
||||
set MIXER custom
|
||||
|
||||
@@ -47,8 +47,6 @@ param set-default PWM_MAIN_FUNC6 201
|
||||
param set-default PWM_MAIN_FUNC7 202
|
||||
param set-default PWM_MAIN_FUNC8 203
|
||||
|
||||
param set-default FW_AIRSPD_MAX 25
|
||||
param set-default FW_THR_ASPD_MAX 0.4
|
||||
param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_FF 0.2
|
||||
param set-default FW_PR_P 0.9
|
||||
@@ -64,18 +62,19 @@ param set-default FW_T_SINK_MAX 2.7
|
||||
param set-default FW_T_SINK_MIN 2.2
|
||||
|
||||
param set-default MC_AIRMODE 1
|
||||
param set-default MC_ROLL_P 4
|
||||
param set-default MC_ROLLRATE_P 0.3
|
||||
param set-default MC_YAW_P 1.6
|
||||
param set-default MC_YAWRATE_P 0.3
|
||||
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 10
|
||||
|
||||
param set-default MPC_XY_P 0.8
|
||||
param set-default MPC_XY_VEL_P_ACC 3
|
||||
param set-default MPC_XY_VEL_I_ACC 4
|
||||
param set-default MPC_XY_VEL_D_ACC 0.1
|
||||
|
||||
param set-default NAV_ACC_RAD 5
|
||||
|
||||
param set-default VT_FWD_THRUST_EN 4
|
||||
param set-default VT_FWD_THRUST_SC 1
|
||||
param set-default VT_F_TRANS_THR 0.75
|
||||
param set-default VT_TYPE 2
|
||||
|
||||
|
||||
@@ -76,7 +76,7 @@ param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
|
||||
param set-default NPFG_PERIOD 12
|
||||
param set-default FW_L1_PERIOD 12
|
||||
param set-default FW_PR_FF 0.2
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PSP_OFF 2
|
||||
|
||||
@@ -52,8 +52,12 @@ param set-default MAV_1_MODE 9
|
||||
# param set-default SER_TEL1_BAUD 921600 Not found
|
||||
|
||||
# Vehicle attitude PID tuning
|
||||
param set-default MC_ACRO_EXPO 0
|
||||
param set-default MC_ACRO_EXPO_Y 0
|
||||
param set-default MC_ACRO_P_MAX 200
|
||||
param set-default MC_ACRO_R_MAX 200
|
||||
param set-default MC_ACRO_SUPEXPO 0
|
||||
param set-default MC_ACRO_SUPEXPOY 0
|
||||
param set-default MC_ACRO_Y_MAX 150
|
||||
param set-default MC_PITCHRATE_D 0.0015
|
||||
param set-default MC_ROLLRATE_D 0.0015
|
||||
|
||||
@@ -1,82 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Advanced Plane SITL
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
|
||||
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
|
||||
PX4_SIM_MODEL=${PX4_SIM_MODEL:=advanced_plane}
|
||||
|
||||
param set-default SIM_GZ_EN 1
|
||||
|
||||
param set-default SENS_EN_GPSSIM 1
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
param set-default SENS_EN_ARSPDSIM 1
|
||||
|
||||
param set-default FW_LND_ANG 8
|
||||
param set-default NPFG_PERIOD 12
|
||||
|
||||
param set-default FW_MAN_P_MAX 30
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MAX 32
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
param set-default FW_RR_FF 0.5
|
||||
param set-default FW_RR_P 0.3
|
||||
param set-default FW_RR_I 0.5
|
||||
|
||||
param set-default FW_YR_FF 0.5
|
||||
param set-default FW_YR_P 0.6
|
||||
param set-default FW_YR_I 0.5
|
||||
|
||||
param set-default FW_SPOILERS_LND 0.4
|
||||
|
||||
param set-default FW_THR_MIN 0.05
|
||||
param set-default FW_THR_TRIM 0.25
|
||||
|
||||
param set-default FW_T_CLMB_MAX 8
|
||||
param set-default FW_T_SINK_MAX 2.7
|
||||
param set-default FW_T_SINK_MIN 2.2
|
||||
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 30
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
param set-default CA_AIRFRAME 1
|
||||
|
||||
param set-default CA_ROTOR_COUNT 1
|
||||
param set-default CA_ROTOR0_PX 0.3
|
||||
|
||||
param set-default CA_SV_CS_COUNT 6
|
||||
param set-default CA_SV_CS0_TRQ_R -0.5
|
||||
param set-default CA_SV_CS0_TYPE 1
|
||||
param set-default CA_SV_CS1_TRQ_R 0.5
|
||||
param set-default CA_SV_CS1_TYPE 2
|
||||
param set-default CA_SV_CS2_TRQ_P 1.0
|
||||
param set-default CA_SV_CS2_TYPE 3
|
||||
param set-default CA_SV_CS3_TRQ_Y 1.0
|
||||
param set-default CA_SV_CS3_TYPE 4
|
||||
param set-default CA_SV_CS4_TYPE 9
|
||||
param set-default CA_SV_CS5_TYPE 10
|
||||
|
||||
param set-default SIM_GZ_EC_FUNC1 101
|
||||
param set-default SIM_GZ_EC_MIN1 10
|
||||
param set-default SIM_GZ_EC_MAX1 1600
|
||||
|
||||
param set-default SIM_GZ_SV_FUNC1 201
|
||||
param set-default SIM_GZ_SV_FUNC2 202
|
||||
param set-default SIM_GZ_SV_FUNC3 203
|
||||
param set-default SIM_GZ_SV_FUNC4 204
|
||||
param set-default SIM_GZ_SV_FUNC5 205
|
||||
param set-default SIM_GZ_SV_FUNC6 206
|
||||
@@ -39,10 +39,8 @@ px4_add_romfs_files(
|
||||
1012_gazebo-classic_iris_rplidar
|
||||
1013_gazebo-classic_iris_vision
|
||||
1013_gazebo-classic_iris_vision.post
|
||||
1014_gazebo-classic_iris_obs_avoid
|
||||
1014_gazebo-classic_iris_obs_avoid.post
|
||||
1015_gazebo-classic_iris_depth_camera
|
||||
1016_gazebo-classic_iris_downward_depth_camera
|
||||
1015_gazebo-classic_iris_obs_avoid
|
||||
1015_gazebo-classic_iris_obs_avoid.post
|
||||
1017_gazebo-classic_iris_opt_flow_mockup
|
||||
1019_gazebo-classic_iris_dual_gps
|
||||
1021_gazebo-classic_uuv_hippocampus
|
||||
@@ -79,7 +77,6 @@ px4_add_romfs_files(
|
||||
4004_gz_standard_vtol
|
||||
4005_gz_x500_vision
|
||||
4006_gz_px4vision
|
||||
4008_gz_advanced_plane
|
||||
|
||||
6011_gazebo-classic_typhoon_h480
|
||||
6011_gazebo-classic_typhoon_h480.post
|
||||
|
||||
@@ -36,20 +36,7 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
|
||||
# set local coordinate frame reference
|
||||
if [ -n "${PX4_HOME_LAT}" ]; then
|
||||
param set SIM_GZ_HOME_LAT ${PX4_HOME_LAT}
|
||||
fi
|
||||
|
||||
if [ -n "${PX4_HOME_LON}" ]; then
|
||||
param set SIM_GZ_HOME_LON ${PX4_HOME_LON}
|
||||
fi
|
||||
|
||||
if [ -n "${PX4_HOME_ALT}" ]; then
|
||||
param set SIM_GZ_HOME_ALT ${PX4_HOME_LON}
|
||||
fi
|
||||
elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; then
|
||||
|
||||
# source generated gz_env.sh for GZ_SIM_RESOURCE_PATH
|
||||
if [ -f ./gz_env.sh ]; then
|
||||
@@ -92,7 +79,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
fi
|
||||
|
||||
# start gz_bridge
|
||||
if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
|
||||
if [ -n "${PX4_GZ_MODEL}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
|
||||
# model specified, gz_bridge will spawn model
|
||||
|
||||
if [ -n "${PX4_GZ_MODEL_POSE}" ]; then
|
||||
@@ -106,7 +93,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
fi
|
||||
|
||||
# start gz bridge with pose arg.
|
||||
if gz_bridge start -p "${model_pose}" -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
|
||||
if gz_bridge start -p "${model_pose}" -m "${PX4_GZ_MODEL}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
|
||||
if param compare -s SENS_EN_BAROSIM 1
|
||||
then
|
||||
sensor_baro_sim start
|
||||
@@ -129,7 +116,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
exit 1
|
||||
fi
|
||||
|
||||
elif [ -n "${PX4_GZ_MODEL_NAME}" ]; then
|
||||
elif [ -n "${PX4_GZ_MODEL_NAME}" ] && [ -z "${PX4_GZ_MODEL}" ]; then
|
||||
# model name specificed, gz_bridge will attach to existing model
|
||||
|
||||
if gz_bridge start -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}"; then
|
||||
@@ -155,8 +142,35 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
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."
|
||||
|
||||
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
|
||||
then
|
||||
sensor_baro_sim start
|
||||
fi
|
||||
if param compare -s SENS_EN_GPSSIM 1
|
||||
then
|
||||
sensor_gps_sim start
|
||||
fi
|
||||
if param compare -s SENS_EN_MAGSIM 1
|
||||
then
|
||||
sensor_mag_sim start
|
||||
fi
|
||||
if param compare -s SENS_EN_ARSPDSIM 1
|
||||
then
|
||||
sensor_airspeed_sim start
|
||||
fi
|
||||
|
||||
else
|
||||
echo "ERROR [init] gz_bridge failed to start"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
else
|
||||
echo "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_SIM_MODEL"
|
||||
echo "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_GZ_MODEL"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
|
||||
@@ -187,11 +187,6 @@ param set-default SYS_FAILURE_EN 1
|
||||
# does not go below 50% by default, but failure injection can trigger failsafes.
|
||||
param set-default COM_LOW_BAT_ACT 2
|
||||
|
||||
# Allow to override SYS_MC_EST_GROUP via env
|
||||
if [ -n "$SYS_MC_EST_GROUP" ]; then
|
||||
param set SYS_MC_EST_GROUP $SYS_MC_EST_GROUP
|
||||
fi
|
||||
|
||||
# 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)
|
||||
|
||||
@@ -45,8 +45,12 @@ param set-default MAV_1_MODE 9
|
||||
param set-default SER_TEL1_BAUD 921600
|
||||
|
||||
# Vehicle attitude PID tuning
|
||||
param set-default MC_ACRO_EXPO 0
|
||||
param set-default MC_ACRO_EXPO_Y 0
|
||||
param set-default MC_ACRO_P_MAX 200
|
||||
param set-default MC_ACRO_R_MAX 200
|
||||
param set-default MC_ACRO_SUPEXPO 0
|
||||
param set-default MC_ACRO_SUPEXPOY 0
|
||||
param set-default MC_ACRO_Y_MAX 150
|
||||
param set-default MC_PITCHRATE_D 0.0015
|
||||
param set-default MC_ROLLRATE_D 0.0015
|
||||
|
||||
@@ -38,3 +38,5 @@ param set-default PWM_MAIN_FUNC1 101
|
||||
param set-default PWM_MAIN_FUNC2 102
|
||||
param set-default PWM_MAIN_FUNC3 103
|
||||
param set-default PWM_MAIN_FUNC4 104
|
||||
param set-default PWM_MAIN_TIM0 -4
|
||||
|
||||
|
||||
@@ -45,8 +45,12 @@ param set-default MAV_1_MODE 9
|
||||
param set-default SER_TEL1_BAUD 921600
|
||||
|
||||
# Vehicle attitude PID tuning
|
||||
param set-default MC_ACRO_EXPO 0
|
||||
param set-default MC_ACRO_EXPO_Y 0
|
||||
param set-default MC_ACRO_P_MAX 200
|
||||
param set-default MC_ACRO_R_MAX 200
|
||||
param set-default MC_ACRO_SUPEXPO 0
|
||||
param set-default MC_ACRO_SUPEXPOY 0
|
||||
param set-default MC_ACRO_Y_MAX 150
|
||||
param set-default MC_PITCHRATE_D 0.0015
|
||||
param set-default MC_ROLLRATE_D 0.0015
|
||||
|
||||
@@ -0,0 +1,65 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Reaper 500 Quad
|
||||
#
|
||||
# @type Quadrotor H
|
||||
# @class Copter
|
||||
#
|
||||
# @maintainer Blankered
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.14
|
||||
param set-default MC_ROLLRATE_I 0.1
|
||||
param set-default MC_ROLLRATE_D 0.004
|
||||
param set-default MC_PITCH_P 6
|
||||
param set-default MC_PITCHRATE_P 0.14
|
||||
param set-default MC_PITCHRATE_I 0.09
|
||||
param set-default MC_PITCHRATE_D 0.004
|
||||
param set-default MC_YAW_P 4
|
||||
|
||||
param set-default NAV_ACC_RAD 2
|
||||
|
||||
param set-default RTL_RETURN_ALT 30
|
||||
param set-default RTL_DESCEND_ALT 10
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.15
|
||||
param set-default CA_ROTOR0_PY 0.15
|
||||
param set-default CA_ROTOR0_KM -0.05
|
||||
param set-default CA_ROTOR1_PX -0.15
|
||||
param set-default CA_ROTOR1_PY -0.15
|
||||
param set-default CA_ROTOR1_KM -0.05
|
||||
param set-default CA_ROTOR2_PX 0.15
|
||||
param set-default CA_ROTOR2_PY -0.15
|
||||
param set-default CA_ROTOR2_KM 0.05
|
||||
param set-default CA_ROTOR3_PX -0.15
|
||||
param set-default CA_ROTOR3_PY 0.15
|
||||
param set-default CA_ROTOR3_KM 0.05
|
||||
|
||||
param set-default PWM_MAIN_FUNC1 101
|
||||
param set-default PWM_MAIN_FUNC2 102
|
||||
param set-default PWM_MAIN_FUNC3 103
|
||||
param set-default PWM_MAIN_FUNC4 104
|
||||
param set-default PWM_MAIN_MIN1 1100
|
||||
param set-default PWM_MAIN_MIN2 1100
|
||||
param set-default PWM_MAIN_MIN3 1100
|
||||
param set-default PWM_MAIN_MIN4 1100
|
||||
param set-default PWM_MAIN_MAX1 1900
|
||||
param set-default PWM_MAIN_MAX2 1900
|
||||
param set-default PWM_MAIN_MAX3 1900
|
||||
param set-default PWM_MAIN_MAX4 1900
|
||||
|
||||
param set-default PWM_MAIN_TIM0 50
|
||||
param set-default PWM_MAIN_TIM1 50
|
||||
param set-default PWM_MAIN_TIM2 50
|
||||
|
||||
param set-default PWM_AUX_TIM0 50
|
||||
param set-default PWM_AUX_TIM1 50
|
||||
param set-default PWM_AUX_TIM2 50
|
||||
|
||||
|
||||
@@ -0,0 +1,92 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Crazyflie 2
|
||||
#
|
||||
# @type Quadrotor x
|
||||
# @class Copter
|
||||
#
|
||||
# @maintainer Dennis Shtatov <densht@gmail.com>
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
# @board px4_fmu-v3 exclude
|
||||
# @board px4_fmu-v4 exclude
|
||||
# @board px4_fmu-v4pro exclude
|
||||
# @board px4_fmu-v5 exclude
|
||||
# @board px4_fmu-v5x exclude
|
||||
# @board diatone_mamba-f405-mk2 exclude
|
||||
#
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
param set-default BAT1_N_CELLS 1
|
||||
param set-default BAT1_CAPACITY 240
|
||||
param set-default BAT1_SOURCE 1
|
||||
|
||||
param set-default CBRK_SUPPLY_CHK 894281
|
||||
param set-default COM_RC_IN_MODE 1
|
||||
|
||||
param set-default EKF2_ABL_LIM 2
|
||||
param set-default EKF2_HGT_REF 2
|
||||
param set-default EKF2_RNG_CTRL 2
|
||||
param set-default EKF2_MAG_TYPE 1
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_DELAY 10
|
||||
|
||||
param set-default IMU_GYRO_CUTOFF 100
|
||||
param set-default IMU_ACCEL_CUTOFF 30
|
||||
|
||||
param set-default MC_AIRMODE 1
|
||||
param set-default IMU_DGYRO_CUTOFF 70
|
||||
param set-default MC_PITCHRATE_D 0.002
|
||||
param set-default MC_PITCHRATE_P 0.07
|
||||
param set-default MC_ROLLRATE_D 0.002
|
||||
param set-default MC_ROLLRATE_P 0.07
|
||||
param set-default MC_YAW_P 3
|
||||
|
||||
param set-default MPC_THR_HOVER 0.7
|
||||
param set-default MPC_THR_MAX 1
|
||||
param set-default MPC_Z_P 1.5
|
||||
param set-default MPC_Z_VEL_P_ACC 8
|
||||
param set-default MPC_Z_VEL_I_ACC 6
|
||||
param set-default MPC_HOLD_MAX_XY 0.1
|
||||
param set-default MPC_MAX_FLOW_HGT 3
|
||||
|
||||
param set-default NAV_RCL_ACT 3
|
||||
|
||||
param set-default CA_ROTOR_COUNT 4
|
||||
param set-default CA_ROTOR0_PX 0.03
|
||||
param set-default CA_ROTOR0_PY 0.03
|
||||
param set-default CA_ROTOR1_PX -0.03
|
||||
param set-default CA_ROTOR1_PY 0.03
|
||||
param set-default CA_ROTOR1_KM -0.05
|
||||
param set-default CA_ROTOR2_PX -0.03
|
||||
param set-default CA_ROTOR2_PY -0.03
|
||||
param set-default CA_ROTOR3_PX 0.03
|
||||
param set-default CA_ROTOR3_PY -0.03
|
||||
param set-default CA_ROTOR3_KM -0.05
|
||||
|
||||
# Run the motors at 328.125 kHz (recommended)
|
||||
param set-default PWM_MAIN_TIM0 3921
|
||||
param set-default PWM_MAIN_TIM1 3921
|
||||
|
||||
param set-default PWM_MAIN_FUNC1 101
|
||||
param set-default PWM_MAIN_FUNC2 102
|
||||
param set-default PWM_MAIN_FUNC3 103
|
||||
param set-default PWM_MAIN_FUNC4 104
|
||||
param set-default PWM_MAIN_DIS0 0
|
||||
param set-default PWM_MAIN_DIS1 0
|
||||
param set-default PWM_MAIN_DIS2 0
|
||||
param set-default PWM_MAIN_DIS3 0
|
||||
param set-default PWM_MAIN_MIN0 0
|
||||
param set-default PWM_MAIN_MIN1 0
|
||||
param set-default PWM_MAIN_MIN2 0
|
||||
param set-default PWM_MAIN_MIN3 0
|
||||
param set-default PWM_MAIN_MAX0 255
|
||||
param set-default PWM_MAIN_MAX1 255
|
||||
param set-default PWM_MAIN_MAX2 255
|
||||
param set-default PWM_MAIN_MAX3 255
|
||||
|
||||
|
||||
param set-default SENS_FLOW_MINRNG 0.05
|
||||
|
||||
syslink start
|
||||
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
|
||||
@@ -42,6 +42,7 @@ param set-default MC_ROLLRATE_P 0.07
|
||||
param set-default MC_YAW_P 3
|
||||
|
||||
param set-default MPC_THR_HOVER 0.7
|
||||
param set-default MPC_THR_MAX 1
|
||||
param set-default MPC_Z_P 1.5
|
||||
param set-default MPC_Z_VEL_P_ACC 8
|
||||
param set-default MPC_Z_VEL_I_ACC 6
|
||||
|
||||
@@ -13,8 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.rover_defaults
|
||||
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 4
|
||||
|
||||
param set-default EKF2_GBIAS_INIT 0.01
|
||||
@@ -54,9 +52,10 @@ param set-default GND_MAX_ANG 3.1415
|
||||
# Set geometry & output configration
|
||||
param set-default CA_AIRFRAME 6
|
||||
param set-default CA_R_REV 3
|
||||
param set-default PWM_MAIN_FUNC1 101
|
||||
param set-default PWM_MAIN_FUNC2 102
|
||||
param set-default PWM_MAIN_DIS1 1500
|
||||
param set-default PWM_MAIN_DIS2 1500
|
||||
param set-default PWM_MAIN_TIM0 50
|
||||
param set-default PWM_MAIN_TIM1 50
|
||||
|
||||
|
||||
param set-default RBCLW_ADDRESS 128
|
||||
param set-default RBCLW_FUNC1 101
|
||||
param set-default RBCLW_FUNC2 102
|
||||
param set-default RBCLW_REV 1
|
||||
|
||||
@@ -58,6 +58,7 @@ px4_add_romfs_files(
|
||||
4017_nxp_hovergames
|
||||
4019_x500_v2
|
||||
4020_holybro_px4vision_v1_5
|
||||
4040_reaper
|
||||
4041_beta75x
|
||||
4050_generic_250
|
||||
4052_holybro_qav250
|
||||
@@ -66,6 +67,7 @@ px4_add_romfs_files(
|
||||
4071_ifo
|
||||
4073_ifo-s
|
||||
4500_clover4
|
||||
4900_crazyflie
|
||||
4901_crazyflie21
|
||||
|
||||
# [5000, 5999] Quadrotor +"
|
||||
|
||||
@@ -17,7 +17,7 @@ param set-default COM_POS_FS_DELAY 5
|
||||
|
||||
# there is a 2.5 factor applied on the _FS thresholds if for invalidation
|
||||
param set-default COM_POS_FS_EPH 50
|
||||
param set-default COM_VEL_FS_EVH 3
|
||||
param set-default COM_VEL_FS_EVH 5
|
||||
|
||||
param set-default COM_POS_LOW_EPH 50
|
||||
|
||||
@@ -34,7 +34,6 @@ param set-default EKF2_REQ_EPV 10
|
||||
param set-default EKF2_REQ_HDRIFT 0.5
|
||||
param set-default EKF2_REQ_SACC 1
|
||||
param set-default EKF2_REQ_VDRIFT 1.0
|
||||
param set-default EKF2_RNG_QLTY_T 3.0
|
||||
|
||||
param set-default RTL_TYPE 1
|
||||
param set-default RTL_RETURN_ALT 100
|
||||
|
||||
@@ -172,12 +172,6 @@ then
|
||||
ms5525dso start -X
|
||||
fi
|
||||
|
||||
# TE ASP5033 differential pressure sensor external I2C
|
||||
if param compare -s SENS_EN_ASP5033 1
|
||||
then
|
||||
asp5033 start -X
|
||||
fi
|
||||
|
||||
# SHT3x temperature and hygrometer sensor, external I2C
|
||||
if param compare -s SENS_EN_SHT3X 1
|
||||
then
|
||||
|
||||
@@ -93,14 +93,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
# Check for an update of the ext_autostart folder, and replace the old one with it
|
||||
if [ -e /fs/microsd/ext_autostart_new ]
|
||||
then
|
||||
echo "Updating external autostart files"
|
||||
rm -r $SDCARD_EXT_PATH
|
||||
mv /fs/microsd/ext_autostart_new $SDCARD_EXT_PATH
|
||||
fi
|
||||
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
set PARAM_BACKUP_FILE "/fs/microsd/parameters_backup.bson"
|
||||
fi
|
||||
@@ -170,7 +162,7 @@ else
|
||||
param select-backup $PARAM_BACKUP_FILE
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X PX4_FMU_V6XRT
|
||||
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X
|
||||
then
|
||||
netman update -i eth0
|
||||
fi
|
||||
@@ -274,9 +266,12 @@ else
|
||||
. $FCONFIG
|
||||
fi
|
||||
|
||||
if px4io supported
|
||||
#
|
||||
# Start IO for PWM output or RC input if enabled
|
||||
#
|
||||
if param compare -s SYS_USE_IO 1
|
||||
then
|
||||
# Check if PX4IO present and update firmware if needed.
|
||||
# Check if PX4IO present and update firmware if needed.
|
||||
if [ -f $IOFW ]
|
||||
then
|
||||
if ! px4io checkcrc ${IOFW}
|
||||
@@ -298,12 +293,12 @@ else
|
||||
tune_control stop
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if ! px4io start
|
||||
then
|
||||
echo "PX4IO start failed"
|
||||
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
|
||||
fi
|
||||
if ! px4io start
|
||||
then
|
||||
echo "PX4IO start failed"
|
||||
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
|
||||
fi
|
||||
fi
|
||||
|
||||
@@ -335,6 +330,12 @@ else
|
||||
fi
|
||||
fi
|
||||
|
||||
# PPS capture driver
|
||||
if param greater -s INPUT_CAP_ENABLE 0
|
||||
then
|
||||
input_capture start
|
||||
fi
|
||||
|
||||
#
|
||||
# Sensors System (start before Commander so Preflight checks are properly run).
|
||||
# Commander needs to be this early for in-air-restarts.
|
||||
@@ -534,10 +535,6 @@ else
|
||||
cyphal start
|
||||
fi
|
||||
fi
|
||||
if param greater -s ZENOH_ENABLE 0
|
||||
then
|
||||
zenoh start
|
||||
fi
|
||||
|
||||
#
|
||||
# End of autostart.
|
||||
|
||||
-25
@@ -1,25 +0,0 @@
|
||||
# Security Policy
|
||||
|
||||
## Supported Versions
|
||||
|
||||
The following is a list of versions the development team is currently supporting.
|
||||
|
||||
| Version | Supported |
|
||||
| ------- | ------------------ |
|
||||
| 1.4.x | :white_check_mark: |
|
||||
| 1.3.3 | :white_check_mark: |
|
||||
| < 1.3 | :x: |
|
||||
|
||||
## Reporting a Vulnerability
|
||||
|
||||
We currently only receive security vulnerability reports through GitHub.
|
||||
|
||||
To begin a report, please go to the top-level repository, for example, PX4/PX4-Autopilot,
|
||||
and click on the Security tab. If you are on mobile, click the ... dropdown menu, and then click Security.
|
||||
|
||||
Click Report a Vulnerability to open the advisory form. Fill in the advisory details form.
|
||||
Make sure your title is descriptive, and the development team can find all of the relevant details needed
|
||||
to verify on the description box. We recommend you add as much data as possible. We welcome logs,
|
||||
screenshots, photos, and videos, anything that can help us verify and identify the issues being reported.
|
||||
|
||||
At the bottom of the form, click Submit report. The maintainer team will be notified and will get back to you ASAP.
|
||||
@@ -25,9 +25,5 @@ exec find boards msg src platforms test \
|
||||
-path src/lib/crypto/monocypher -prune -o \
|
||||
-path src/lib/crypto/libtomcrypt -prune -o \
|
||||
-path src/lib/crypto/libtommath -prune -o \
|
||||
-path src/lib/heatshrink/heatshrink -prune -o \
|
||||
-path src/modules/uxrce_dds_client/Micro-XRCE-DDS-Client -prune -o \
|
||||
-path src/lib/cdrstream/cyclonedds -prune -o \
|
||||
-path src/lib/cdrstream/rosidl -prune -o \
|
||||
-path src/modules/zenoh/zenoh-pico -prune -o \
|
||||
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN
|
||||
|
||||
@@ -1,115 +0,0 @@
|
||||
#!/bin/bash
|
||||
# Flash PX4 to a device running AuterionOS in the local network
|
||||
if [ "$1" == "-h" ] || [ "$1" == "--help" ] || [ $# -lt 2 ]; then
|
||||
echo "Usage: $0 -f <firmware.px4|.elf> [-c <configuration_dir>] -d <IP/Device> [-u <user>] [-p <ssh_port>] [--revert]"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
ssh_port=22
|
||||
ssh_user=root
|
||||
|
||||
while getopts ":f:c:d:p:u:r" opt; do
|
||||
case ${opt} in
|
||||
f )
|
||||
if [ -n "$OPTARG" ]; then
|
||||
firmware_file="$OPTARG"
|
||||
else
|
||||
echo "ERROR: -f requires a non-empty option argument."
|
||||
exit 1
|
||||
fi
|
||||
;;
|
||||
c )
|
||||
if [ -f "$OPTARG/rc.autostart" ]; then
|
||||
config_dir="$OPTARG"
|
||||
else
|
||||
echo "ERROR: -c configuration directory is empty or does not contain a valid rc.autostart"
|
||||
exit 1
|
||||
fi
|
||||
;;
|
||||
d )
|
||||
if [ "$OPTARG" ]; then
|
||||
device="$OPTARG"
|
||||
else
|
||||
echo "ERROR: -d requires a non-empty option argument."
|
||||
exit 1
|
||||
fi
|
||||
;;
|
||||
p )
|
||||
if [[ "$OPTARG" =~ ^[0-9]+$ ]]; then
|
||||
ssh_port="$OPTARG"
|
||||
else
|
||||
echo "ERROR: -p ssh_port must be a number."
|
||||
exit 1
|
||||
fi
|
||||
;;
|
||||
u )
|
||||
if [ "$OPTARG" ]; then
|
||||
ssh_user="$OPTARG"
|
||||
else
|
||||
echo "ERROR: -u requires a non-empty option argument."
|
||||
exit 1
|
||||
fi
|
||||
;;
|
||||
r )
|
||||
revert=true
|
||||
;;
|
||||
esac
|
||||
done
|
||||
|
||||
if [ -z "$device" ]; then
|
||||
echo "Error: missing device"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
target_dir=/shared_container_dir/fmu
|
||||
target_file_name="update-dev.tar"
|
||||
|
||||
if [ "$revert" == true ]; then
|
||||
# revert to the release version which was originally deployed
|
||||
cmd="cp $target_dir/update.tar $target_dir/$target_file_name"
|
||||
ssh -t -p $ssh_port $ssh_user@$device "$cmd"
|
||||
else
|
||||
# create custom update-dev.tar
|
||||
tmp_dir="$(mktemp -d)"
|
||||
config_path=""
|
||||
firmware_path=""
|
||||
|
||||
if [ -d "$config_dir" ]; then
|
||||
cp -r "$config_dir" "$tmp_dir/config"
|
||||
config_path=config
|
||||
fi
|
||||
|
||||
if [ -f "$firmware_file" ]; then
|
||||
extension="${firmware_file##*.}"
|
||||
cp "$firmware_file" "$tmp_dir/firmware.$extension"
|
||||
if [ "$extension" == "elf" ]; then
|
||||
# ensure the file is stripped to reduce file size
|
||||
arm-none-eabi-strip "$tmp_dir/firmware.$extension"
|
||||
fi
|
||||
firmware_path="firmware.$extension"
|
||||
fi
|
||||
|
||||
pushd "$tmp_dir" &>/dev/null
|
||||
|
||||
if [ -z $firmware_path ] && [ -z $config_path ]; then
|
||||
exit 1
|
||||
fi
|
||||
|
||||
tar_name="tar"
|
||||
|
||||
if [ -x "$(command -v gtar)" ]; then
|
||||
# check if gnu-tar is installed on macOS and use that instead
|
||||
tar_name="gtar"
|
||||
fi
|
||||
|
||||
$tar_name -C "$tmp_dir" --sort=name --owner=root:0 --group=root:0 --mtime='2019-01-01 00:00:00' -cvf $target_file_name $firmware_path $config_path
|
||||
|
||||
# send it to the target to start flashing
|
||||
scp -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir
|
||||
popd &>/dev/null
|
||||
rm -rf "$tmp_dir"
|
||||
fi
|
||||
|
||||
# grab status output for flashing progress
|
||||
cmd="tail --follow=name $target_dir/update_status 2>/dev/null || true"
|
||||
ssh -t -p $ssh_port $ssh_user@$device "$cmd"
|
||||
@@ -1,51 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
|
||||
DIR="$(dirname $(readlink -f $0))"
|
||||
DEFAULT_AUTOPILOT_HOST=10.41.1.1
|
||||
DEFAULT_AUTOPILOT_PORT=33333
|
||||
DEFAULT_AUTOPILOT_USER=auterion
|
||||
|
||||
for i in "$@"
|
||||
do
|
||||
case $i in
|
||||
--file=*)
|
||||
PX4_BINARY_FILE="${i#*=}"
|
||||
;;
|
||||
--default-ip=*)
|
||||
DEFAULT_AUTOPILOT_HOST="${i#*=}"
|
||||
;;
|
||||
--default-port=*)
|
||||
DEFAULT_AUTOPILOT_PORT="${i#*=}"
|
||||
;;
|
||||
--default-user=*)
|
||||
DEFAULT_AUTOPILOT_USER="${i#*=}"
|
||||
;;
|
||||
--revert)
|
||||
REVERT_AUTOPILOT_ARGUMENT=-r
|
||||
;;
|
||||
--wifi)
|
||||
DEFAULT_AUTOPILOT_HOST=10.41.0.1
|
||||
;;
|
||||
*)
|
||||
# unknown option
|
||||
;;
|
||||
esac
|
||||
done
|
||||
|
||||
# allow these to be overridden
|
||||
[ -z "$AUTOPILOT_HOST" ] && AUTOPILOT_HOST=$DEFAULT_AUTOPILOT_HOST
|
||||
[ -z "$AUTOPILOT_PORT" ] && AUTOPILOT_PORT=$DEFAULT_AUTOPILOT_PORT
|
||||
[ -z "$AUTOPILOT_USER" ] && AUTOPILOT_USER=$DEFAULT_AUTOPILOT_USER
|
||||
|
||||
ARGUMENTS=()
|
||||
ARGUMENTS+=(-d "$AUTOPILOT_HOST")
|
||||
ARGUMENTS+=(-p "$AUTOPILOT_PORT")
|
||||
ARGUMENTS+=(-u "$AUTOPILOT_USER")
|
||||
ARGUMENTS+=(${PX4_BINARY_FILE:+-f "$PX4_BINARY_FILE"})
|
||||
ARGUMENTS+=($REVERT_AUTOPILOT_ARGUMENT)
|
||||
|
||||
echo "Flashing $AUTOPILOT_HOST ..."
|
||||
|
||||
"$DIR"/remote_update_fmu.sh "${ARGUMENTS[@]}"
|
||||
|
||||
exit 0
|
||||
@@ -43,11 +43,6 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
|
||||
except:
|
||||
raise PreconditionError('could not find estimator_states instance', multi_instance)
|
||||
|
||||
try:
|
||||
estimator_sensor_bias = ulog.get_dataset('estimator_sensor_bias', multi_instance).data
|
||||
except:
|
||||
raise PreconditionError('could not find estimator_sensor_bias instance', multi_instance)
|
||||
|
||||
try:
|
||||
estimator_innovations = ulog.get_dataset('estimator_innovations', multi_instance).data
|
||||
estimator_innovation_variances = ulog.get_dataset('estimator_innovation_variances', multi_instance).data
|
||||
@@ -304,21 +299,21 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
|
||||
data_plot.save()
|
||||
data_plot.close()
|
||||
|
||||
# Plot the gyro bias estimates
|
||||
# Plot the delta angle bias estimates
|
||||
data_plot = CheckFlagsPlot(
|
||||
1e-6 * estimator_sensor_bias['timestamp'], estimator_sensor_bias,
|
||||
[['gyro_bias[0]'], ['gyro_bias[1]'], ['gyro_bias[2]']],
|
||||
x_label='time (sec)', y_labels=['X (rad/s)', 'Y (rad/s)', 'Z (rad/s)'],
|
||||
plot_title='Gyro Bias Estimates', annotate=False, pdf_handle=pdf_pages)
|
||||
1e-6 * estimator_states['timestamp'], estimator_states,
|
||||
[['states[10]'], ['states[11]'], ['states[12]']],
|
||||
x_label='time (sec)', y_labels=['X (rad)', 'Y (rad)', 'Z (rad)'],
|
||||
plot_title='Delta Angle Bias Estimates', annotate=False, pdf_handle=pdf_pages)
|
||||
data_plot.save()
|
||||
data_plot.close()
|
||||
|
||||
# Plot the accel bias estimates
|
||||
# Plot the delta velocity bias estimates
|
||||
data_plot = CheckFlagsPlot(
|
||||
1e-6 * estimator_sensor_bias['timestamp'], estimator_sensor_bias,
|
||||
[['accel_bias[0]'], ['accel_bias[1]'], ['accel_bias[2]']],
|
||||
x_label='time (sec)', y_labels=['X (m/s^2)', 'Y (m/s^2)', 'Z (m/s^2)'],
|
||||
plot_title='Accel Bias Estimates', annotate=False, pdf_handle=pdf_pages)
|
||||
1e-6 * estimator_states['timestamp'], estimator_states,
|
||||
[['states[13]'], ['states[14]'], ['states[15]']],
|
||||
x_label='time (sec)', y_labels=['X (m/s)', 'Y (m/s)', 'Z (m/s)'],
|
||||
plot_title='Delta Velocity Bias Estimates', annotate=False, pdf_handle=pdf_pages)
|
||||
data_plot.save()
|
||||
data_plot.close()
|
||||
|
||||
|
||||
@@ -302,6 +302,12 @@ When set to -1 (default), the value depends on the function (see {:}).
|
||||
for key, label, param_suffix, description in standard_params_array:
|
||||
if key in standard_params:
|
||||
|
||||
# values must be in range of an uint16_t
|
||||
if standard_params[key]['min'] < 0:
|
||||
raise Exception('minimum value for {:} expected >= 0 (got {:})'.format(key, standard_params[key]['min']))
|
||||
if standard_params[key]['max'] >= 1<<16:
|
||||
raise Exception('maximum value for {:} expected <= {:} (got {:})'.format(key, 1<<16, standard_params[key]['max']))
|
||||
|
||||
if key == 'failsafe':
|
||||
standard_params[key]['default'] = -1
|
||||
standard_params[key]['min'] = -1
|
||||
@@ -311,7 +317,7 @@ When set to -1 (default), the value depends on the function (see {:}).
|
||||
'short': channel_label+' ${i} '+label+' Value',
|
||||
'long': description
|
||||
},
|
||||
'type': 'float',
|
||||
'type': 'int32',
|
||||
'instance_start': instance_start,
|
||||
'instance_start_label': instance_start_label,
|
||||
'num_instances': num_channels,
|
||||
|
||||
@@ -1,235 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
#############################################################################
|
||||
#
|
||||
# Copyright (C) 2023 PX4 Pro Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
#############################################################################
|
||||
|
||||
"""
|
||||
Generates cpp source + header files with compressed uorb topic fields from json files
|
||||
"""
|
||||
|
||||
import argparse
|
||||
import json
|
||||
import struct
|
||||
from operator import itemgetter
|
||||
import sys
|
||||
import os
|
||||
|
||||
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../src/lib/heatshrink'))
|
||||
import heatshrink_encode
|
||||
|
||||
|
||||
def parse_json_files(json_files: [str]) -> dict:
|
||||
"""Read list of json files into a dict"""
|
||||
definitions = {}
|
||||
for json_file in json_files:
|
||||
with open(json_file, encoding='utf-8') as file_handle:
|
||||
definition = json.load(file_handle)
|
||||
assert definition['name'] not in definitions
|
||||
definitions[definition['name']] = definition
|
||||
definitions[definition['name']]['completed'] = False
|
||||
|
||||
return definitions
|
||||
|
||||
|
||||
def get_ordered_list_by_dependency(name: str, definitions: dict) -> [str]:
|
||||
"""Iterate dependency graph and create an ordered list"""
|
||||
if definitions[name]['completed']:
|
||||
return []
|
||||
ret = []
|
||||
# Get nested types first (DFS)
|
||||
for dependency in definitions[name]['dependencies']:
|
||||
ret.extend(get_ordered_list_by_dependency(dependency, definitions))
|
||||
|
||||
ret.append(name)
|
||||
definitions[name]['completed'] = True
|
||||
return ret
|
||||
|
||||
|
||||
def get_field_definitions(names: [str], definitions: dict) -> (bytes, [str]):
|
||||
"""Get byte array with all definitions"""
|
||||
ret = bytes()
|
||||
formats_list = []
|
||||
|
||||
for name in names:
|
||||
# Format as '<# orb_ids><orb_id0...><# orb_ids dependencies<orb_id_dependency0...><fields><null>'
|
||||
assert len(definitions[name]['orb_ids']) < 255
|
||||
assert len(definitions[name]['dependencies']) < 255
|
||||
ret += struct.pack('<B', len(definitions[name]['orb_ids']))
|
||||
for orb_id in definitions[name]['orb_ids']:
|
||||
assert orb_id < (1 << 16)
|
||||
ret += struct.pack('<H', orb_id)
|
||||
# Dependencies
|
||||
ret += struct.pack('<B', len(definitions[name]['dependencies']))
|
||||
for dependent_message_name in definitions[name]['dependencies']:
|
||||
# Get ORB ID by looking up the name in all definitions
|
||||
dependent_orb_id_list = [definitions[k]['main_orb_id'] for k in definitions if
|
||||
definitions[k]['name'] == dependent_message_name]
|
||||
assert len(dependent_orb_id_list) == 1
|
||||
orb_id = dependent_orb_id_list[0]
|
||||
assert (1 << 16) > orb_id >= 0
|
||||
ret += struct.pack('<H', orb_id)
|
||||
|
||||
ret += bytes(definitions[name]['fields'], 'latin1')
|
||||
ret += b'\0'
|
||||
|
||||
formats_list.append(definitions[name]['fields'])
|
||||
|
||||
return ret, formats_list
|
||||
|
||||
|
||||
def write_fields_to_cpp_file(file_name: str, compressed_fields: bytes):
|
||||
fields_str = ', '.join(str(c) for c in compressed_fields)
|
||||
with open(file_name, 'w') as file_handle:
|
||||
file_handle.write('''
|
||||
// Auto-generated from px4_generate_uorb_compressed_fields.py
|
||||
#include <uORB/topics/uORBMessageFieldsGenerated.hpp>
|
||||
|
||||
namespace uORB {
|
||||
|
||||
static const uint8_t compressed_fields[] = {
|
||||
{FIELDS}
|
||||
};
|
||||
|
||||
const uint8_t* orb_compressed_message_formats()
|
||||
{
|
||||
return compressed_fields;
|
||||
}
|
||||
unsigned orb_compressed_message_formats_size()
|
||||
{
|
||||
return sizeof(compressed_fields) / sizeof(compressed_fields[0]);
|
||||
}
|
||||
|
||||
} // namespace uORB
|
||||
'''.replace('{FIELDS}', fields_str))
|
||||
|
||||
|
||||
def c_encode(s, encoding='ascii'):
|
||||
result = ''
|
||||
for c in s:
|
||||
if not (32 <= ord(c) < 127) or c in ('\\', '"'):
|
||||
result += '\\%03o' % ord(c)
|
||||
else:
|
||||
result += c
|
||||
return '"' + result + '"'
|
||||
|
||||
|
||||
def write_fields_to_hpp_file(file_name: str, definitions: dict, window_length: int, lookahead_length: int,
|
||||
format_list: [str]):
|
||||
max_tokenized_field_length, max_tokenized_field_length_msg = max(
|
||||
((len(definitions[k]['fields']), k) for k in definitions), key=itemgetter(0))
|
||||
max_untokenized_field_length = max(definitions[k]['fields_total_length'] for k in definitions)
|
||||
max_num_orb_ids = max(len(definitions[k]['orb_ids']) for k in definitions)
|
||||
max_num_orb_id_dependencies = max(len(definitions[k]['dependencies']) for k in definitions)
|
||||
|
||||
with open(file_name, 'w') as file_handle:
|
||||
file_handle.write('''
|
||||
// Auto-generated from px4_generate_uorb_compressed_fields.py
|
||||
#include <cstdint>
|
||||
|
||||
namespace uORB {
|
||||
|
||||
/**
|
||||
* Get compressed string of all uorb message format definitions
|
||||
*/
|
||||
const uint8_t* orb_compressed_message_formats();
|
||||
|
||||
/**
|
||||
* Get length of compressed message format definitions
|
||||
*/
|
||||
unsigned orb_compressed_message_formats_size();
|
||||
|
||||
static constexpr unsigned orb_tokenized_fields_max_length = {MAX_TOKENIZED_FIELD_LENGTH}; // {MAX_TOKENIZED_FIELD_LENGTH_MSG}
|
||||
static constexpr unsigned orb_untokenized_fields_max_length = {MAX_UNTOKENIZED_FIELD_LENGTH};
|
||||
static constexpr unsigned orb_compressed_max_num_orb_ids = {MAX_NUM_ORB_IDS};
|
||||
static constexpr unsigned orb_compressed_max_num_orb_id_dependencies = {MAX_NUM_ORB_ID_DEPENDENCIES};
|
||||
|
||||
static constexpr unsigned orb_compressed_heatshrink_window_length = {WINDOW_LENGTH};
|
||||
static constexpr unsigned orb_compressed_heatshrink_lookahead_length = {LOOKAHEAD_LENGTH};
|
||||
|
||||
#define ORB_DECOMPRESSED_MESSAGE_FIELDS {{DECOMPRESSED_MESSAGE_FIELDS}}
|
||||
|
||||
} // namespace uORB
|
||||
'''
|
||||
.replace('{MAX_TOKENIZED_FIELD_LENGTH}', str(max_tokenized_field_length))
|
||||
.replace('{MAX_TOKENIZED_FIELD_LENGTH_MSG}', max_tokenized_field_length_msg)
|
||||
.replace('{MAX_UNTOKENIZED_FIELD_LENGTH}', str(max_untokenized_field_length))
|
||||
.replace('{MAX_NUM_ORB_IDS}', str(max_num_orb_ids))
|
||||
.replace('{MAX_NUM_ORB_ID_DEPENDENCIES}', str(max_num_orb_id_dependencies))
|
||||
.replace('{WINDOW_LENGTH}', str(window_length))
|
||||
.replace('{LOOKAHEAD_LENGTH}', str(lookahead_length))
|
||||
.replace('{DECOMPRESSED_MESSAGE_FIELDS}', ','.join(c_encode(x) for x in format_list))
|
||||
)
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(description='Generate compressed uorb topic fields')
|
||||
parser.add_argument('-f', dest='file',
|
||||
help="json input files",
|
||||
nargs="+")
|
||||
parser.add_argument('--source-output-file', dest='output_cpp',
|
||||
help='cpp output file to generate')
|
||||
parser.add_argument('--header-output-file', dest='output_hpp',
|
||||
help='hpp output file to generate')
|
||||
parser.add_argument('-v', '--verbose',
|
||||
action='store_true',
|
||||
help="verbose output")
|
||||
args = parser.parse_args()
|
||||
|
||||
if args.file is not None:
|
||||
definitions = parse_json_files(args.file)
|
||||
|
||||
# Get array of all field definitions
|
||||
names = []
|
||||
for definition in definitions:
|
||||
names.extend(get_ordered_list_by_dependency(definitions[definition]['name'], definitions))
|
||||
names.reverse() # Dependent definitions must be after
|
||||
assert len(names) == len(definitions)
|
||||
for definition in definitions: # sanity check
|
||||
assert definitions[definition]['completed']
|
||||
field_definitions, format_list = get_field_definitions(names, definitions)
|
||||
|
||||
# Compress
|
||||
window_size = 8 # Larger value = better compression; memory requirement (for decompression): 2 ^ window_size
|
||||
lookahead = 4
|
||||
compressed_field_definitions = heatshrink_encode.encode(field_definitions, window_size, lookahead)
|
||||
|
||||
if args.verbose:
|
||||
print(
|
||||
f'Field definitions: size: {len(field_definitions)}, reduction from compression: {len(field_definitions) - len(compressed_field_definitions)}')
|
||||
|
||||
# Write cpp & hpp file
|
||||
write_fields_to_cpp_file(args.output_cpp, compressed_field_definitions)
|
||||
write_fields_to_hpp_file(args.output_hpp, definitions, window_size, lookahead, format_list)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@@ -70,8 +70,9 @@ __license__ = "BSD"
|
||||
__email__ = "thomasgubler@gmail.com"
|
||||
|
||||
|
||||
TEMPLATE_FILE = ['msg.h.em', 'msg.cpp.em', 'uorb_idl_header.h.em', 'msg.json.em']
|
||||
TOPICS_LIST_TEMPLATE_FILE = ['uORBTopics.hpp.em', 'uORBTopics.cpp.em', None, None]
|
||||
TEMPLATE_FILE = ['msg.h.em', 'msg.cpp.em']
|
||||
TOPICS_LIST_TEMPLATE_FILE = ['uORBTopics.hpp.em', 'uORBTopics.cpp.em']
|
||||
OUTPUT_FILE_EXT = ['.h', '.cpp']
|
||||
INCL_DEFAULT = ['std_msgs:./msg/std_msgs']
|
||||
PACKAGE = 'px4'
|
||||
TOPICS_TOKEN = '# TOPICS '
|
||||
@@ -104,7 +105,7 @@ def get_topics(filename):
|
||||
return result
|
||||
|
||||
|
||||
def generate_output_from_file(format_idx, filename, outputdir, package, templatedir, includepath, all_topics):
|
||||
def generate_output_from_file(format_idx, filename, outputdir, package, templatedir, includepath):
|
||||
"""
|
||||
Converts a single .msg file to an uorb header/source file
|
||||
"""
|
||||
@@ -149,12 +150,10 @@ def generate_output_from_file(format_idx, filename, outputdir, package, template
|
||||
em_globals = {
|
||||
"name_snake_case": full_type_name_snake,
|
||||
"file_name_in": filename,
|
||||
"file_base_name": file_base_name,
|
||||
"search_path": search_path,
|
||||
"msg_context": msg_context,
|
||||
"spec": spec,
|
||||
"topics": topics,
|
||||
"all_topics": all_topics,
|
||||
}
|
||||
|
||||
# Make sure output directory exists:
|
||||
@@ -162,11 +161,7 @@ def generate_output_from_file(format_idx, filename, outputdir, package, template
|
||||
os.makedirs(outputdir)
|
||||
|
||||
template_file = os.path.join(templatedir, TEMPLATE_FILE[format_idx])
|
||||
extension = os.path.splitext(os.path.splitext(TEMPLATE_FILE[format_idx])[0])[1]
|
||||
if format_idx == 2:
|
||||
output_file = os.path.join(outputdir, file_base_name + extension)
|
||||
else:
|
||||
output_file = os.path.join(outputdir, full_type_name_snake + extension)
|
||||
output_file = os.path.join(outputdir, full_type_name_snake + OUTPUT_FILE_EXT[format_idx])
|
||||
|
||||
return generate_by_template(output_file, template_file, em_globals)
|
||||
|
||||
@@ -196,13 +191,17 @@ def generate_by_template(output_file, template_file, em_globals):
|
||||
return True
|
||||
|
||||
|
||||
def generate_topics_list_file_from_files(files, outputdir, template_filename, templatedir, all_topics):
|
||||
def generate_topics_list_file_from_files(files, outputdir, template_filename, templatedir):
|
||||
# generate cpp file with topics list
|
||||
filenames = []
|
||||
for filename in [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]:
|
||||
filenames.append(re.sub(r'(?<!^)(?=[A-Z])', '_', filename).lower())
|
||||
|
||||
tl_globals = {"msgs": filenames, "all_topics": all_topics}
|
||||
topics = []
|
||||
for msg_filename in files:
|
||||
topics.extend(get_topics(msg_filename))
|
||||
|
||||
tl_globals = {"msgs": filenames, "topics": topics}
|
||||
tl_template_file = os.path.join(templatedir, template_filename)
|
||||
tl_out_file = os.path.join(outputdir, template_filename.replace(".em", ""))
|
||||
|
||||
@@ -218,10 +217,8 @@ if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(description='Convert msg files to uorb headers/sources')
|
||||
parser.add_argument('--headers', help='Generate header files', action='store_true')
|
||||
parser.add_argument('--sources', help='Generate source files', action='store_true')
|
||||
parser.add_argument('--uorb-idl-header', help='Generate uORB compatible idl header', action='store_true')
|
||||
parser.add_argument('--json', help='Generate json files', action='store_true')
|
||||
parser.add_argument('-f', dest='file',
|
||||
help="files to convert",
|
||||
help="files to convert (use only without -d)",
|
||||
nargs="+")
|
||||
parser.add_argument('-i', dest="include_paths",
|
||||
help='Additional Include Paths', nargs="*",
|
||||
@@ -244,22 +241,13 @@ if __name__ == "__main__":
|
||||
generate_idx = 0
|
||||
elif args.sources:
|
||||
generate_idx = 1
|
||||
elif args.uorb_idl_header:
|
||||
generate_idx = 2
|
||||
elif args.json:
|
||||
generate_idx = 3
|
||||
else:
|
||||
print('Error: either --headers, --sources or --json must be specified')
|
||||
print('Error: either --headers or --sources must be specified')
|
||||
exit(-1)
|
||||
if args.file is not None:
|
||||
all_topics = []
|
||||
for msg_filename in args.file:
|
||||
all_topics.extend(get_topics(msg_filename))
|
||||
all_topics.sort()
|
||||
|
||||
for f in args.file:
|
||||
generate_output_from_file(generate_idx, f, args.outputdir, args.package, args.templatedir, INCL_DEFAULT, all_topics)
|
||||
generate_output_from_file(generate_idx, f, args.outputdir, args.package, args.templatedir, INCL_DEFAULT)
|
||||
|
||||
# Generate topics list header and source file
|
||||
if TOPICS_LIST_TEMPLATE_FILE[generate_idx] is not None and os.path.isfile(os.path.join(args.templatedir, TOPICS_LIST_TEMPLATE_FILE[generate_idx])):
|
||||
generate_topics_list_file_from_files(args.file, args.outputdir, TOPICS_LIST_TEMPLATE_FILE[generate_idx], args.templatedir, all_topics)
|
||||
if os.path.isfile(os.path.join(args.templatedir, TOPICS_LIST_TEMPLATE_FILE[generate_idx])):
|
||||
generate_topics_list_file_from_files(args.file, args.outputdir, TOPICS_LIST_TEMPLATE_FILE[generate_idx], args.templatedir)
|
||||
|
||||
@@ -171,61 +171,6 @@ def get_children_fields(base_type, search_path):
|
||||
return spec_temp.parsed_fields()
|
||||
|
||||
|
||||
def get_message_fields_str_for_message_hash(msg_fields, search_path):
|
||||
"""
|
||||
Get all fields (including for nested types) in the form of:
|
||||
'''
|
||||
uint64 timestamp
|
||||
uint8 esc_count
|
||||
uint8 esc_online_flags
|
||||
EscReport[8] esc
|
||||
uint64 timestamp
|
||||
uint32 esc_errorcount
|
||||
int32 esc_rpm
|
||||
float32 esc_voltage
|
||||
uint16 failures
|
||||
int8 esc_power
|
||||
'''
|
||||
"""
|
||||
all_fields_str = ''
|
||||
for field in msg_fields:
|
||||
if field.is_header:
|
||||
continue
|
||||
|
||||
type_name = field.type
|
||||
# detect embedded types
|
||||
sl_pos = type_name.find('/')
|
||||
if sl_pos >= 0:
|
||||
type_name = type_name[sl_pos + 1:]
|
||||
|
||||
all_fields_str += type_name + ' ' + field.name + '\n'
|
||||
|
||||
if sl_pos >= 0: # nested type, add all nested fields
|
||||
children_fields = get_children_fields(field.base_type, search_path)
|
||||
all_fields_str += get_message_fields_str_for_message_hash(children_fields, search_path)
|
||||
|
||||
return all_fields_str
|
||||
|
||||
|
||||
def hash_32_fnv1a(data: str):
|
||||
hash_val = 0x811c9dc5
|
||||
prime = 0x1000193
|
||||
for i in range(len(data)):
|
||||
value = ord(data[i])
|
||||
hash_val = hash_val ^ value
|
||||
hash_val *= prime
|
||||
hash_val &= 0xffffffff
|
||||
return hash_val
|
||||
|
||||
|
||||
def get_message_hash(msg_fields, search_path):
|
||||
"""
|
||||
Get a 32 bit message hash over all fields
|
||||
"""
|
||||
all_fields_str = get_message_fields_str_for_message_hash(msg_fields, search_path)
|
||||
return hash_32_fnv1a(all_fields_str)
|
||||
|
||||
|
||||
def add_padding_bytes(fields, search_path):
|
||||
"""
|
||||
Add padding fields before the embedded types, at the end and calculate the
|
||||
|
||||
@@ -1,65 +0,0 @@
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import re
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
uorb_struct = '%s_s'%name_snake_case
|
||||
uorb_struct_upper = name_snake_case.upper()
|
||||
}@
|
||||
|
||||
/****************************************************************
|
||||
|
||||
PX4 Cyclone DDS IDL to C Translator compatible idl struct
|
||||
Source: @file_name_in
|
||||
Compatible with Cyclone DDS: V0.11.0
|
||||
|
||||
*****************************************************************/
|
||||
#ifndef DDSC_IDL_UORB_@(uorb_struct_upper)_H
|
||||
#define DDSC_IDL_UORB_@(uorb_struct_upper)_H
|
||||
|
||||
#include "dds/ddsc/dds_public_impl.h"
|
||||
#include "dds/cdr/dds_cdrstream.h"
|
||||
#include <uORB/topics/@(name_snake_case).h>
|
||||
|
||||
@##############################
|
||||
@# Includes for dependencies
|
||||
@##############################
|
||||
@{
|
||||
for field in spec.parsed_fields():
|
||||
if (not field.is_builtin):
|
||||
if (not field.is_header):
|
||||
(package, name) = genmsg.names.package_resource_name(field.base_type)
|
||||
package = package or spec.package # convert '' to package
|
||||
|
||||
print('#include "%s.h"'%(name))
|
||||
name = re.sub(r'(?<!^)(?=[A-Z])', '_', name).lower()
|
||||
print('#include <uORB/topics/%s.h>'%(name))
|
||||
}@
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
@{
|
||||
for field in spec.parsed_fields():
|
||||
if (not field.is_builtin):
|
||||
if (not field.is_header):
|
||||
(package, name) = genmsg.names.package_resource_name(field.base_type)
|
||||
package = package or spec.package # convert '' to package
|
||||
|
||||
print('typedef px4_msg_%s px4_msg_px4__msg__%s;' % (name,name))
|
||||
}@
|
||||
|
||||
|
||||
|
||||
typedef struct @uorb_struct px4_msg_@(file_base_name);
|
||||
|
||||
extern const struct dds_cdrstream_desc px4_msg_@(file_base_name)_cdrstream_desc;
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* DDSC_IDL_UORB_@(uorb_struct_upper)_H */
|
||||
@@ -124,9 +124,8 @@ static inline constexpr int ucdr_topic_size_@(topic)()
|
||||
return @(struct_size);
|
||||
}
|
||||
|
||||
static inline bool ucdr_serialize_@(topic)(const void* data, ucdrBuffer& buf, int64_t time_offset = 0)
|
||||
bool ucdr_serialize_@(topic)(const @(uorb_struct)& topic, ucdrBuffer& buf, int64_t time_offset = 0)
|
||||
{
|
||||
const @(uorb_struct)& topic = *static_cast<const @(uorb_struct)*>(data);
|
||||
@{
|
||||
for field_type, field_name, field_size, padding in fields:
|
||||
if padding > 0:
|
||||
@@ -153,7 +152,7 @@ for field_type, field_name, field_size, padding in fields:
|
||||
return true;
|
||||
}
|
||||
|
||||
static inline bool ucdr_deserialize_@(topic)(ucdrBuffer& buf, @(uorb_struct)& topic, int64_t time_offset = 0)
|
||||
bool ucdr_deserialize_@(topic)(ucdrBuffer& buf, @(uorb_struct)& topic, int64_t time_offset = 0)
|
||||
{
|
||||
@{
|
||||
for field_type, field_name, field_size, padding in fields:
|
||||
|
||||
@@ -14,7 +14,6 @@
|
||||
@# - spec (msggen.MsgSpec) Parsed specification of the .msg file
|
||||
@# - search_path (dict) search paths for genmsg
|
||||
@# - topics (List of String) topic names
|
||||
@# - all_topics (List of String) all generated topic names (sorted)
|
||||
@###############################################
|
||||
/****************************************************************************
|
||||
*
|
||||
@@ -58,9 +57,9 @@ from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
uorb_struct = '%s_s'%name_snake_case
|
||||
|
||||
message_hash = get_message_hash(spec.parsed_fields(), search_path)
|
||||
sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True)
|
||||
struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
|
||||
topic_fields = ["%s %s" % (convert_type(field.type, True), field.name) for field in sorted_fields]
|
||||
}@
|
||||
|
||||
#include <inttypes.h>
|
||||
@@ -73,9 +72,12 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
|
||||
@# join all msg files in one line e.g: "float[3] position;float[3] velocity;bool armed"
|
||||
@# This is used for the logger
|
||||
constexpr char __orb_@(name_snake_case)_fields[] = "@( ";".join(topic_fields) );";
|
||||
|
||||
@[for topic in topics]@
|
||||
static_assert(static_cast<orb_id_size_t>(ORB_ID::@topic) == @(all_topics.index(topic)), "ORB_ID index mismatch");
|
||||
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), @(message_hash)u, static_cast<orb_id_size_t>(ORB_ID::@topic));
|
||||
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), __orb_@(name_snake_case)_fields, static_cast<uint8_t>(ORB_ID::@topic));
|
||||
@[end for]
|
||||
|
||||
void print_message(const orb_metadata *meta, const @uorb_struct& message)
|
||||
|
||||
@@ -1,50 +0,0 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# PX4 ROS compatible message source code
|
||||
@# generation for C++
|
||||
@#
|
||||
@# EmPy template for generating <msg>.h files
|
||||
@# Based on the original template for ROS
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - file_name_in (String) Source file
|
||||
@# - spec (msggen.MsgSpec) Parsed specification of the .msg file
|
||||
@# - search_path (dict) search paths for genmsg
|
||||
@# - topics (List of String) topic names
|
||||
@# - all_topics (List of String) all generated topic names (sorted)
|
||||
@###############################################
|
||||
|
||||
@{
|
||||
import genmsg.msgs
|
||||
import json
|
||||
|
||||
from px_generate_uorb_topic_helper import * # this is in Tools/
|
||||
|
||||
uorb_struct = '%s_s'%name_snake_case
|
||||
|
||||
sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True)
|
||||
struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
|
||||
topic_fields = ["%s %s" % (convert_type(field.type, True), field.name) for field in sorted_fields]
|
||||
|
||||
dependencies = []
|
||||
for field in spec.parsed_fields():
|
||||
if not field.is_header:
|
||||
type_name = field.type
|
||||
# detect embedded types
|
||||
sl_pos = type_name.find('/')
|
||||
if sl_pos >= 0: # nested type
|
||||
dependencies.append(field.base_type)
|
||||
}@
|
||||
|
||||
{
|
||||
@# join all msg files in one line e.g: "float[3] position;float[3] velocity;bool armed;"
|
||||
"fields": @( json.dumps(bytearray(";".join(topic_fields)+";", 'utf-8').decode('unicode_escape')) ),
|
||||
"fields_total_length": @(sum([len(convert_type(field.type))+1+len(field.name)+1 for field in sorted_fields])),
|
||||
"orb_ids": @( json.dumps([ all_topics.index(topic) for topic in topics]) ),
|
||||
"main_orb_id": @( all_topics.index(name_snake_case) if name_snake_case in all_topics else -1 ),
|
||||
"dependencies": @( json.dumps(list(set(dependencies))) ),
|
||||
"name": "@( spec.full_name )"
|
||||
}
|
||||
@@ -8,7 +8,7 @@
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@# - all_topics (List) list of all topic names (sorted)
|
||||
@# - multi_topics (List) list of all multi-topic names
|
||||
@###############################################
|
||||
/****************************************************************************
|
||||
*
|
||||
@@ -50,7 +50,9 @@ msg_names = list(set([mn.replace(".msg", "") for mn in msgs])) # set() filters d
|
||||
msg_names.sort()
|
||||
msgs_count = len(msg_names)
|
||||
|
||||
topics_count = len(all_topics)
|
||||
topic_names = list(set(topics)) # set() filters duplicates
|
||||
topic_names.sort()
|
||||
topics_count = len(topics)
|
||||
|
||||
}@
|
||||
@[for msg_name in msg_names]@
|
||||
@@ -58,8 +60,8 @@ topics_count = len(all_topics)
|
||||
@[end for]
|
||||
|
||||
const constexpr struct orb_metadata *const uorb_topics_list[ORB_TOPICS_COUNT] = {
|
||||
@[for idx, topic_name in enumerate(all_topics, 1)]@
|
||||
ORB_ID(@(topic_name))@[if idx != all_topics], @[end if]
|
||||
@[for idx, topic_name in enumerate(topic_names, 1)]@
|
||||
ORB_ID(@(topic_name))@[if idx != topic_names], @[end if]
|
||||
@[end for]
|
||||
};
|
||||
|
||||
@@ -74,5 +76,5 @@ const struct orb_metadata *get_orb_meta(ORB_ID id)
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return uorb_topics_list[static_cast<orb_id_size_t>(id)];
|
||||
return uorb_topics_list[static_cast<uint8_t>(id)];
|
||||
}
|
||||
|
||||
@@ -7,8 +7,7 @@
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - msgs (List) list of all msg files
|
||||
@# - all_topics (List) list of all topic names (sorted)
|
||||
@# - topics (List) list of all topic names
|
||||
@###############################################
|
||||
/****************************************************************************
|
||||
*
|
||||
@@ -44,7 +43,9 @@
|
||||
****************************************************************************/
|
||||
|
||||
@{
|
||||
topics_count = len(all_topics)
|
||||
topics_count = len(topics)
|
||||
topic_names_all = list(set(topics)) # set() filters duplicates
|
||||
topic_names_all.sort()
|
||||
}@
|
||||
|
||||
#pragma once
|
||||
@@ -61,8 +62,8 @@ static constexpr size_t orb_topics_count() { return ORB_TOPICS_COUNT; }
|
||||
*/
|
||||
extern const struct orb_metadata *const *orb_get_topics() __EXPORT;
|
||||
|
||||
enum class ORB_ID : orb_id_size_t {
|
||||
@[for idx, topic_name in enumerate(all_topics)]@
|
||||
enum class ORB_ID : uint8_t {
|
||||
@[for idx, topic_name in enumerate(topic_names_all)]@
|
||||
@(topic_name) = @(idx),
|
||||
@[end for]
|
||||
INVALID
|
||||
|
||||
@@ -250,22 +250,6 @@ class SourceParser(object):
|
||||
event.group = "arming_check"
|
||||
event.prepend_arguments([('navigation_mode_group_t', 'modes'),
|
||||
('uint8_t', 'health_component_index')])
|
||||
elif call in ['reporter.healthFailureExt', 'reporter.armingCheckFailureExt']: # from ROS2
|
||||
assert len(args_split) == num_args + 3, \
|
||||
"Unexpected Number of arguments for: {:}, {:}".format(args_split, num_args)
|
||||
m = self.re_event_id.search(args_split[0])
|
||||
if m:
|
||||
_, event_name = m.group(1, 2)
|
||||
else:
|
||||
raise Exception("Could not extract event ID from {:}".format(args_split[0]))
|
||||
event.name = event_name
|
||||
event.message = args_split[2][1:-1]
|
||||
if 'health' in call:
|
||||
event.group = "health"
|
||||
else:
|
||||
event.group = "arming_check"
|
||||
event.prepend_arguments([('navigation_mode_group_t', 'modes'),
|
||||
('uint8_t', 'health_component_index')])
|
||||
else:
|
||||
raise Exception("unknown event method call: {}, args: {}".format(call, args))
|
||||
|
||||
|
||||
+38
-10
@@ -1,7 +1,7 @@
|
||||
#! /usr/bin/env bash
|
||||
|
||||
## Bash script to setup PX4 development environment on Arch Linux.
|
||||
## Tested on Arch 2023-03-01
|
||||
## Tested on Manjaro 20.2.1.
|
||||
##
|
||||
## Installs:
|
||||
## - Common dependencies and tools for nuttx, jMAVSim
|
||||
@@ -50,7 +50,6 @@ sudo pacman -Sy --noconfirm --needed \
|
||||
cmake \
|
||||
cppcheck \
|
||||
doxygen \
|
||||
fuse2 \
|
||||
gdb \
|
||||
git \
|
||||
gnutls \
|
||||
@@ -67,7 +66,7 @@ sudo pacman -Sy --noconfirm --needed \
|
||||
|
||||
# Python dependencies
|
||||
echo "Installing PX4 Python3 dependencies"
|
||||
pip install --break-system-packages -r ${DIR}/${REQUIREMENTS_FILE}
|
||||
pip install --user -r ${DIR}/requirements.txt
|
||||
|
||||
# NuttX toolchain (arm-none-eabi-gcc)
|
||||
if [[ $INSTALL_NUTTX == "true" ]]; then
|
||||
@@ -75,17 +74,45 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
|
||||
echo "Installing NuttX dependencies"
|
||||
|
||||
sudo pacman -S --noconfirm --needed \
|
||||
arm-none-eabi-gcc \
|
||||
arm-none-eabi-newlib \
|
||||
gperf \
|
||||
vim \
|
||||
;
|
||||
|
||||
if [ ! -z "$USER" ]; then
|
||||
# add user to dialout group (serial port access)
|
||||
sudo echo usermod -aG uucp $USER
|
||||
sudo usermod -aG uucp $USER
|
||||
fi
|
||||
|
||||
# don't run modem manager (interferes with PX4 serial port usage)
|
||||
sudo systemctl disable --now ModemManager
|
||||
# remove modem manager (interferes with PX4 serial port usage)
|
||||
sudo pacman -R modemmanager --noconfirm
|
||||
|
||||
# arm-none-eabi-gcc
|
||||
NUTTX_GCC_VERSION="10-2020-q4-major"
|
||||
NUTTX_GCC_VERSION_SHORT="10-2020q4"
|
||||
|
||||
source $HOME/.profile # load changed path for the case the script is reran before relogin
|
||||
if [ $(which arm-none-eabi-gcc) ]; then
|
||||
GCC_VER_STR=$(arm-none-eabi-gcc --version)
|
||||
GCC_FOUND_VER=$(echo $GCC_VER_STR | grep -c "${NUTTX_GCC_VERSION}")
|
||||
fi
|
||||
|
||||
if [[ "$GCC_FOUND_VER" == "1" ]]; then
|
||||
echo "arm-none-eabi-gcc-${NUTTX_GCC_VERSION} found, skipping installation"
|
||||
|
||||
else
|
||||
echo "Installing arm-none-eabi-gcc-${NUTTX_GCC_VERSION}";
|
||||
wget -O /tmp/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}-linux.tar.bz2 https://armkeil.blob.core.windows.net/developer/Files/downloads/gnu-rm/${NUTTX_GCC_VERSION_SHORT}/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}-x86_64-linux.tar.bz2 && \
|
||||
sudo tar -jxf /tmp/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}-linux.tar.bz2 -C /opt/;
|
||||
|
||||
# add arm-none-eabi-gcc to user's PATH
|
||||
exportline="export PATH=/opt/gcc-arm-none-eabi-${NUTTX_GCC_VERSION}/bin:\$PATH"
|
||||
|
||||
if grep -Fxq "$exportline" $HOME/.profile; then
|
||||
echo "${NUTTX_GCC_VERSION} path already set.";
|
||||
else
|
||||
echo $exportline >> $HOME/.profile;
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
# Simulation tools
|
||||
@@ -95,7 +122,8 @@ if [[ $INSTALL_SIM == "true" ]]; then
|
||||
|
||||
# java (jmavsim)
|
||||
sudo pacman -S --noconfirm --needed \
|
||||
ant
|
||||
ant \
|
||||
jdk-openjdk \
|
||||
;
|
||||
|
||||
# Gazebo setup
|
||||
@@ -133,5 +161,5 @@ fi
|
||||
|
||||
if [[ $INSTALL_NUTTX == "true" ]]; then
|
||||
echo
|
||||
echo "Reboot or logout, login computer before attempting to flash NuttX targets"
|
||||
echo "Reboot or logout, login computer before attempting to build NuttX targets"
|
||||
fi
|
||||
|
||||
@@ -2,7 +2,7 @@ argcomplete
|
||||
argparse>=1.2
|
||||
cerberus
|
||||
coverage
|
||||
empy==3.3.4
|
||||
empy>=3.3
|
||||
future
|
||||
jinja2>=2.8
|
||||
jsonschema
|
||||
|
||||
@@ -155,7 +155,7 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
|
||||
|
||||
if [ -n "$USER" ]; then
|
||||
# add user to dialout group (serial port access)
|
||||
sudo usermod -aG dialout $USER
|
||||
sudo usermod -a -G dialout $USER
|
||||
fi
|
||||
|
||||
# arm-none-eabi-gcc
|
||||
@@ -165,7 +165,7 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
|
||||
source $HOME/.profile # load changed path for the case the script is reran before relogin
|
||||
if [ $(which arm-none-eabi-gcc) ]; then
|
||||
GCC_VER_STR=$(arm-none-eabi-gcc --version)
|
||||
GCC_FOUND_VER=$(echo $GCC_VER_STR | grep -c "${NUTTX_GCC_VERSION}" || true)
|
||||
GCC_FOUND_VER=$(echo $GCC_VER_STR | grep -c "${NUTTX_GCC_VERSION}")
|
||||
fi
|
||||
|
||||
if [[ "$GCC_FOUND_VER" == "1" ]]; then
|
||||
|
||||
Submodule Tools/simulation/gazebo-classic/sitl_gazebo-classic updated: 33ac87a376...20ded0757b
@@ -1,14 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>Advanced Plane</name>
|
||||
<version>1.0</version>
|
||||
<sdf version='1.5'>model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Karthik Srivatsan</name>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
This is a model of a standard plane, which uses the advanced liftdrag plugin.
|
||||
</description>
|
||||
</model>
|
||||
@@ -1,578 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<sdf version='1.5'>
|
||||
<model name='plane'>
|
||||
<pose>0 0 0.246 0 0 0</pose>
|
||||
<link name='base_link'>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<mass>1</mass>
|
||||
<inertia>
|
||||
<ixx>0.197563</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.1458929</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.1477</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='base_link_collision'>
|
||||
<pose>0 0 -0.07 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.47 0.47 0.11</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>10</max_vel>
|
||||
<min_depth>0.01</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='base_link_visual'>
|
||||
<pose>0.07 0 -0.08 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/body.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>.175 .175 .175 1.0</ambient>
|
||||
<diffuse>.175 .175 .175 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
<gravity>1</gravity>
|
||||
<velocity_decay/>
|
||||
<self_collide>0</self_collide>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>250</update_rate>
|
||||
</sensor>
|
||||
<sensor name="air_pressure_sensor" type="air_pressure">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>50</update_rate>
|
||||
<air_pressure>
|
||||
<pressure>
|
||||
<noise type="gaussian">
|
||||
<mean>0</mean>
|
||||
<stddev>0.01</stddev>
|
||||
</noise>
|
||||
</pressure>
|
||||
</air_pressure>
|
||||
</sensor>
|
||||
</link>
|
||||
<link name='rotor_puller'>
|
||||
<pose>0.3 0 0.0 0 1.57 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<mass>0.005</mass>
|
||||
<inertia>
|
||||
<ixx>9.75e-07</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.000166704</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.000167604</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='rotor_puller_collision'>
|
||||
<pose>0.0 0 0.0 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<length>0.005</length>
|
||||
<radius>0.1</radius>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='rotor_puller_visual'>
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/iris_prop_ccw.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>.175 .175 .175 1.0</ambient>
|
||||
<diffuse>.175 .175 .175 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
<gravity>1</gravity>
|
||||
<velocity_decay/>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
<joint name='rotor_puller_joint' type='revolute'>
|
||||
<child>rotor_puller</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-1e+16</lower>
|
||||
<upper>1e+16</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
<use_parent_model_frame>1</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name="left_elevon">
|
||||
<inertial>
|
||||
<mass>0.00000001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000001</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<iyy>0.000001</iyy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.000001</izz>
|
||||
</inertia>
|
||||
<pose>0 0.3 0 0.00 0 0.0</pose>
|
||||
</inertial>
|
||||
<visual name='left_elevon_visual'>
|
||||
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/left_aileron.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1.0</ambient>
|
||||
<diffuse>1 0 0 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="right_elevon">
|
||||
<inertial>
|
||||
<mass>0.00000001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000001</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<iyy>0.000001</iyy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.000001</izz>
|
||||
</inertia>
|
||||
<pose>0 -0.3 0 0.00 0 0.0</pose>
|
||||
</inertial>
|
||||
<visual name='right_elevon_visual'>
|
||||
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/right_aileron.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1.0</ambient>
|
||||
<diffuse>1 0 0 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="left_flap">
|
||||
<inertial>
|
||||
<mass>0.00000001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000001</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<iyy>0.000001</iyy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.000001</izz>
|
||||
</inertia>
|
||||
<pose>0 0.15 0 0.00 0 0.0</pose>
|
||||
</inertial>
|
||||
<visual name='left_flap_visual'>
|
||||
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/left_flap.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1.0</ambient>
|
||||
<diffuse>1 0 0 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="right_flap">
|
||||
<inertial>
|
||||
<mass>0.00000001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000001</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<iyy>0.000001</iyy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.000001</izz>
|
||||
</inertia>
|
||||
<pose>0 -0.15 0 0.00 0 0.0</pose>
|
||||
</inertial>
|
||||
<visual name='right_flap_visual'>
|
||||
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/right_flap.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1.0</ambient>
|
||||
<diffuse>1 0 0 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="elevator">
|
||||
<inertial>
|
||||
<mass>0.00000001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000001</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<iyy>0.000001</iyy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.000001</izz>
|
||||
</inertia>
|
||||
<pose> -0.5 0 0 0.00 0 0.0</pose>
|
||||
</inertial>
|
||||
<visual name='elevator_visual'>
|
||||
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/elevators.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1.0</ambient>
|
||||
<diffuse>1 0 0 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="rudder">
|
||||
<inertial>
|
||||
<mass>0.00000001</mass>
|
||||
<inertia>
|
||||
<ixx>0.000001</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<iyy>0.000001</iyy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.000001</izz>
|
||||
</inertia>
|
||||
<pose>-0.5 0 0.05 0 0 0 </pose>
|
||||
</inertial>
|
||||
<visual name='rudder_visual'>
|
||||
<pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.1 0.1 0.1</scale>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Advanced%20Plane/tip/files/meshes/rudder.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1.0</ambient>
|
||||
<diffuse>1 0 0 1.0</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name='servo_0' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>left_elevon</child>
|
||||
<pose>-0.07 0.4 0.08 0.00 0 0.0</pose>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<!-- -30/+30 deg. -->
|
||||
<lower>-0.53</lower>
|
||||
<upper>0.53</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.000</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<plugin
|
||||
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
|
||||
<joint_name>servo_0</joint_name>
|
||||
<sub_topic>servo_0</sub_topic>
|
||||
<p_gain>10</p_gain>
|
||||
<i_gain>0</i_gain>
|
||||
<d_gain>0</d_gain>
|
||||
</plugin>
|
||||
<joint name='servo_1' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>right_elevon</child>
|
||||
<pose>-0.07 -0.4 0.08 0.00 0 0.0</pose>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<!-- -30/+30 deg. -->
|
||||
<lower>-0.53</lower>
|
||||
<upper>0.53</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.000</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<plugin
|
||||
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
|
||||
<joint_name>servo_1</joint_name>
|
||||
<sub_topic>servo_1</sub_topic>
|
||||
<p_gain>10</p_gain>
|
||||
<i_gain>0</i_gain>
|
||||
<d_gain>0</d_gain>
|
||||
</plugin>
|
||||
<joint name='servo_4' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>left_flap</child>
|
||||
<pose>-0.07 0.2 0.08 0.00 0 0.0</pose>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<!-- -30/+30 deg. -->
|
||||
<lower>-0.53</lower>
|
||||
<upper>0.53</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.000</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<plugin
|
||||
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
|
||||
<joint_name>servo_4</joint_name>
|
||||
<sub_topic>servo_4</sub_topic>
|
||||
<p_gain>10</p_gain>
|
||||
<i_gain>0</i_gain>
|
||||
<d_gain>0</d_gain>
|
||||
</plugin>
|
||||
<joint name='servo_5' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>right_flap</child>
|
||||
<pose>-0.07 -0.2 0.08 0.00 0 0.0</pose>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<!-- -30/+30 deg. -->
|
||||
<lower>-0.53</lower>
|
||||
<upper>0.53</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.000</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<plugin
|
||||
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
|
||||
<joint_name>servo_5</joint_name>
|
||||
<sub_topic>servo_5</sub_topic>
|
||||
<p_gain>10</p_gain>
|
||||
<i_gain>0</i_gain>
|
||||
<d_gain>0</d_gain>
|
||||
</plugin>
|
||||
<joint name='servo_2' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>elevator</child>
|
||||
<pose> -0.5 0 0 0 0 0</pose>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<!-- -30/+30 deg. -->
|
||||
<lower>-0.53</lower>
|
||||
<upper>0.53</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.000</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<plugin
|
||||
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
|
||||
<joint_name>servo_2</joint_name>
|
||||
<sub_topic>servo_2</sub_topic>
|
||||
<p_gain>10</p_gain>
|
||||
<i_gain>0</i_gain>
|
||||
<d_gain>0</d_gain>
|
||||
</plugin>
|
||||
<joint name='servo_3' type='revolute'>
|
||||
<parent>base_link</parent>
|
||||
<child>rudder</child>
|
||||
<pose>-0.5 0 0.05 0.00 0 0.0</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<!-- -30/+30 deg. -->
|
||||
<lower>-0.53</lower>
|
||||
<upper>0.53</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>1.000</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
<physics>
|
||||
<ode>
|
||||
<implicit_spring_damper>1</implicit_spring_damper>
|
||||
</ode>
|
||||
</physics>
|
||||
</joint>
|
||||
<plugin
|
||||
filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController">
|
||||
<joint_name>servo_3</joint_name>
|
||||
<sub_topic>servo_3</sub_topic>
|
||||
<p_gain>10</p_gain>
|
||||
<i_gain>0</i_gain>
|
||||
<d_gain>0</d_gain>
|
||||
</plugin>
|
||||
|
||||
<plugin filename="gz-sim-advanced-lift-drag-system" name="gz::sim::systems::AdvancedLiftDrag">
|
||||
<a0>0.0</a0>
|
||||
<CL0>0.15188</CL0>
|
||||
<AR>6.5</AR>
|
||||
<eff>0.97</eff>
|
||||
<CLa>5.015</CLa>
|
||||
<CD0>0.029</CD0>
|
||||
<Cem0>0.075</Cem0>
|
||||
<Cema>-0.463966</Cema>
|
||||
<CYb>-0.258244</CYb>
|
||||
<Cellb>-0.039250</Cellb>
|
||||
<Cenb>0.100826</Cenb>
|
||||
<CDp>0.0</CDp>
|
||||
<CYp>0.065861</CYp>
|
||||
<CLp>0.0</CLp>
|
||||
<Cellp>-0.487407</Cellp>
|
||||
<Cemp>0.0</Cemp>
|
||||
<Cenp>-0.040416</Cenp>
|
||||
<CDq>0.055166</CDq>
|
||||
<CYq>0.0</CYq>
|
||||
<CLq>7.971792</CLq>
|
||||
<Cellq>0.0</Cellq>
|
||||
<Cemq>-12.140140</Cemq>
|
||||
<Cenq>0.0</Cenq>
|
||||
<CDr>0.0</CDr>
|
||||
<CYr>0.230299</CYr>
|
||||
<CLr>0.0</CLr>
|
||||
<Cellr>0.078165</Cellr>
|
||||
<Cemr>0.0</Cemr>
|
||||
<Cenr>-0.089947</Cenr>
|
||||
<alpha_stall>0.3391428111</alpha_stall>
|
||||
<CLa_stall>-3.85</CLa_stall>
|
||||
<CDa_stall>-0.9233984055</CDa_stall>
|
||||
<Cema_stall>0</Cema_stall>
|
||||
<cp>-0.12 0.0 0.0</cp>
|
||||
<area>0.34</area>
|
||||
<mac>0.22</mac>
|
||||
<air_density>1.2041</air_density>
|
||||
<forward>1 0 0</forward>
|
||||
<upward>0 0 1</upward>
|
||||
<link_name>base_link</link_name>
|
||||
<num_ctrl_surfaces>4</num_ctrl_surfaces>
|
||||
<control_surface>
|
||||
<name>servo_0</name>
|
||||
<index>0</index>
|
||||
<direction>1</direction>
|
||||
<CD_ctrl>-0.000059</CD_ctrl>
|
||||
<CY_ctrl>0.000171</CY_ctrl>
|
||||
<CL_ctrl>-0.011940</CL_ctrl>
|
||||
<Cell_ctrl>-0.003331</Cell_ctrl>
|
||||
<Cem_ctrl>0.001498</Cem_ctrl>
|
||||
<Cen_ctrl>-0.000057</Cen_ctrl>
|
||||
</control_surface>
|
||||
<control_surface>
|
||||
<name>servo_1</name>
|
||||
<direction>1</direction>
|
||||
<index>1</index>
|
||||
<CD_ctrl>-0.000059</CD_ctrl>
|
||||
<CY_ctrl>-0.000171</CY_ctrl>
|
||||
<CL_ctrl>-0.011940</CL_ctrl>
|
||||
<Cell_ctrl>0.003331</Cell_ctrl>
|
||||
<Cem_ctrl>0.001498</Cem_ctrl>
|
||||
<Cen_ctrl>0.000057</Cen_ctrl>
|
||||
</control_surface>
|
||||
<control_surface>
|
||||
<name>servo_2</name>
|
||||
<direction>-1</direction>
|
||||
<index>2</index>
|
||||
<CD_ctrl>0.000274</CD_ctrl>
|
||||
<CY_ctrl>0</CY_ctrl>
|
||||
<CL_ctrl>0.010696</CL_ctrl>
|
||||
<Cell_ctrl>0.0</Cell_ctrl>
|
||||
<Cem_ctrl>-0.025798</Cem_ctrl>
|
||||
<Cen_ctrl>0.0</Cen_ctrl>
|
||||
</control_surface>
|
||||
<control_surface>
|
||||
<name>servo_3</name>
|
||||
<direction>1</direction>
|
||||
<index>3</index>
|
||||
<CD_ctrl>0.0</CD_ctrl>
|
||||
<CY_ctrl>-0.003913</CY_ctrl>
|
||||
<CL_ctrl>0.0</CL_ctrl>
|
||||
<Cell_ctrl>-0.000257</Cell_ctrl>
|
||||
<Cem_ctrl>0.0</Cem_ctrl>
|
||||
<Cen_ctrl>0.001613</Cen_ctrl>
|
||||
</control_surface>
|
||||
</plugin>
|
||||
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
|
||||
<jointName>rotor_puller_joint</jointName>
|
||||
<linkName>rotor_puller</linkName>
|
||||
<turningDirection>cw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>3500</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.01</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>0</motorNumber>
|
||||
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
<motorType>velocity</motorType>
|
||||
|
||||
</plugin>
|
||||
</model>
|
||||
</sdf>
|
||||
@@ -2,7 +2,7 @@
|
||||
<sdf version='1.9'>
|
||||
<include>
|
||||
<name>omnicopter</name>
|
||||
<pose>0 0 0.2 0 0 0</pose>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<uri>https://fuel.gazebosim.org/1.0/PX4/models/Omnicopter</uri>
|
||||
</include>
|
||||
</sdf>
|
||||
|
||||
@@ -806,7 +806,7 @@
|
||||
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
|
||||
<jointName>rotor_puller_joint</jointName>
|
||||
<linkName>rotor_puller</linkName>
|
||||
<turningDirection>ccw</turningDirection>
|
||||
<turningDirection>cw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>1000</maxRotVelocity>
|
||||
|
||||
@@ -1,149 +0,0 @@
|
||||
## Purpose
|
||||
|
||||
The idea of this tool is to automate the writing of the Advanced Lift Drag plugin by automatizing the coefficient generation and requiring minimal user calculations.
|
||||
|
||||
## Setup
|
||||
|
||||
In order to run this tool, it is necessary to follow these steps:
|
||||
|
||||
1. Download AVL 3.36 from <https://web.mit.edu/drela/Public/web/avl/>. The file for AVL version 3.36 can be found about halfway down the page.
|
||||
2. After downloading, extract AVL and move it to the home directory using:
|
||||
|
||||
```shell
|
||||
sudo tar -xf avl3.36.tgz
|
||||
mv ./Avl /home/
|
||||
```
|
||||
|
||||
Follow the README.md found in Avl to finish the setup process for AVL (requires to set up plotlib and eispack libraries). I recommend using the gfortran compile option. This might require you to install gfortran. This can be done by running:
|
||||
|
||||
```shell
|
||||
sudo apt update
|
||||
sudo apt install gfortran
|
||||
```
|
||||
|
||||
When running the Makefile for AVL, you might encounter an Error 1 message stating that there is a directory missing. This does not prevent AVL from working for our purposes. Once the process described in the AVL README is completed, AVL is ready to be used. No further set up is required on the side of the AVL or the tool.
|
||||
If you want to move the location of the AVL directory, this can simply be done by passing the `--avl_path` flag to the `input_avl.py` file, using the desired directory location for the flag (don't forget to place a "/" behind the last part of the path). Running this will automatically also adjust the paths where necessary.
|
||||
|
||||
## Run
|
||||
|
||||
To run the tool all that is needed is to modify the `input.yml` to the plane that you desire and then run `python input_avl.py <your_custom_yaml_file>.yml` Note that you require to have the yaml and argparse packages in your python environment to run this. An example template has been provided in the form of the `input.yml` that implements a standard plane with two ailerons, an elevator and a rudder. This example template can be run using: `python input_avl.py --yaml_file input.yml`.
|
||||
Once the script has been executed, the generated .avl, .sdf and a plot of the proposed control surfaces can be found in <your-planes-name> directory. The sdf file is the generated Advanced Lift Drag Plugin that can be copied and pasted straight into a model.sdf file, which can then be run in Gazebo.
|
||||
|
||||
## Functionality
|
||||
|
||||
The tool first asks the user for a range of vehicle specific parameters that are needed in order to specify the geometry and physical properties of the plane. The user has the choice to define a completely custom model, or alternatively select a predefined model template (such as a Cessna or a VTOL), which has a known number of control surfaces, and then provide only some physical properties, without having to define the entire model themselves. The input_avl.py file takes the provided parameter and creates an .avl file from this that can be read by AVL (the program). This happens in the process.sh file. The necessary output generated by AVL will be saved in two files: custom_vehicle_body_axis_derivatives.txt and custom_vehicle_stability_derivatives.txt. These two files contain the parameters that are required in order to populate the Advanced Lift Drag Plugin. Finally, avl_out_parse.py reads the generated .txt files and accordingly assigns parameters to the correct element in sdf. Once this is done, it is only a question of copy and pasting the generated Advanced Lift Drag plugin (found as <custom_plane>.sdf into the desired model.sdf file. )
|
||||
|
||||
|
||||
## Usability
|
||||
|
||||
The current implementation provides a minimal working example. More accurate measurements can be made by adjusting the chosen number of vortices along span and chord according to desired preferences. A good starting point for this can be found here: <https://www.redalyc.org/pdf/6735/673571173005.pdf>. Furthermore, one can also more accurately model a vehicle by using a larger number of sections. In the current .yml file, only a left and right edge are defined for each surface yielding exactly one section, but the code supports expanding this to any number of desired sections.
|
||||
|
||||
## IMPORTANT POINTS TO NOTE
|
||||
|
||||
- A control surface in AVL is always defined from left to right. This means you need to first provide the left edge of a surface and then the right edge. If you do this the opposite way around, a surface will essentially be defined upside down.
|
||||
- The tool is designed to only support at most two control surfaces of any type on any one vehicle. Having more surfaces than that can lead to faulty behavior.
|
||||
- Another important point is that these scripts make use of the match, case syntax, which was only introduced in Python in version 3.10.
|
||||
- The primary reference resource for AVL can be found at <https://web.mit.edu/drela/Public/web/avl/AVL_User_Primer.pdf>. This document was written by the creators of AVL and contains all the variables that could be required in defining the control surfaces.
|
||||
- AVL cannot predict stall values. As such these need to be calculated/estimated another way. In the current implementation, default stall values have been taken from PX4's Advanced Plane. These should naturally be changed for new/different models.
|
||||
|
||||
## Parameter Assignment
|
||||
|
||||
Below is a comprehensive list on how the parameters are assigned at output and what files in AVL they are taken from. I am by no means an AVL expert, so please verify that these are actually the correct parameters required by the Advanced Lift Drag Plugin. For an explanation of what the parameters do, please see take a look at the Advanced Lift Drag Plugin.
|
||||
|
||||
(name-in-AVL) -> (name-in-plugin)
|
||||
|
||||
From the stability derivatives log file, the following advanced lift drag plugin parameters are taken:
|
||||
|
||||
Alpha -> alpha The angle of attack
|
||||
|
||||
Cmtot -> Cem0 Pitching moment coefficient at zero angle of attack
|
||||
|
||||
CLtot -> CL0 Lift Coefficient at zero angle of attack
|
||||
|
||||
CDtot -> CD0 Drag coefficient at zero angle of attack
|
||||
|
||||
CLa -> CLa dCL/da (slope of CL-alpha curve)
|
||||
|
||||
CYa -> CYa dCy/da (sideforce slope wrt alpha)
|
||||
|
||||
Cla -> Cella dCl/da (roll moment slope wrt alpha)
|
||||
|
||||
Cma -> Cema dCm/da (pitching moment slope wrt alpha - before stall)
|
||||
|
||||
Cna -> Cena dCn/da (yaw moment slope wrt alpha)
|
||||
|
||||
CLb -> CLb dCL/dbeta (lift coefficient slope wrt beta)
|
||||
|
||||
CYb -> CYb dCY/dbeta (side force slope wrt beta)
|
||||
|
||||
Clb -> Cellb dCl/dbeta (roll moment slope wrt beta)
|
||||
|
||||
Cmb -> Cemb dCm/dbeta (pitching moment slope wrt beta)
|
||||
|
||||
Cnb -> Cenb dCn/dbeta (yaw moment slope wrt beta)
|
||||
|
||||
|
||||
From the body axis derivatives log file, the following advanced lift drag plugin parameters are taken:
|
||||
|
||||
e -> eff Wing efficiency (Oswald efficiency factor for a 3D wing)
|
||||
|
||||
CXp -> CDp dCD/dp (drag coefficient slope wrt roll rate)
|
||||
|
||||
CYp -> CYp dCY/dp (sideforce slope wrt roll rate)
|
||||
|
||||
CZp -> CLp dCL/dp (lift coefficient slope wrt roll rate)
|
||||
|
||||
Clp -> Cellp dCl/dp (roll moment slope wrt roll rate)
|
||||
|
||||
Cmp -> Cemp dCm/dp (pitching moment slope wrt roll rate)
|
||||
|
||||
Cmp -> Cenp dCn/dp (yaw moment slope wrt roll rate)
|
||||
|
||||
CXq -> CDq dCD/dq (drag coefficient slope wrt pitching rate)
|
||||
|
||||
CYq -> CYq dCY/dq (side force slope wrt pitching rate)
|
||||
|
||||
CZq -> CLq dCL/dq (lift coefficient slope wrt pitching rate)
|
||||
|
||||
Clq -> Cellq dCl/dq (roll moment slope wrt pitching rate)
|
||||
|
||||
Cmq -> Cemq dCm/dq (pitching moment slope wrt pitching rate)
|
||||
|
||||
Cnq -> Cenq dCn/dq (yaw moment slope wrt pitching rate)
|
||||
|
||||
CXr -> CDr dCD/dr (drag coefficient slope wrt yaw rate)
|
||||
|
||||
CYr -> CYr dCY/dr (side force slope wrt yaw rate)
|
||||
|
||||
CZr -> CLr dCL/dr (lift coefficient slope wrt yaw rate)
|
||||
|
||||
Clr -> Cellr dCl/dr (roll moment slope wrt yaw rate)
|
||||
|
||||
Cmr -> Cemr dCm/dr (pitching moment slope wrt yaw rate)
|
||||
|
||||
Cnr -> Cenr dCn/dr (yaw moment slope wrt yaw rate)
|
||||
|
||||
|
||||
Furthermore, every control surface also has six own parameters, which are also derived from this log file. {i} below ranges from 1 to the number of unique control surface types in the model.
|
||||
|
||||
CXd{i} -> CD_ctrl Effect of the control surface's deflection on drag
|
||||
|
||||
CYd{i} -> CY_ctrl Effect of the control surface's deflection on side force
|
||||
|
||||
CZd{i} -> CL_ctrl Effect of the control surface's deflection on lift
|
||||
|
||||
Cld{i} -> Cell_ctrl Effect of the control surface's deflection on roll moment
|
||||
|
||||
Cmd{i} -> Cem_ctrl Effect of the control surface's deflection on pitching moment
|
||||
|
||||
Cnd{i} -> Cen_ctrl Effect of the control surface's deflection on yaw moment
|
||||
|
||||
|
||||
## Future Work
|
||||
|
||||
The tool, while self-contained, could be expanded into multiple directions.
|
||||
|
||||
1. Currently hinge positions and gains are set at default levels, and these could, if desired be further customized for more control.
|
||||
2. More vehicles could be added to provide default templates that require less input. At the moment, only "custom" works completely.
|
||||
3. Fuselage modelling could be included to further improve the accuracy of calculated coefficients.
|
||||
4. At the moment only NACA airfoils are provided as a way to generate cambered surfaces. An alternative to this would be to use custom airfoil files.
|
||||
@@ -1,342 +0,0 @@
|
||||
#!/usr/bin/env
|
||||
|
||||
import argparse
|
||||
import shutil
|
||||
import fileinput
|
||||
import subprocess
|
||||
import os
|
||||
from typing import TextIO
|
||||
|
||||
|
||||
"""
|
||||
Get the desired coefficient from the AVL output files by looking through the file line by line and picking it out when encountered.
|
||||
|
||||
Args:
|
||||
file (TextIO): The file from which the desired coefficient should be read.
|
||||
token (str): The coefficient which to look for.
|
||||
|
||||
Return:
|
||||
value (str): The value associated with the desired coefficient.
|
||||
|
||||
"""
|
||||
def get_coef(file: TextIO,token: str) -> str:
|
||||
|
||||
linesplit = []
|
||||
for line in file:
|
||||
if f' {token} ' in line:
|
||||
linesplit = line.split()
|
||||
break
|
||||
|
||||
index = 0
|
||||
for i,v in enumerate(linesplit):
|
||||
if v == token:
|
||||
index = i
|
||||
value = linesplit[index+2]
|
||||
return value
|
||||
|
||||
|
||||
|
||||
"""
|
||||
Write all gathered, model-wide coefficients to the sdf file.
|
||||
|
||||
Args:
|
||||
file (TextIO): The file to which the desired coefficient should be written.
|
||||
token_str (str): The coefficients for which the associated value should be written.
|
||||
token (str): The value which should be placed in the avl.
|
||||
|
||||
Return:
|
||||
None.
|
||||
|
||||
"""
|
||||
def write_coef(file: TextIO, token_str: str, token: str):
|
||||
old_line = f'<{token_str}></{token_str}>'
|
||||
new_line = f'<{token_str}>{token}</{token_str}>'
|
||||
with fileinput.FileInput(file, inplace=True) as output_file:
|
||||
for line in output_file:
|
||||
print(line.replace(old_line, new_line), end='')
|
||||
|
||||
|
||||
|
||||
"""
|
||||
Write all gathered, control surface specific parameters to the sdf file.
|
||||
|
||||
Args:
|
||||
file (TextIO): The file to which the desired coefficients should be written.
|
||||
ctrl_surface_vec (list): A vector that contains all 6 necessary coefficient values for the control surface in question.
|
||||
index (str): The model-wide index number of the control surface in question.
|
||||
direction (str): The direction in which the control surface can be actuated.
|
||||
|
||||
Return:
|
||||
None.
|
||||
"""
|
||||
def ctrl_surface_coef(file: TextIO,ctrl_surface_vec: list,index: str, direction: str):
|
||||
|
||||
extracted_text = ''
|
||||
with open("./templates/control_surface.sdf",'r') as open_file:
|
||||
for line in open_file:
|
||||
extracted_text += line
|
||||
open_file.close()
|
||||
|
||||
# Insert necessary coefficient values, index and direction in correct sdf location.
|
||||
extracted_text = extracted_text.replace("<name></name>",f'<name>servo_{index}</name>')
|
||||
extracted_text = extracted_text.replace("<index></index>",f'<index>{index}</index>')
|
||||
extracted_text = extracted_text.replace("<direction></direction>",f'<directon>{direction}</direction>')
|
||||
extracted_text = extracted_text.replace("<CD_ctrl></CD_ctrl>",f'<CD_ctrl>{ctrl_surface_vec[0]}</CD_ctrl>')
|
||||
extracted_text = extracted_text.replace("<CY_ctrl></CY_ctrl>",f'<CY_ctrl>{ctrl_surface_vec[1]}</CY_ctrl>')
|
||||
extracted_text = extracted_text.replace("<CL_ctrl></CL_ctrl>",f'<CL_ctrl>{ctrl_surface_vec[2]}</CL_ctrl>')
|
||||
extracted_text = extracted_text.replace("<Cell_ctrl></Cell_ctrl>",f'<Cell_ctrl>{ctrl_surface_vec[3]}</Cell_ctrl>')
|
||||
extracted_text = extracted_text.replace("<Cem_ctrl></Cem_ctrl>",f'<Cem_ctrl>{ctrl_surface_vec[4]}</Cem_ctrl>')
|
||||
extracted_text = extracted_text.replace("<Cen_ctrl></Cen_ctrl>",f'<Cen_ctrl>{ctrl_surface_vec[5]}</Cen_ctrl>')
|
||||
|
||||
|
||||
# Create model specific template
|
||||
with open(file,'a') as plugin_file:
|
||||
plugin_file.write(extracted_text + "\n")
|
||||
plugin_file.close()
|
||||
|
||||
"""
|
||||
Read out the necessary log files to gather the desired parameters and write them to the sdf plugin file.
|
||||
Arguments provided here are passed in the input_avl.py file.
|
||||
|
||||
Args:
|
||||
file_name (TextIO): The file to which the desired coefficients should be written.
|
||||
vehicle_type (str): The type of vehicle in use.
|
||||
AR (str): The calculated aspect ratio.
|
||||
mac (str): The calculated mean aerodynamic chord.
|
||||
ref_pt_x (str): The x coordinate of the reference point, at which forces and moments are applied.
|
||||
ref_pt_y (str): The y coordinate of the reference point, at which forces and moments are applied.
|
||||
ref_pt_z (str): The z coordinate of the reference point, at which forces and moments are applied.
|
||||
num_ctrl_surfaces (str): The number of control surfaces that the model uses.
|
||||
area (str): The wing surface area.
|
||||
ctrl_surface_order (list): A list containing the types of control surfaces, in theorder in which
|
||||
they have been defined in the .avl file.
|
||||
avl_path (str): A string containing the directory where the AVL directory should be moved to.
|
||||
|
||||
Return:
|
||||
None.
|
||||
"""
|
||||
|
||||
def main(file_name: TextIO, vehicle_type: str, AR: str, mac: str, ref_pt_x: str, ref_pt_y: str, ref_pt_z: str, num_ctrl_surfaces: str, area: str, ctrl_surface_order: list, avl_path:str):
|
||||
|
||||
# Set current path for user
|
||||
curr_path = subprocess.run(['pwd'], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
|
||||
|
||||
if curr_path.returncode == 0:
|
||||
# Save the output in a variable
|
||||
savedir = curr_path.stdout.strip()
|
||||
else:
|
||||
raise LookupError("Invalid path to directory. Check both the avl_automation directory and the Avl directory are positioned correctly.")
|
||||
|
||||
# Set the file directory path from where the AVL output logs can be read.
|
||||
filedir = f'{avl_path}Avl/runs/'
|
||||
|
||||
# Read out all necessary parameters from the stability and body axis derivatives files.
|
||||
with open(f'{filedir}custom_vehicle_stability_derivatives.txt','r+') as stability_file:
|
||||
original_position = stability_file.tell()
|
||||
|
||||
# As plane is modelled at 0 degree AoA, the total coefficients should(?) correspond to the
|
||||
# 0 degree coefficients required by the plugin.
|
||||
alpha = get_coef(stability_file,"Alpha")
|
||||
Cem0 = get_coef(stability_file,"Cmtot")
|
||||
CL0 = get_coef(stability_file,"CLtot")
|
||||
CD0 = get_coef(stability_file,"CDtot")
|
||||
|
||||
CLa = get_coef(stability_file,"CLa")
|
||||
CYa = get_coef(stability_file,"CYa")
|
||||
Cella = get_coef(stability_file,"Cla")
|
||||
Cema = get_coef(stability_file,"Cma")
|
||||
Cena = get_coef(stability_file,"Cna")
|
||||
|
||||
stability_file.seek(original_position)
|
||||
|
||||
CLb = get_coef(stability_file,"CLb")
|
||||
CYb = get_coef(stability_file,"CYb")
|
||||
Cellb = get_coef(stability_file,"Clb")
|
||||
Cemb = get_coef(stability_file,"Cmb")
|
||||
Cenb = get_coef(stability_file,"Cnb")
|
||||
stability_file.close()
|
||||
|
||||
with open(f'{filedir}custom_vehicle_body_axis_derivatives.txt') as bodyax_file:
|
||||
original_position = bodyax_file.tell()
|
||||
|
||||
eff = get_coef(bodyax_file,"e")
|
||||
|
||||
bodyax_file.seek(original_position)
|
||||
|
||||
CDp = get_coef(bodyax_file,"CXp")
|
||||
CYp = get_coef(bodyax_file,"CYp")
|
||||
CLp = get_coef(bodyax_file,"CZp")
|
||||
Cellp = get_coef(bodyax_file,"Clp")
|
||||
Cemp = get_coef(bodyax_file,"Cmp")
|
||||
Cenp = get_coef(bodyax_file,"Cnp")
|
||||
|
||||
bodyax_file.seek(original_position)
|
||||
|
||||
CDq = get_coef(bodyax_file,"CXq")
|
||||
CYq = get_coef(bodyax_file,"CYq")
|
||||
CLq = get_coef(bodyax_file,"CZq")
|
||||
Cellq = get_coef(bodyax_file,"Clq")
|
||||
Cemq = get_coef(bodyax_file,"Cmq")
|
||||
Cenq = get_coef(bodyax_file,"Cnq")
|
||||
|
||||
bodyax_file.seek(original_position)
|
||||
|
||||
CDr = get_coef(bodyax_file,"CXr")
|
||||
CYr = get_coef(bodyax_file,"CYr")
|
||||
CLr = get_coef(bodyax_file,"CZr")
|
||||
Cellr = get_coef(bodyax_file,"Clr")
|
||||
Cemr = get_coef(bodyax_file,"Cmr")
|
||||
Cenr = get_coef(bodyax_file,"Cnr")
|
||||
bodyax_file.close()
|
||||
|
||||
plane_type = vehicle_type
|
||||
ctrl_surface_mat = []
|
||||
|
||||
# Maybe in the future you want more types of set aircraft. Thus us a case differentiator.
|
||||
match plane_type:
|
||||
|
||||
case "custom":
|
||||
ctrl_surface_vec = []
|
||||
with open(f'{filedir}custom_vehicle_body_axis_derivatives.txt') as bodyax_file:
|
||||
original_position = bodyax_file.tell()
|
||||
for i in range(1,(len(set(ctrl_surface_order)))+1):
|
||||
ctrl_surface_vec = []
|
||||
ctrl_surface_vec.append(get_coef(bodyax_file,f'CXd{i}'))
|
||||
ctrl_surface_vec.append(get_coef(bodyax_file,f'CYd{i}'))
|
||||
ctrl_surface_vec.append(get_coef(bodyax_file,f'CZd{i}'))
|
||||
ctrl_surface_vec.append(get_coef(bodyax_file,f'Cld{i}'))
|
||||
ctrl_surface_vec.append(get_coef(bodyax_file,f'Cmd{i}'))
|
||||
ctrl_surface_vec.append(get_coef(bodyax_file,f'Cnd{i}'))
|
||||
bodyax_file.seek(original_position)
|
||||
ctrl_surface_mat.append(ctrl_surface_vec)
|
||||
|
||||
|
||||
# SPECIFY STALL PARAMETERS BASED ON AIRCRAFT TYPE (IF PROVIDED)
|
||||
if not os.path.exists(f'{savedir}/{file_name}'):
|
||||
os.makedirs(f'{savedir}/{file_name}')
|
||||
file_name = f'{savedir}/{file_name}/{file_name}.sdf'
|
||||
shutil.copy(f'{savedir}/templates/advanced_lift_drag_template.sdf',file_name)
|
||||
|
||||
# Get argument coefficients taken directly from the input file.
|
||||
write_coef(file_name,"a0",alpha)
|
||||
write_coef(file_name,"CL0",CL0)
|
||||
write_coef(file_name,"CD0",CD0)
|
||||
write_coef(file_name,"Cem0",Cem0)
|
||||
write_coef(file_name,"AR",AR)
|
||||
write_coef(file_name,"area",area)
|
||||
write_coef(file_name,"mac",mac)
|
||||
write_coef(file_name,"air_density",1.2041) # TODO: Provide custom air density option
|
||||
write_coef(file_name,"forward","1 0 0")
|
||||
write_coef(file_name,"upward","0 0 1")
|
||||
write_coef(file_name,"link_name","base_link")
|
||||
write_coef(file_name,"cp",f'{ref_pt_x} {ref_pt_y} {ref_pt_z}')
|
||||
write_coef(file_name,"num_ctrl_surfaces",num_ctrl_surfaces)
|
||||
|
||||
write_coef(file_name,"CLa",CLa)
|
||||
write_coef(file_name,"CYa",CYa)
|
||||
write_coef(file_name,"Cella",Cella)
|
||||
write_coef(file_name,"Cema",Cema)
|
||||
write_coef(file_name,"Cena",Cena)
|
||||
write_coef(file_name,"CLb",CLb)
|
||||
write_coef(file_name,"CYb",CYb)
|
||||
write_coef(file_name,"Cellb",Cellb)
|
||||
write_coef(file_name,"Cemb",Cemb)
|
||||
write_coef(file_name,"Cenb",Cenb)
|
||||
|
||||
write_coef(file_name,"CDp",CDp)
|
||||
write_coef(file_name,"CYp",CYp)
|
||||
write_coef(file_name,"CLp",CLp)
|
||||
write_coef(file_name,"Cellp",Cellp)
|
||||
write_coef(file_name,"Cemp",Cemp)
|
||||
write_coef(file_name,"Cenp",Cenp)
|
||||
write_coef(file_name,"CDq",CDq)
|
||||
write_coef(file_name,"CYq",CYq)
|
||||
write_coef(file_name,"CLq",CLq)
|
||||
write_coef(file_name,"Cellq",Cellq)
|
||||
write_coef(file_name,"Cemq",Cemq)
|
||||
write_coef(file_name,"Cenq",Cenq)
|
||||
write_coef(file_name,"CDr",CDr)
|
||||
write_coef(file_name,"CYr",CYr)
|
||||
write_coef(file_name,"CLr",CLr)
|
||||
write_coef(file_name,"Cellr",Cellr)
|
||||
write_coef(file_name,"Cemr",Cemr)
|
||||
write_coef(file_name,"Cenr",Cenr)
|
||||
|
||||
write_coef(file_name,"eff",eff)
|
||||
|
||||
# TODO: Improve this for custom stall values
|
||||
# Note: Currently these stall values are simply taken from advanced_plane presets.
|
||||
|
||||
write_coef(file_name,"alpha_stall","0.3391428111")
|
||||
write_coef(file_name,"CLa_stall","-3.85")
|
||||
write_coef(file_name,"CDa_stall","-0.9233984055")
|
||||
write_coef(file_name,"Cema_stall","0")
|
||||
|
||||
# Check whether a particular type of control surface has been seen before. If it has,
|
||||
# then the current control surface is the (right) counterpart.
|
||||
|
||||
# ASSUMPTION: There is the assumption that an vehicle will only ever have two of any
|
||||
# particular type of control surface. (left and right). If this is not the case, the negation
|
||||
# below will likely not work correctly.
|
||||
type_seen = list()
|
||||
|
||||
# Dictionary containing the directions that each type of control surface can move.
|
||||
ctrl_direction = {"aileron": 1,"elevator": -1,"rudder": 1}
|
||||
|
||||
# More set types in the future?
|
||||
match plane_type:
|
||||
|
||||
case "custom":
|
||||
for i, ctrl_surface in enumerate(ctrl_surface_order):
|
||||
|
||||
# Check whether a particular type of control surface has been seen before. If it has,
|
||||
# then the current control surface is the (right) counterpart. Depending on the exact
|
||||
# nature of the encountered type you then need to negate the correct parameters.
|
||||
if ctrl_surface in type_seen:
|
||||
# Work out what the corresponding index for the first encounter of the ctrl surface is.
|
||||
seen_index = type_seen.index(ctrl_surface)
|
||||
|
||||
if ctrl_surface == 'aileron':
|
||||
#Change for right wing aileron by flipping sign
|
||||
ctrl_surface_mat[seen_index][3] = -float(ctrl_surface_mat[0][3])
|
||||
ctrl_surface_mat[seen_index][5] = -float(ctrl_surface_mat[0][5])
|
||||
|
||||
# Split Elevators are assumed to never run differentially. Feel free to add a
|
||||
# condition if your plane does require differential elevator action.
|
||||
|
||||
else:
|
||||
# If a ctrl surface has not been encountered add it to the type_seen list and
|
||||
# set the index to the length of the list - 1 as this corresponds to the newest
|
||||
# unseen element in ctrl_surface_mat .
|
||||
type_seen.append(ctrl_surface)
|
||||
seen_index = len(type_seen) - 1
|
||||
|
||||
ctrl_surface_coef(file_name,ctrl_surface_mat[seen_index],i,ctrl_direction[ctrl_surface])
|
||||
|
||||
|
||||
# close the sdf file with plugin
|
||||
with open(file_name,'a') as plugin_file:
|
||||
plugin_file.write("</plugin>")
|
||||
plugin_file.close()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
parser = argparse.ArgumentParser()
|
||||
|
||||
parser.add_argument("file_name", help="The file to which the desired coefficients should be written.")
|
||||
parser.add_argument("vehicle_type", help="The type of vehicle in use.")
|
||||
parser.add_argument("AR", help="The calculated aspect ratio.")
|
||||
parser.add_argument("mac", help="The calculated mean aerodynamic chord.")
|
||||
parser.add_argument("ref_pt_x", help="The x coordinate of the reference point, at which forces and moments are applied.")
|
||||
parser.add_argument("ref_pt_y", help="The y coordinate of the reference point, at which forces and moments are applied.")
|
||||
parser.add_argument("ref_pt_z", help="The z coordinate of the reference point, at which forces and moments are applied.")
|
||||
parser.add_argument("num_ctrl_surfaces", help="The number of control surfaces that the model uses.")
|
||||
parser.add_argument("area", help= "The wing surface area.")
|
||||
parser.add_argument("ctrl_surface_order", help=" A list containing the types of control surfaces, in theorder in which \
|
||||
they have been defined in the .avl file.")
|
||||
parser.add_argument("avl_path",help="A string containing the directory where the AVL directory should be moved to.")
|
||||
|
||||
args = parser.parse_args()
|
||||
|
||||
main(args.file_name,args.vehicle_type,args.AR,args.mac,args.ref_pt_x,args.ref_pt_y,
|
||||
args.ref_pt_z,args.num_ctrl_surfaces,args.area,args.ctrl_surface_order,args.avl_path)
|
||||
@@ -1,10 +0,0 @@
|
||||
oper
|
||||
x
|
||||
n custom_plane
|
||||
st custom_vehicle_stability_derivatives.txt
|
||||
sb custom_vehicle_body_axis_derivatives.txt
|
||||
g
|
||||
h
|
||||
|
||||
|
||||
quit
|
||||
@@ -1,142 +0,0 @@
|
||||
# Enter a name for your vehicle
|
||||
vehicle_name: plane_example_2
|
||||
|
||||
# Enter the type of airframe you would like to use:
|
||||
frame_type: custom
|
||||
|
||||
# First define some model-wide parameters for custom models:
|
||||
reference_area: 12
|
||||
wing_span: 15
|
||||
# Provide a reference point at which the forces and moments generated will act.
|
||||
reference_point:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
|
||||
#Provide information on each of the Control Surfaces
|
||||
num_ctrl_surfaces: 4
|
||||
control_surfaces:
|
||||
- name: right_wing
|
||||
type: aileron
|
||||
nchord: 1
|
||||
cspace: 1
|
||||
nspan: 16
|
||||
sspace: -2
|
||||
angle: 4
|
||||
translation:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
naca: 2412
|
||||
sections:
|
||||
- name: section_1
|
||||
position:
|
||||
X: -0.25
|
||||
Y: 0
|
||||
Z: 0
|
||||
chord: 1
|
||||
ainc: 0
|
||||
nspan: 8
|
||||
sspace: 1
|
||||
- name: section_2
|
||||
position:
|
||||
X: -0.175
|
||||
Y: 5
|
||||
Z: 0.5
|
||||
chord: 0.7
|
||||
ainc: 0
|
||||
nspan: 0
|
||||
sspace: 0
|
||||
|
||||
|
||||
- name: left_wing
|
||||
type: aileron
|
||||
nchord: 1
|
||||
cspace: 1
|
||||
nspan: 16
|
||||
sspace: -2
|
||||
angle: 4
|
||||
translation:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
naca: 2412
|
||||
sections:
|
||||
- name: section_1
|
||||
position:
|
||||
X: -0.175
|
||||
Y: -5
|
||||
Z: 0.5
|
||||
chord: 0.7
|
||||
ainc: 0
|
||||
nspan: 0
|
||||
sspace: 0
|
||||
- name: section_2
|
||||
position:
|
||||
X: -0.25
|
||||
Y: 0
|
||||
Z: 0
|
||||
chord: 1
|
||||
ainc: 0
|
||||
nspan: 8
|
||||
sspace: 1
|
||||
|
||||
- name: elevator
|
||||
type: elevator
|
||||
nchord: 1
|
||||
cspace: 1
|
||||
nspan: 7
|
||||
sspace: -2
|
||||
translation:
|
||||
X: 6
|
||||
Y: 0
|
||||
Z: 0.5
|
||||
sections:
|
||||
- name: section_1
|
||||
position:
|
||||
X: -0.1
|
||||
Y: 0
|
||||
Z: 0
|
||||
chord: 0.4
|
||||
ainc: 0
|
||||
nspan: 7
|
||||
sspace: -1.25
|
||||
- name: section_2
|
||||
position:
|
||||
X: -0.075
|
||||
Y: 2
|
||||
Z: 0
|
||||
chord: 0.3
|
||||
ainc: 0
|
||||
nspan: 0
|
||||
sspace: 0
|
||||
|
||||
- name: fin
|
||||
type: rudder
|
||||
nchord: 1
|
||||
cspace: 1
|
||||
nspan: 10
|
||||
sspace: 1
|
||||
translation:
|
||||
X: 6
|
||||
Y: 0
|
||||
Z: 0.5
|
||||
sections:
|
||||
- name: section_1
|
||||
position:
|
||||
X: -0.1
|
||||
Y: 0
|
||||
Z: 0
|
||||
chord: 0.4
|
||||
ainc: 0
|
||||
nspan: 7
|
||||
sspace: -1.25
|
||||
- name: section_2
|
||||
position:
|
||||
X: -0.075
|
||||
Y: 0
|
||||
Z: 1
|
||||
chord: 0.3
|
||||
ainc: 0
|
||||
nspan: 0
|
||||
sspace: 0
|
||||
@@ -1,314 +0,0 @@
|
||||
#!/usr/bin/env
|
||||
|
||||
import argparse
|
||||
import avl_out_parse
|
||||
import os
|
||||
import yaml
|
||||
import subprocess
|
||||
import shutil
|
||||
|
||||
"""
|
||||
Write individual airfoil section definitions to the .avl file.
|
||||
Sections are defined through a 3D point in space and assigned properties such as chord, angle of incidence etc.
|
||||
AVL then links them up to the other sections of a particular surface. You can define any number of sections for
|
||||
a particular surface, but there always have to be at least two (a left and right edge).
|
||||
|
||||
Args:
|
||||
plane_name (str): The name of the vehicle.
|
||||
x (str): The x coordinate of the section.
|
||||
y (str): The y coordinate of the section.
|
||||
z (str): The z coordinate of the section.
|
||||
chord (str): Chord in this section of the surface. Trailing edge is at x + chord, y, z.
|
||||
ainc (str): Angle of incidence for this section. Taken as a rotation (RH rule) about the surface's
|
||||
spanwise axis projected onto the Y-Z plane.
|
||||
nspan (str): Number of spanwise vortices in until the next section.
|
||||
sspan (str): Controls the spanwise spacing of the vortices.
|
||||
naca_number (str): The chosen NACA number that will define the cambered properties of this section
|
||||
of the surface. For help picking an airfoil go to: http://airfoiltools.com/airfoil/naca4digit.
|
||||
ctrl_surface_type: The selected type of control surface. This should be consistent along the entirety of
|
||||
the surface. (Question: Flap and Aileron along the same airfoil?)
|
||||
|
||||
Return:
|
||||
None.
|
||||
|
||||
"""
|
||||
def write_section(plane_name: str,x: str,y: str,z: str,chord: str,ainc: str,nspan: str,sspace: str,naca_number: str,ctrl_surf_type: str):
|
||||
|
||||
with open(f'{plane_name}.avl','a') as avl_file:
|
||||
avl_file.write("SECTION \n")
|
||||
avl_file.write("!Xle Yle Zle Chord Ainc Nspanwise Sspace \n")
|
||||
avl_file.write(f'{x} {y} {z} {chord} {ainc} {nspan} {sspace} \n')
|
||||
if naca_number != "0000":
|
||||
avl_file.write("NACA \n")
|
||||
avl_file.write(f'{naca_number} \n')
|
||||
avl_file.close()
|
||||
|
||||
match ctrl_surf_type:
|
||||
case 'aileron':
|
||||
#TODO provide custom options for gain and hinge positions
|
||||
with open(f'{plane_name}.avl','a') as avl_file:
|
||||
avl_file.write("CONTROL \n")
|
||||
avl_file.write("aileron 1.0 0.0 0.0 0.0 0.0 -1 \n")
|
||||
avl_file.close()
|
||||
|
||||
case 'elevator':
|
||||
with open(f'{plane_name}.avl','a') as avl_file:
|
||||
avl_file.write("CONTROL \n")
|
||||
avl_file.write("elevator 1.0 0.0 0.0 0.0 0.0 1 \n")
|
||||
avl_file.close()
|
||||
|
||||
case 'rudder':
|
||||
with open(f'{plane_name}.avl','a') as avl_file:
|
||||
avl_file.write("CONTROL \n")
|
||||
avl_file.write("rudder 1.0 0.0 0.0 0.0 0.0 1 \n")
|
||||
avl_file.close()
|
||||
|
||||
|
||||
|
||||
"""
|
||||
Read the provided yaml file and generate the corresponding .avl file that can be read into AVL.
|
||||
Also calls AVL and the avl_out_parse.py file that generates the sdf plugin.
|
||||
|
||||
Args:
|
||||
yaml_file: Path to the input yaml file
|
||||
avl_path: Set the avl_path to provide a desired directory for where Avl should be located.
|
||||
|
||||
Return:
|
||||
None
|
||||
|
||||
"""
|
||||
def main():
|
||||
user = os.environ.get('USER')
|
||||
# This will find Avl on a users machine.
|
||||
for root, dirs, _ in os.walk(f'/home/{user}/'):
|
||||
if "Avl" in dirs:
|
||||
target_directory_path = os.path.join(root, "Avl")
|
||||
break
|
||||
parent_directory_path = os.path.dirname(target_directory_path)
|
||||
filedir = f'{parent_directory_path}/'
|
||||
print(filedir)
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument("--yaml_file", help="Path to input yaml file.")
|
||||
parser.add_argument("--avl_path", default=filedir, help="Provide an absolute AVL path. If this argument is passed, AVL will be moved there and the files will adjust their paths accordingly.")
|
||||
inputs = parser.parse_args()
|
||||
|
||||
|
||||
# If the user passes the avl_path argument then move Avl to that location:
|
||||
if inputs.avl_path != filedir:
|
||||
|
||||
#Check if the directory is already there
|
||||
if os.path.exists(f'{inputs.avl_path}/Avl') and os.path.isdir(f'{inputs.avl_path}/Avl'):
|
||||
print("Avl is already at desired location")
|
||||
else:
|
||||
shutil.move(f'{filedir}Avl',inputs.avl_path)
|
||||
|
||||
# Adjust paths to AVL in process.sh
|
||||
print("Adjusting paths")
|
||||
with open("./process.sh", "r") as file:
|
||||
all_lines = file.readlines()
|
||||
file.close()
|
||||
|
||||
it = 0
|
||||
for line in all_lines:
|
||||
if "cp $DIR_PATH/$CUSTOM_MODEL.avl" in line:
|
||||
new_line = f'cp $DIR_PATH/$CUSTOM_MODEL.avl {inputs.avl_path}Avl/runs\n'
|
||||
all_lines[it] = new_line
|
||||
|
||||
if "/Avl/runs/plot.ps $DIR_PATH/" in line:
|
||||
new_line =f'mv {inputs.avl_path}Avl/runs/plot.ps $DIR_PATH/\n'
|
||||
all_lines[it] = new_line
|
||||
|
||||
if "cd" in line and "/Avl/runs" in line:
|
||||
new_line = f'cd {inputs.avl_path}Avl/runs\n'
|
||||
all_lines[it] = new_line
|
||||
it += 1
|
||||
|
||||
with open("./process.sh", "w") as file:
|
||||
file.writelines(all_lines)
|
||||
file.close()
|
||||
|
||||
|
||||
with open(inputs.yaml_file,'r') as yaml_file:
|
||||
yaml_data = yaml.safe_load(yaml_file)
|
||||
|
||||
airframes = ['cessna','standard_vtol','custom']
|
||||
plane_name = yaml_data['vehicle_name']
|
||||
frame_type = yaml_data['frame_type']
|
||||
if not frame_type in airframes:
|
||||
raise ValueError("\nThis is not a valid airframe, please choose a valid airframe. \n")
|
||||
|
||||
# Parameters that need to be provided:
|
||||
# General
|
||||
# - Reference Area (Sref)
|
||||
# - Wing span (Bref) (wing span squared / area = aspect ratio which is a required parameter for the sdf file)
|
||||
# - Reference point (X,Y,Zref) point at which moments and forces are calculated
|
||||
#Control Surface specific
|
||||
# - type (select from options; aileron,elevator,rudder)
|
||||
# - nchord
|
||||
# - cspace
|
||||
# - nspanwise
|
||||
# - sspace
|
||||
# - x,y,z 1. (section)
|
||||
# - chord 1. (section)
|
||||
# - ainc 1. (section)
|
||||
# - Nspan 1. (optional for section)
|
||||
# - sspace 1. (optional for section)
|
||||
# - x,y,z 2. (section)
|
||||
# - chord 2. (section)
|
||||
# - ainc 2. (section)
|
||||
# - Nspan 2. (optional for section)
|
||||
# - sspace 2. (optional for section)
|
||||
|
||||
# TODO: Find out if elevons are defined
|
||||
ctrl_surface_types = ['aileron','elevator','rudder']
|
||||
# - Reference Chord (Cref) (= area/wing span)
|
||||
delineation = '!***************************************'
|
||||
sec_demark = '#--------------------------------------------------'
|
||||
num_ctrl_surfaces = 0
|
||||
ctrl_surface_order = []
|
||||
area = 0
|
||||
span = 0
|
||||
|
||||
ref_pt_x = None
|
||||
ref_pt_y = None
|
||||
ref_pt_z = None
|
||||
|
||||
# Future work: Provide some pre-worked frames for a Cessna and standard VTOL if there is a need for it
|
||||
match frame_type:
|
||||
|
||||
case "custom":
|
||||
|
||||
# These parameters are consistent across all models.
|
||||
# At the moment we do not use any symmetry axis for mirroring.
|
||||
with open(f'{plane_name}.avl','w') as avl_file:
|
||||
avl_file.write(f'{delineation} \n')
|
||||
avl_file.write(f'!{plane_name} input dataset \n')
|
||||
avl_file.write(f'{delineation} \n')
|
||||
avl_file.write(f'{plane_name} \n')
|
||||
avl_file.write('!Mach \n0.0 \n')
|
||||
avl_file.write('!IYsym IZsym Zsym \n')
|
||||
avl_file.write('0 0 0 \n')
|
||||
avl_file.close()
|
||||
|
||||
# First define some model-specific parameters for custom models
|
||||
area = yaml_data["reference_area"]
|
||||
span = yaml_data["wing_span"]
|
||||
ref_pt_x = yaml_data["reference_point"]["X"]
|
||||
ref_pt_y = yaml_data["reference_point"]["Y"]
|
||||
ref_pt_z = yaml_data["reference_point"]["Z"]
|
||||
|
||||
if(span != 0 and area != 0):
|
||||
ref_chord = float(area)/float(span)
|
||||
else:
|
||||
raise ValueError("Invalid reference chord value. Check area and wing span values.")
|
||||
|
||||
# Write the gathered model-wide parameters into the .avl file
|
||||
with open(f'{plane_name}.avl','a') as avl_file:
|
||||
avl_file.write('!Sref Cref Bref \n')
|
||||
avl_file.write(f'{area} {str(ref_chord)} {span} \n')
|
||||
avl_file.write('!Xref Yref Zref \n')
|
||||
avl_file.write(f'{ref_pt_x} {ref_pt_y} {ref_pt_z} \n')
|
||||
avl_file.close()
|
||||
|
||||
num_ctrl_surfaces = yaml_data["num_ctrl_surfaces"]
|
||||
for i, control_surface in enumerate(yaml_data["control_surfaces"]):
|
||||
|
||||
# Wings always need to be defined from left to right
|
||||
ctrl_surf_name = control_surface['name']
|
||||
ctrl_surf_type = control_surface['type']
|
||||
if ctrl_surf_type not in ctrl_surface_types:
|
||||
raise ValueError(f'The selected type is invalid. Available types are: {ctrl_surface_types}')
|
||||
|
||||
# The order of control surfaces becomes important in the output parsing
|
||||
# to correctly assign derivatives to particular surfaces.
|
||||
ctrl_surface_order.append(ctrl_surf_type)
|
||||
|
||||
nchord = control_surface["nchord"]
|
||||
cspace = control_surface["cspace"]
|
||||
nspanwise = control_surface["nspan"]
|
||||
sspace = control_surface["sspace"]
|
||||
|
||||
# TODO: Add more control surface types that also require Angles.
|
||||
if ctrl_surf_type.lower() == 'aileron':
|
||||
angle = control_surface["angle"]
|
||||
|
||||
#Translation of control surface, will move the whole surface to specified position
|
||||
tx = control_surface["translation"]["X"]
|
||||
ty = control_surface["translation"]["Y"]
|
||||
tz = control_surface["translation"]["Z"]
|
||||
|
||||
# Write common part of this surface to .avl file
|
||||
with open(f'{plane_name}.avl','a') as avl_file:
|
||||
avl_file.write(sec_demark)
|
||||
avl_file.write("\nSURFACE \n")
|
||||
avl_file.write(f'{ctrl_surf_name} \n')
|
||||
avl_file.write("!Nchordwise Cspace Nspanwise Sspace \n")
|
||||
avl_file.write(f'{nchord} {cspace} {nspanwise} {sspace} \n')
|
||||
|
||||
# If we have a elevator, we can duplicate the defined control surface along the y-axis of the model
|
||||
# as both sides are generally modelled and controlled as one in simulation. Adjust for split elevators if desired.
|
||||
if ctrl_surf_type.lower() == 'elevator':
|
||||
avl_file.write("\nYDUPLICATE\n")
|
||||
avl_file.write("0.0\n\n")
|
||||
|
||||
# Elevators and Rudders do not require an angle of incidence.
|
||||
if ctrl_surf_type.lower() == 'aileron':
|
||||
avl_file.write("ANGLE \n")
|
||||
avl_file.write(f'{angle} \n')
|
||||
|
||||
# Translate the surface to a particular position in space.
|
||||
avl_file.write("TRANSLATE \n")
|
||||
avl_file.write(f'{tx} {ty} {tz} \n')
|
||||
avl_file.close()
|
||||
|
||||
|
||||
# Define NACA airfoil shape.
|
||||
# For help picking an airfoil go to: http://airfoiltools.com/airfoil/naca4digit
|
||||
# NOTE: AVL can only use 4-digit NACA codes.
|
||||
if ctrl_surf_type.lower() == "aileron":
|
||||
naca_number = control_surface["naca"]
|
||||
else:
|
||||
# Provide a default NACA number for unused airfoils
|
||||
naca_number = '0000'
|
||||
|
||||
# Iterating over each defined section for the control surface. There need to be at least
|
||||
# two in order to define a left and right edge, but there is no upper limit.
|
||||
# CRITICAL: ALWAYS DEFINE YOUR SECTION FROM LEFT TO RIGHT
|
||||
for j, section in enumerate(control_surface["sections"]):
|
||||
|
||||
print(f'Defining {j}. section of {i+1}. control surface \n')
|
||||
y = section["position"]["Y"]
|
||||
z = section["position"]["Z"]
|
||||
x = section["position"]["X"]
|
||||
chord = section["chord"]
|
||||
ainc = section["ainc"]
|
||||
nspan = section["nspan"]
|
||||
write_section(plane_name,x,y,z,chord,ainc,nspan,sspace,naca_number,ctrl_surf_type)
|
||||
|
||||
print(f'\nPARAMETER DEFINITION FOR {i+1}. CONTROL SURFACE COMPLETED \n')
|
||||
|
||||
|
||||
# Calculation of Aspect Ratio (AR) and Mean Aerodynamic Chord (mac)
|
||||
AR = str((float(span)*float(span))/float(area))
|
||||
mac = str((2/3)*(float(area)/float(span)))
|
||||
|
||||
# Call shell script that will pass the generated .avl file to AVL
|
||||
os.system(f'./process.sh {plane_name}')
|
||||
|
||||
# Call main function of avl parse script to parse the generated AVL files.
|
||||
avl_out_parse.main(plane_name,frame_type,AR,mac,ref_pt_x,ref_pt_y,ref_pt_z,num_ctrl_surfaces,area,ctrl_surface_order,inputs.avl_path)
|
||||
|
||||
# Finally move all generated files to a new directory and show the generated geometry image:
|
||||
result = subprocess.run(['pwd'], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
|
||||
|
||||
if result.returncode == 0:
|
||||
# Save the output in a variable
|
||||
current_path = result.stdout.strip()
|
||||
|
||||
# Run image plot from avl_automation directory.
|
||||
os.system(f'mv ./{plane_name}.* ./{plane_name}' )
|
||||
os.system(f'evince {current_path}/{plane_name}/{plane_name}.ps')
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
@@ -1,27 +0,0 @@
|
||||
#!/bin/bash
|
||||
CUSTOM_MODEL=$1
|
||||
DIR_PATH=$(pwd)
|
||||
|
||||
cp $DIR_PATH/$CUSTOM_MODEL.avl /home/$USER/Avl/runs/
|
||||
cd
|
||||
cd /home/$USER/Avl/runs
|
||||
|
||||
old_stability_derivatives="custom_vehicle_stability_derivatives.txt"
|
||||
old_body_ax_derivatives="custom_vehicle_body_axis_derivatives.txt"
|
||||
|
||||
if [ -e "$old_stability_derivatives" ]; then
|
||||
# Delete old stability derivative file
|
||||
rm "$old_stability_derivatives"
|
||||
fi
|
||||
if [ -e "$old_body_ax_derivatives" ]; then
|
||||
# Delete old body_axis derivative file
|
||||
rm "$old_body_ax_derivatives"
|
||||
fi
|
||||
|
||||
#avl_steps.txt can be used to run commands on the AVL commandline.
|
||||
../bin/avl $CUSTOM_MODEL.avl < $DIR_PATH/avl_steps.txt
|
||||
echo "\n"
|
||||
|
||||
#After completion move the plot to avl_automation directory
|
||||
mv /home/$USER/Avl/runs/plot.ps $DIR_PATH/
|
||||
mv $DIR_PATH/plot.ps $DIR_PATH/$CUSTOM_MODEL.ps
|
||||
@@ -1,43 +0,0 @@
|
||||
<plugin filename="gz-sim-advanced-lift-drag-system" name="gz::sim::systems::AdvancedLiftDrag">
|
||||
<a0></a0>
|
||||
<CL0></CL0>
|
||||
<AR></AR>
|
||||
<eff></eff>
|
||||
<CLa></CLa>
|
||||
<CD0></CD0>
|
||||
<Cem0></Cem0>
|
||||
<Cema></Cema>
|
||||
<CYb></CYb>
|
||||
<Cellb></Cellb>
|
||||
<Cenb></Cenb>
|
||||
<CDp></CDp>
|
||||
<CYp></CYp>
|
||||
<CLp></CLp>
|
||||
<Cellp></Cellp>
|
||||
<Cemp></Cemp>
|
||||
<Cenp></Cenp>
|
||||
<CDq></CDq>
|
||||
<CYq></CYq>
|
||||
<CLq></CLq>
|
||||
<Cellq></Cellq>
|
||||
<Cemq></Cemq>
|
||||
<Cenq></Cenq>
|
||||
<CDr></CDr>
|
||||
<CYr></CYr>
|
||||
<CLr></CLr>
|
||||
<Cellr></Cellr>
|
||||
<Cemr></Cemr>
|
||||
<Cenr></Cenr>
|
||||
<alpha_stall></alpha_stall>
|
||||
<CLa_stall></CLa_stall>
|
||||
<CDa_stall></CDa_stall>
|
||||
<Cema_stall></Cema_stall>
|
||||
<cp></cp>
|
||||
<area></area>
|
||||
<mac></mac>
|
||||
<air_density></air_density>
|
||||
<forward></forward>
|
||||
<upward></upward>
|
||||
<link_name></link_name>
|
||||
<num_ctrl_surfaces></num_ctrl_surfaces>
|
||||
|
||||
@@ -1,11 +0,0 @@
|
||||
<control_surface>
|
||||
<name></name>
|
||||
<index></index>
|
||||
<direction></direction>
|
||||
<CD_ctrl></CD_ctrl>
|
||||
<CY_ctrl></CY_ctrl>
|
||||
<CL_ctrl></CL_ctrl>
|
||||
<Cell_ctrl></Cell_ctrl>
|
||||
<Cem_ctrl></Cem_ctrl>
|
||||
<Cen_ctrl></Cen_ctrl>
|
||||
</control_surface>
|
||||
@@ -1,151 +0,0 @@
|
||||
<sdf version='1.9'>
|
||||
<world name='windy'>
|
||||
<physics type="ode">
|
||||
<max_step_size>0.004</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
<real_time_update_rate>250</real_time_update_rate>
|
||||
</physics>
|
||||
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
|
||||
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
|
||||
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
|
||||
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
|
||||
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
|
||||
<plugin name='gz::sim::systems::AirPressure' filename='gz-sim-air-pressure-system'/>
|
||||
<plugin name='gz::sim::systems::ApplyLinkWrench' filename='gz-sim-apply-link-wrench-system'/>
|
||||
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
<gui fullscreen='false'>
|
||||
<plugin name='3D View' filename='GzScene3D'>
|
||||
<gz-gui>
|
||||
<title>3D View</title>
|
||||
<property type='bool' key='showTitleBar'>0</property>
|
||||
<property type='string' key='state'>docked</property>
|
||||
</gz-gui>
|
||||
<engine>ogre2</engine>
|
||||
<scene>scene</scene>
|
||||
<ambient_light>0.5984631152222222 0.5984631152222222 0.5984631152222222</ambient_light>
|
||||
<background_color>0.8984631152222222 0.8984631152222222 0.8984631152222222</background_color>
|
||||
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
|
||||
</plugin>
|
||||
<plugin name='World control' filename='WorldControl'>
|
||||
<gz-gui>
|
||||
<title>World control</title>
|
||||
<property type='bool' key='showTitleBar'>0</property>
|
||||
<property type='bool' key='resizable'>0</property>
|
||||
<property type='double' key='height'>72</property>
|
||||
<property type='double' key='width'>121</property>
|
||||
<property type='double' key='z'>1</property>
|
||||
<property type='string' key='state'>floating</property>
|
||||
<anchors target='3D View'>
|
||||
<line own='left' target='left'/>
|
||||
<line own='bottom' target='bottom'/>
|
||||
</anchors>
|
||||
</gz-gui>
|
||||
<play_pause>1</play_pause>
|
||||
<step>1</step>
|
||||
<start_paused>1</start_paused>
|
||||
</plugin>
|
||||
<plugin name='World stats' filename='WorldStats'>
|
||||
<gz-gui>
|
||||
<title>World stats</title>
|
||||
<property type='bool' key='showTitleBar'>0</property>
|
||||
<property type='bool' key='resizable'>0</property>
|
||||
<property type='double' key='height'>110</property>
|
||||
<property type='double' key='width'>290</property>
|
||||
<property type='double' key='z'>1</property>
|
||||
<property type='string' key='state'>floating</property>
|
||||
<anchors target='3D View'>
|
||||
<line own='right' target='right'/>
|
||||
<line own='bottom' target='bottom'/>
|
||||
</anchors>
|
||||
</gz-gui>
|
||||
<sim_time>1</sim_time>
|
||||
<real_time>1</real_time>
|
||||
<real_time_factor>1</real_time_factor>
|
||||
<iterations>1</iterations>
|
||||
</plugin>
|
||||
<plugin name='Entity tree' filename='EntityTree'/>
|
||||
</gui>
|
||||
<gravity>0 0 -9.8</gravity>
|
||||
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
|
||||
<atmosphere type='adiabatic'/>
|
||||
<scene>
|
||||
<grid>false</grid>
|
||||
<ambient>0.4 0.4 0.4 1</ambient>
|
||||
<background>0.7 0.7 0.7 1</background>
|
||||
<shadows>true</shadows>
|
||||
</scene>
|
||||
<model name='ground_plane'>
|
||||
<static>true</static>
|
||||
<link name='link'>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>1 1</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode/>
|
||||
</friction>
|
||||
<bounce/>
|
||||
<contact/>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<mass>1</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<enable_wind>true</enable_wind>
|
||||
</link>
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<self_collide>false</self_collide>
|
||||
</model>
|
||||
<light name='sunUTC' type='directional'>
|
||||
<pose>0 0 500 0 -0 0</pose>
|
||||
<cast_shadows>true</cast_shadows>
|
||||
<intensity>1</intensity>
|
||||
<direction>0.001 0.625 -0.78</direction>
|
||||
<diffuse>0.904 0.904 0.904 1</diffuse>
|
||||
<specular>0.271 0.271 0.271 1</specular>
|
||||
<attenuation>
|
||||
<range>2000</range>
|
||||
<linear>0</linear>
|
||||
<constant>1</constant>
|
||||
<quadratic>0</quadratic>
|
||||
</attenuation>
|
||||
<spot>
|
||||
<inner_angle>0</inner_angle>
|
||||
<outer_angle>0</outer_angle>
|
||||
<falloff>0</falloff>
|
||||
</spot>
|
||||
</light>
|
||||
<wind>
|
||||
<linear_velocity>10 10 10</linear_velocity>
|
||||
</wind>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -1,175 +0,0 @@
|
||||
#!/usr/bin/env python3
|
||||
#############################################################################
|
||||
#
|
||||
# Copyright (C) 2013-2022 PX4 Pro Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
#############################################################################
|
||||
|
||||
"""
|
||||
px_generate_zenoh_topic_files.py
|
||||
Generates c/cpp header/source files for use with zenoh
|
||||
message files
|
||||
"""
|
||||
|
||||
import os
|
||||
import argparse
|
||||
import re
|
||||
import sys
|
||||
|
||||
try:
|
||||
import em
|
||||
except ImportError as e:
|
||||
print("Failed to import em: " + str(e))
|
||||
print("")
|
||||
print("You may need to install it using:")
|
||||
print(" pip3 install --user empy")
|
||||
print("")
|
||||
sys.exit(1)
|
||||
|
||||
try:
|
||||
import genmsg.template_tools
|
||||
except ImportError as e:
|
||||
print("Failed to import genmsg: " + str(e))
|
||||
print("")
|
||||
print("You may need to install it using:")
|
||||
print(" pip3 install --user pyros-genmsg")
|
||||
print("")
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
__author__ = "Sergey Belash, Thomas Gubler, Beat Kueng"
|
||||
__copyright__ = "Copyright (C) 2013-2022 PX4 Development Team."
|
||||
__license__ = "BSD"
|
||||
__email__ = "thomasgubler@gmail.com"
|
||||
|
||||
ZENOH_TEMPLATE_FILE = ['Kconfig.topics.em', 'uorb_pubsub_factory.hpp.em']
|
||||
TOPICS_TOKEN = '# TOPICS '
|
||||
|
||||
|
||||
def get_topics(filename):
|
||||
"""
|
||||
Get TOPICS names from a "# TOPICS" line
|
||||
"""
|
||||
ofile = open(filename, 'r')
|
||||
text = ofile.read()
|
||||
result = []
|
||||
for each_line in text.split('\n'):
|
||||
if each_line.startswith(TOPICS_TOKEN):
|
||||
topic_names_str = each_line.strip()
|
||||
topic_names_str = topic_names_str.replace(TOPICS_TOKEN, "")
|
||||
topic_names_list = topic_names_str.split(" ")
|
||||
for topic in topic_names_list:
|
||||
# topic name PascalCase (file name) to snake_case (topic name)
|
||||
topic_name = re.sub(r'(?<!^)(?=[A-Z])', '_', topic).lower()
|
||||
result.append(topic_name)
|
||||
ofile.close()
|
||||
|
||||
if len(result) == 0:
|
||||
# topic name PascalCase (file name) to snake_case (topic name)
|
||||
file_base_name = os.path.basename(filename).replace(".msg", "")
|
||||
topic_name = re.sub(r'(?<!^)(?=[A-Z])', '_', file_base_name).lower()
|
||||
result.append(topic_name)
|
||||
|
||||
return result
|
||||
|
||||
def generate_by_template(output_file, template_file, em_globals):
|
||||
"""
|
||||
Invokes empy intepreter to geneate output_file by the
|
||||
given template_file and predefined em_globals dict
|
||||
"""
|
||||
# check if folder exists:
|
||||
folder_name = os.path.dirname(output_file)
|
||||
if not os.path.exists(folder_name):
|
||||
os.makedirs(folder_name)
|
||||
|
||||
ofile = open(output_file, 'w')
|
||||
# todo, reuse interpreter
|
||||
interpreter = em.Interpreter(output=ofile, globals=em_globals, options={
|
||||
em.RAW_OPT: True, em.BUFFERED_OPT: True})
|
||||
try:
|
||||
interpreter.file(open(template_file))
|
||||
except OSError as e:
|
||||
ofile.close()
|
||||
os.remove(output_file)
|
||||
raise
|
||||
interpreter.shutdown()
|
||||
ofile.close()
|
||||
return True
|
||||
|
||||
|
||||
def generate_topics_list_file_from_files(files, outputdir, template_filename, templatedir):
|
||||
# generate cpp file with topics list
|
||||
filenames = []
|
||||
for filename in [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]:
|
||||
filenames.append(re.sub(r'(?<!^)(?=[A-Z])', '_', filename).lower())
|
||||
|
||||
datatypes = []
|
||||
for filename in [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]:
|
||||
datatypes.append(re.sub(r'(?<!^)(?=[A-Z])', '_', filename).lower().replace(".msg",""))
|
||||
|
||||
full_base_names = []
|
||||
for filename in [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")]:
|
||||
full_base_names.append(filename.replace(".msg",""))
|
||||
|
||||
topics = []
|
||||
for msg_filename in files:
|
||||
topics.extend(get_topics(msg_filename))
|
||||
|
||||
tl_globals = {"msgs": filenames, "topics": topics, "datatypes": datatypes, "full_base_names": full_base_names}
|
||||
tl_template_file = os.path.join(templatedir, template_filename)
|
||||
tl_out_file = os.path.join(outputdir, template_filename.replace(".em", ""))
|
||||
|
||||
generate_by_template(tl_out_file, tl_template_file, tl_globals)
|
||||
|
||||
if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(description='Convert msg files to uorb headers/sources')
|
||||
parser.add_argument('--zenoh-config', help='Generate Zenoh Kconfig file', action='store_true')
|
||||
parser.add_argument('--zenoh-pub-sub', help='Generate Zenoh Pubsub factory', action='store_true')
|
||||
parser.add_argument('-f', dest='file',
|
||||
help="files to convert (use only without -d)",
|
||||
nargs="+")
|
||||
parser.add_argument('-e', dest='templatedir',
|
||||
help='directory with template files',)
|
||||
parser.add_argument('-o', dest='outputdir',
|
||||
help='output directory for header files')
|
||||
parser.add_argument('-p', dest='prefix', default='',
|
||||
help='string added as prefix to the output file '
|
||||
' name when converting directories')
|
||||
args = parser.parse_args()
|
||||
|
||||
if args.zenoh_config:
|
||||
generate_topics_list_file_from_files(args.file, args.outputdir, ZENOH_TEMPLATE_FILE[0], args.templatedir)
|
||||
exit(0)
|
||||
elif args.zenoh_pub_sub:
|
||||
generate_topics_list_file_from_files(args.file, args.outputdir, ZENOH_TEMPLATE_FILE[1], args.templatedir)
|
||||
exit(0)
|
||||
else:
|
||||
print('Error: either --headers or --sources must be specified')
|
||||
exit(-1)
|
||||
@@ -1,25 +0,0 @@
|
||||
@{
|
||||
topics_count = len(topics)
|
||||
topic_names_all = list(set(topics)) # set() filters duplicates
|
||||
topic_names_all.sort()
|
||||
|
||||
datatypes = list(set(datatypes)) # set() filters duplicates
|
||||
datatypes.sort()
|
||||
}@
|
||||
|
||||
menu "Zenoh publishers/subscribers"
|
||||
depends on MODULES_ZENOH
|
||||
@[for idx, topic_name in enumerate(datatypes)]@
|
||||
config ZENOH_PUBSUB_@(topic_name.upper())
|
||||
bool "@(topic_name)"
|
||||
default n
|
||||
|
||||
@[end for]
|
||||
|
||||
config ZENOH_PUBSUB_ALL_SELECTION
|
||||
bool
|
||||
default y if ZENOH_PUBSUB_ALL
|
||||
@[for idx, topic_name in enumerate(datatypes)]@
|
||||
select ZENOH_PUBSUB_@(topic_name.upper())
|
||||
@[end for]
|
||||
endmenu
|
||||
@@ -1,154 +0,0 @@
|
||||
@###############################################
|
||||
@#
|
||||
@# EmPy template for generating u.hpp file
|
||||
@# for logging purposes
|
||||
@#
|
||||
@###############################################
|
||||
@# Start of Template
|
||||
@#
|
||||
@# Context:
|
||||
@# - topics (List) list of all topic names
|
||||
@###############################################
|
||||
@{
|
||||
|
||||
topic_dict = dict(zip(datatypes, full_base_names))
|
||||
|
||||
topics_count = len(topics)
|
||||
topic_names_all = list(set(topics)) # set() filters duplicates
|
||||
topic_names_all.sort()
|
||||
|
||||
datatypes = list(set(datatypes)) # set() filters duplicates
|
||||
datatypes.sort()
|
||||
|
||||
full_base_names = list(set(full_base_names)) # set() filters duplicates
|
||||
full_base_names.sort()
|
||||
|
||||
|
||||
}@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* uorb_pubsub_factory.hpp
|
||||
*
|
||||
* Defines generic, templatized uORB over Zenoh / ROS2
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <publishers/uorb_publisher.hpp>
|
||||
#include <uORB/topics/uORBTopics.hpp>
|
||||
@[for idx, topic_name in enumerate(full_base_names)]@
|
||||
#include <px4/msg/@(topic_name).h>
|
||||
@[end for]
|
||||
|
||||
@[for idx, topic_name in enumerate(datatypes)]@
|
||||
@{
|
||||
type_topic_count = len([e for e in topic_names_all if e.startswith(topic_name)])
|
||||
}@
|
||||
#ifdef CONFIG_ZENOH_PUBSUB_@(topic_name.upper())
|
||||
# define CONFIG_ZENOH_PUBSUB_@(topic_name.upper())_COUNT @(type_topic_count)
|
||||
#else
|
||||
# define CONFIG_ZENOH_PUBSUB_@(topic_name.upper())_COUNT 0
|
||||
#endif
|
||||
@[end for]
|
||||
|
||||
#define ZENOH_PUBSUB_COUNT \
|
||||
@[for idx, topic_name in enumerate(datatypes)]@
|
||||
CONFIG_ZENOH_PUBSUB_@(topic_name.upper())_COUNT + \
|
||||
@[end for] 0
|
||||
|
||||
typedef struct {
|
||||
const uint32_t *ops;
|
||||
const orb_metadata* orb_meta;
|
||||
} UorbPubSubTopicBinder;
|
||||
|
||||
const UorbPubSubTopicBinder _topics[ZENOH_PUBSUB_COUNT] {
|
||||
@{
|
||||
uorb_id_idx = 0
|
||||
}@
|
||||
@[for idx, topic_name in enumerate(datatypes)]@
|
||||
#ifdef CONFIG_ZENOH_PUBSUB_@(topic_name.upper())
|
||||
@{
|
||||
topic_names = [e for e in topic_names_all if e.startswith(topic_name)]
|
||||
}@
|
||||
@[for topic_name_inst in topic_names]@
|
||||
{
|
||||
px4_msg_@(topic_dict[topic_name])_cdrstream_desc.ops.ops,
|
||||
ORB_ID(@(topic_name_inst))
|
||||
},
|
||||
@{
|
||||
uorb_id_idx += 1
|
||||
}@
|
||||
@[end for]#endif
|
||||
@[end for]
|
||||
};
|
||||
|
||||
uORB_Zenoh_Publisher* genPublisher(const orb_metadata *meta) {
|
||||
for (auto &pub : _topics) {
|
||||
if(pub.orb_meta->o_id == meta->o_id) {
|
||||
return new uORB_Zenoh_Publisher(meta, pub.ops);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
uORB_Zenoh_Publisher* genPublisher(const char *name) {
|
||||
for (auto &pub : _topics) {
|
||||
if(strcmp(pub.orb_meta->o_name, name) == 0) {
|
||||
return new uORB_Zenoh_Publisher(pub.orb_meta, pub.ops);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
Zenoh_Subscriber* genSubscriber(const orb_metadata *meta) {
|
||||
for (auto &sub : _topics) {
|
||||
if(sub.orb_meta->o_id == meta->o_id) {
|
||||
return new uORB_Zenoh_Subscriber(meta, sub.ops);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
Zenoh_Subscriber* genSubscriber(const char *name) {
|
||||
for (auto &sub : _topics) {
|
||||
if(strcmp(sub.orb_meta->o_name, name) == 0) {
|
||||
return new uORB_Zenoh_Subscriber(sub.orb_meta, sub.ops);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
@@ -16,8 +16,8 @@ CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
|
||||
CONFIG_DRIVERS_IMU_ST_L3GD20=y
|
||||
CONFIG_DRIVERS_IMU_ST_LSM303D=y
|
||||
CONFIG_DRIVERS_IMU_L3GD20=y
|
||||
CONFIG_DRIVERS_IMU_LSM303D=y
|
||||
CONFIG_DRIVERS_IRLOCK=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
|
||||
@@ -106,7 +106,7 @@ CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_INIT_STACKSIZE=3094
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
@@ -140,8 +140,6 @@ CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
|
||||
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
|
||||
@@ -4,7 +4,6 @@
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default IMU_GYRO_RATEMAX 1000
|
||||
param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
# Internal SPI
|
||||
if ! paw3902 -s start -Y 180
|
||||
|
||||
@@ -27,6 +27,7 @@
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
@@ -65,8 +66,17 @@ CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
@@ -78,9 +88,14 @@ CONFIG_INIT_STACKSIZE=2624
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
@@ -93,20 +108,29 @@ CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=254
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=3000
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
@@ -125,6 +149,11 @@ CONFIG_STM32_FLASH_PREFETCH=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
|
||||
@@ -65,7 +65,7 @@
|
||||
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
|
||||
|
||||
//todo:wrap OPT_x in in ifdefs for command line definitions
|
||||
#define OPT_TBOOT_MS 3000
|
||||
#define OPT_TBOOT_MS 5000
|
||||
#define OPT_NODE_STATUS_RATE_MS 800
|
||||
#define OPT_NODE_INFO_RATE_MS 50
|
||||
#define OPT_BL_NUMBER_TIMERS 7
|
||||
@@ -93,7 +93,7 @@
|
||||
*/
|
||||
#define OPT_WAIT_FOR_GETNODEINFO 0
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
|
||||
|
||||
#define OPT_ENABLE_WD 1
|
||||
|
||||
|
||||
@@ -156,7 +156,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
led_on(LED_BLUE);
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
//px4_platform_configure();
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# UAVCAN boot loadable Module ID
|
||||
set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR})
|
||||
set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR})
|
||||
set(uavcanblid_sw_version_major 0)
|
||||
set(uavcanblid_sw_version_minor 1)
|
||||
add_definitions(
|
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
|
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
@@ -14,4 +14,4 @@ add_definitions(
|
||||
-DHW_UAVCAN_NAME=${uavcanblid_name}
|
||||
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
|
||||
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
|
||||
)
|
||||
)
|
||||
@@ -5,7 +5,6 @@
|
||||
|
||||
param set-default CBRK_IO_SAFETY 0
|
||||
param set-default MBE_ENABLE 1
|
||||
param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
safety_button start
|
||||
tone_alarm start
|
||||
|
||||
@@ -27,6 +27,7 @@
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
@@ -65,8 +66,17 @@ CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
@@ -80,9 +90,14 @@ CONFIG_INIT_STACKSIZE=2624
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
@@ -95,25 +110,35 @@ CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
@@ -128,6 +153,11 @@ CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2C2=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
|
||||
@@ -65,7 +65,7 @@
|
||||
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
|
||||
|
||||
//todo:wrap OPT_x in in ifdefs for command line definitions
|
||||
#define OPT_TBOOT_MS 3000
|
||||
#define OPT_TBOOT_MS 5000
|
||||
#define OPT_NODE_STATUS_RATE_MS 800
|
||||
#define OPT_NODE_INFO_RATE_MS 50
|
||||
#define OPT_BL_NUMBER_TIMERS 7
|
||||
@@ -93,7 +93,7 @@
|
||||
*/
|
||||
#define OPT_WAIT_FOR_GETNODEINFO 0
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
|
||||
|
||||
#define OPT_ENABLE_WD 1
|
||||
|
||||
|
||||
@@ -156,7 +156,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
//px4_platform_configure();
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# UAVCAN boot loadable Module ID
|
||||
set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR})
|
||||
set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR})
|
||||
set(uavcanblid_sw_version_major 0)
|
||||
set(uavcanblid_sw_version_minor 1)
|
||||
add_definitions(
|
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
|
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
|
||||
@@ -7,7 +7,6 @@ param set-default CBRK_IO_SAFETY 0
|
||||
param set-default CANNODE_SUB_MBD 1
|
||||
param set-default CANNODE_SUB_RTCM 1
|
||||
param set-default MBE_ENABLE 1
|
||||
param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
safety_button start
|
||||
tone_alarm start
|
||||
|
||||
@@ -6,9 +6,6 @@ gps start -d /dev/ttyS0 -p ubx
|
||||
|
||||
icm42688p -R 0 -s start
|
||||
|
||||
if ! bmp388 -I -b 2 start
|
||||
then
|
||||
bmp388 -I -b 1 start
|
||||
fi
|
||||
bmp388 -I -b 2 start
|
||||
|
||||
bmm150 -I -b 1 start
|
||||
|
||||
@@ -27,6 +27,7 @@
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
@@ -65,8 +66,17 @@ CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
@@ -80,9 +90,14 @@ CONFIG_INIT_STACKSIZE=2624
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
@@ -95,20 +110,29 @@ CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
@@ -129,6 +153,11 @@ CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2C2=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
|
||||
@@ -65,7 +65,7 @@
|
||||
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
|
||||
|
||||
//todo:wrap OPT_x in in ifdefs for command line definitions
|
||||
#define OPT_TBOOT_MS 3000
|
||||
#define OPT_TBOOT_MS 5000
|
||||
#define OPT_NODE_STATUS_RATE_MS 800
|
||||
#define OPT_NODE_INFO_RATE_MS 50
|
||||
#define OPT_BL_NUMBER_TIMERS 7
|
||||
@@ -93,7 +93,7 @@
|
||||
*/
|
||||
#define OPT_WAIT_FOR_GETNODEINFO 0
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
|
||||
|
||||
#define OPT_ENABLE_WD 1
|
||||
|
||||
|
||||
@@ -162,7 +162,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
//px4_platform_configure();
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# UAVCAN boot loadable Module ID
|
||||
set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR})
|
||||
set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR})
|
||||
set(uavcanblid_sw_version_major 0)
|
||||
set(uavcanblid_sw_version_minor 1)
|
||||
add_definitions(
|
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
|
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
|
||||
@@ -3,8 +3,6 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
pwm_out start
|
||||
|
||||
dshot start
|
||||
|
||||
@@ -27,6 +27,7 @@
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
@@ -65,8 +66,17 @@ CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
@@ -80,9 +90,14 @@ CONFIG_INIT_STACKSIZE=2624
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
@@ -95,20 +110,29 @@ CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=254
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=3000
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
@@ -129,6 +153,11 @@ CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
|
||||
@@ -65,7 +65,7 @@
|
||||
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
|
||||
|
||||
//todo:wrap OPT_x in in ifdefs for command line definitions
|
||||
#define OPT_TBOOT_MS 3000
|
||||
#define OPT_TBOOT_MS 5000
|
||||
#define OPT_NODE_STATUS_RATE_MS 800
|
||||
#define OPT_NODE_INFO_RATE_MS 50
|
||||
#define OPT_BL_NUMBER_TIMERS 7
|
||||
@@ -92,12 +92,8 @@
|
||||
*
|
||||
*/
|
||||
#define OPT_WAIT_FOR_GETNODEINFO 0
|
||||
/* The ARK CANnode uses PH1 for GPIO_BOOT_CONFIG but it is not
|
||||
* compatible with px4_arch_gpioread as Port H = 7 which is greater
|
||||
* than STM32_NPORTS
|
||||
* #define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 0
|
||||
*/
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
|
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
|
||||
|
||||
#define OPT_ENABLE_WD 1
|
||||
|
||||
|
||||
@@ -180,7 +180,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
//px4_platform_configure();
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
# UAVCAN boot loadable Module ID
|
||||
set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR})
|
||||
set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR})
|
||||
set(uavcanblid_sw_version_major 0)
|
||||
set(uavcanblid_sw_version_minor 1)
|
||||
add_definitions(
|
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major}
|
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
|
||||
@@ -20,7 +20,6 @@ CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user