Compare commits

...

332 Commits

Author SHA1 Message Date
Zebulon 2ba5e9645a tfmini_i2c: add Kconfig 3 years ago
zbr3550 56f67fc365 tfmini_i2c: add support for Benewake driver on I2C 3 years ago
Daniel Agar 6823cbc414
sensors/vehicle_angular_velocity: add IMU_GYRO_RATEMAX constraints 3 years ago
Daniel Agar beaebe4d0b
sensors/vehicle_imu: don't bother checking IMU_GYRO_RATEMAX 3 years ago
Daniel Agar 0bddca6b9b
boards: NuttX update all boards to preallocated sem holder list 3 years ago
Daniel Agar c50c1e3982
update NuttX and apps to latest with sem holder fixes and updated ostest 3 years ago
Daniel Agar a249b77647
boards: reduce SPI DMA buffers on older STM32F4 boards 3 years ago
Daniel Agar 17de164e95
boards: pixhawk 2 cube skip starting low quality l3gd20 gyro to save memory and cpu 3 years ago
David Sidrane a057b38c40
Update all H7 Bootloders 3 years ago
David Sidrane 39e53711d5
flash_cache:Flush complete cache line 3 years ago
David Sidrane 1294851bb6
boards: STM32H7 pad to 256 bit - 32 bytes (#19724) 3 years ago
David Sidrane 1c15a1a7f4
px4_fmu-v6c:Fix mag rotation 3 years ago
David Sidrane 21567ca187
boards: new px4_fmu-v6c board support (#19544) 3 years ago
bresch 8e789bcc7f
ekf2_post-processing: use estimator_status_flags instead of bitmasks 3 years ago
Julian Oes d699d5f27e
sitl_gazebo: update submodule 3 years ago
Julian Oes 4ae97c505f
commander: lockdown is not termination 3 years ago
Daniel Agar b8ce2a6039
icm42688p: only check configured registers periodically (as intended) 3 years ago
bresch 1f399e5b33
ekf2: use explicit flags instead of bitmask position 3 years ago
Serhat Aksun d67cddae7d
sensors/vehicle_magnetometer: fix multi_mode check 3 years ago
Julian Oes 0290282b17
ROMFS: disable UAVCAN in HITL 3 years ago
Nicolas MARTIN 39d1c79f48
HITL: undefined time_remaining_s should be NAN 3 years ago
Nico van Duijn ad410a2512
Commander: ignore MAV_CMD_REQUEST_MSG 3 years ago
Daniel Agar 453acdce31
.vscode/.gitignore ignore all log files 3 years ago
Beat Küng afb2538da3
output drivers: init SmartLock after exit_and_cleanup 3 years ago
alexklimaj af58c412c3
Fix uavcan battery causing immediate RTL time remaining low 3 years ago
Daniel Agar d5226b28ce
drivers/rc_input: ensure RC inversion is disabled initially and latch RC_INPUT_PROTO conservatively 3 years ago
Beat Küng b091ea9fd9
log_writer_file: fix corner case when mission log is enabled 3 years ago
Beat Küng 9e91ca8294
log_writer_file: protect access to _should_run, use px4::atomicbool for _exit_thread 3 years ago
Igor Mišić 8302f076e7
uavcan: use timer 6 by default on stm32f7 3 years ago
Thomas Stastny de26ffa6e0 fw pos ctrl: turn back to takeoff point with npfg 3 years ago
Thomas Stastny f60d38db65 fw pos ctrl: add missing guidance control interval setting to control_manual_position() 3 years ago
Thomas Stastny 5e3c8d2fa0 fw pos ctrl: fix state switching logic for takeoff and landing 3 years ago
Matthias Grob 90998837ec
Commander: ensure diconnected battery is cleared from bit field 3 years ago
Beat Küng 8cff9a1e04
commander: fix incorrect return in set_link_loss_nav_state() 3 years ago
bresch f8ff34f82d
ekf2: optimize KHP computation 3 years ago
Beat Küng e69d9ec48f
dshot: avoid using pwm failsafe params when dynamic mixing is enabled 3 years ago
Beat Küng f033e164fe
fix dshot: remove setAllFailsafeValues 3 years ago
Daniel Agar 41191765ad
drivers/rc_input: RC_INPUT_PROTO parameter minimal implementation (#19539) 3 years ago
Daniel Agar fc7e979d84 boards: px4_fmu-v5_uavcanv0periph disable modules to save flash 3 years ago
Daniel Agar 7ab9b0c6e2 boards: cubepilot_cubeorange_test disable examples/fake_gps to save flash 3 years ago
Daniel Agar f390f52058 drivers/differential_pressure: remove lib/drivers/airspeed dependency and cleanup 3 years ago
Daniel Agar d1d15a6f6d differential pressure remove filters from drivers and average in sensors/airspeed 3 years ago
Daniel Agar 258f558fea apply differential pressure calibration (SENS_DPRES_OFF) centrally 3 years ago
JaeyoungLim c6ab4c466e
Separate takeoff and landing to individual fixed wing states for FW pos control (#19495) 3 years ago
Daniel Agar d6210d1725
boards: px4_fmu-v6x_default disable common barometers to save flash 3 years ago
Daniel Agar 3d7a6b4021 mc_pos_control: silence invalid setpoint warning when disarmed 3 years ago
Daniel Agar b2bcd2631a
boards/diatone/mamba-f405-mk2: disable modules to save flash 3 years ago
Daniel Agar c8d2d83e55
boards: px4_fmu-v2 restore systemcmds/ver needed for board init 3 years ago
Daniel Agar 7bb789cb23
boards: update bootloaders to latest 3 years ago
Daniel Agar d8a57e15b0
boards/mro/ctrl-zero-classic: fix code style 3 years ago
Daniel Agar 248f42f9ec
boards/diatone/mamba-f405-mk2: fix code style 3 years ago
achim adacdad32d
boards: add new Diatone Mamba F405 mk2 3 years ago
achim 1bf16cb4df
boards: add new mRo Control Zero Classic 3 years ago
Daniel Agar 3d590af115 mc_att_control: only apply quat reset if estimate is newer than setpoint 3 years ago
Daniel Agar 23c89429ac systemcmds/param: set-default should mark parameter active to avoid race conditions 3 years ago
bresch e32a484906 [AUTO COMMIT] update change indication 3 years ago
bresch db0274e19b ekf: robustify bad_acc_vertical check 3 years ago
Daniel Agar 980f696023 commander: mag calibration tolerate fit failure if sensor disabled 3 years ago
Daniel Agar 89374b2e1d mavlink: delete Mavlink instance if early startup fails 3 years ago
Alex Mikhalev 45dff7f71a commander: Add prearm check for flight termination 3 years ago
Daniel Agar 6359c8c008
mavlink: shell expand locking (#19308) 3 years ago
Junwoo Hwang af839c828d Set Tune's Volume for Power-Off in Commander to default volume of tune_control message 3 years ago
Daniel Agar 8df3932d6a icm20948: disable debug output (_debug_enabled=true) 3 years ago
Kirill Shilov 6981a70859
boards: new Sky-Drones AIRLink board support 3 years ago
Daniel Agar 503f97c8bc
logger: add default ground truth logging for HITL/SITL 3 years ago
Silvan Fuhrer 680fe86c05 FlightTaskAuto: fix Weather Vane during landing 3 years ago
Silvan Fuhrer ae5725e71a ROMFS: fix typo in convergence and clair configs 3 years ago
Silvan Fuhrer bd1b0cab73 Mission: don't do anything in set_current_mission_index() when index=current already 3 years ago
Daniel Agar 6f87a4546d platforms/nuttx: cdc_acm_check implement mavlink reboot directly 3 years ago
Daniel Agar 9073f3ccdf px4flow allow delayed background startup 3 years ago
mcsauder fef47513f5 Add gyro and accel range register values to the icm42688p driver. 3 years ago
Hamish Willee e1d3728208 13004_quad+_tailsitter - outputs mixed up 3 years ago
Daniel Agar 435a474dff
Update submodule GPSDrivers to latest Thu Apr 21 12:38:20 UTC 2022 3 years ago
bresch e9c07fac6f EKF: move python tuning tools to EKF module 3 years ago
bresch 49bc5082e7 Tools: add baro pressure coefficient tuning script 3 years ago
bresch ea7009546b mc wind: rename MC wind estimor tuning script 3 years ago
Julian Oes 37fa4bccb6 mavsdk_tests: update MAVSDK dependency 3 years ago
bresch 3c6b72c33b commander: improve set_in_air_position 3 years ago
bresch e9a2b3f260 geofence: remove unused function parameters 3 years ago
bresch 3f3a4ac5c1 navigator: home_positionvalid -> global_home_position_valid 3 years ago
bresch d2f2ba59a4 commander: refactor home position setter 3 years ago
RomanBapst a7683eea07 mission_block: fix vehicle not exiting loiter after reaching exit heading 3 years ago
Thomas Stastny d5a6174e7f
mission block: fix incorrectly calculated ccw loiter exit (#19487) 3 years ago
Daniel Agar 5e05d98fe2 output modules simplify locking for mixer reset and load 3 years ago
bazooka joe 5d95cc001f small cleanup for FlightTask::_evaluateDistanceToGround if-else 3 years ago
Daniel Agar 2e290345d3
boards: px4_fmu-v5_stackcheck disable unused systemcmds to save flash 3 years ago
Daniel Agar 90e2cab3fa
boards: px4_fmu-v5/v5x run default & rtps boards through kconfiglib to cleanup 3 years ago
Daniel Agar 3cdeeb8d64
px4iofirmware: convert most files to c++ 3 years ago
Daniel Agar 3211d0ff19
boards: px4_fmu-v2_multicopter disable lightware_laser_serial to save flash 3 years ago
Daniel Agar d06032d7f3
boards: px4_fmu-v5_uacanv0periph disable systecmds/sd_bench to save flash 3 years ago
stmoon e7562df13a boards: px4_fmu_v5x_rtps disable several modules to save flash 3 years ago
Daniel Agar cbc37f9fcd
boards: px4_fmu-v6x_default disable systemcmds/sd_bench to save flash 3 years ago
alexklimaj 6e0ac66c3c drivers/optical_flow: new PixArt PAA3905 optical flow driver 3 years ago
Beat Küng 9a9aad98a1 mavlink: add COMPONENT_METADATA message 3 years ago
Igor Misic cdfa65d792 commander/safety: set early safety_button_available 3 years ago
Thomas Debrunner f6bdc42977 param-reset: Add option to reset all configurable params, but not the ones that store vehicle information 3 years ago
Daniel Agar 3f13c70cae
px4io cleanup LED and heater handling 3 years ago
Alessandro Simovic 510ad00024 dronecan beeper: remove unneded var 3 years ago
chris1seto 912962f109
lib/rc: Fix DSM2/DSMX guessing routine and DSM range checking (#18270) 3 years ago
PX4 BuildBot 93268a285d Update submodule mavlink to latest Wed Apr 13 12:39:05 UTC 2022 3 years ago
Daniel Agar 9c381a60b5 Tools/ecl_ekf: fix vibe_metrics usage (moved to vehicle_imu_status instances) 3 years ago
Daniel Agar b4158c1b48 sensors/vehicle_imu: Integrator use 1 microsecond for minimum DT 3 years ago
Daniel Agar d2f1349d1a sensors/vehicle_imu: replace coning metric with actual integrator coning correction (averaged) 3 years ago
bresch 37cafe7dcd ekf rng kin: reduce minimum rng variance 3 years ago
bresch 4994649500 ekf rng kin: increase default gate size 3 years ago
bresch 1fbe04986f ekf rng finder consistency: simplify class member names 3 years ago
bresch 4c03f0bc50 ekf: make range finder kin consistency gate tunable by parameter 3 years ago
bresch 079a5e92ba ekf: run rng consistency check only when not horizontally moving 3 years ago
bresch d903613c9c ekf: add logging for rng kinematic consistency check 3 years ago
bresch 8693ad15a7 ekf: add logging of range finder consistency check 3 years ago
bresch baf9cc9597 ekf: use uint64_t for time variables 3 years ago
bresch 9fc331b7ea ekf: requires kinematically consistent range finder data to continue terrain aiding 3 years ago
bresch 78211f9dbb ekf: improve rng consistency check 3 years ago
bresch b1ea2e4e15 ekf: use same gate for innov and innov sequence monitoring 3 years ago
bresch f96287b80a ekf: access member variable without getter 3 years ago
bresch 904bf8ef9f ekf: add range finder kinematic consistency check 3 years ago
bresch 064518f57a ekf: extract range finder noise computation 3 years ago
Matthias Grob 97b2947416 FlightTaskAuto: refactor _commanded_speed_ts -> _time_last_cruise_speed_override 3 years ago
Matthias Grob 68cf686892 FlightTask: rename and move setCruisingSpeed() -> overrideCruiseSpeed() 3 years ago
Matthias Grob f892a624b7 FlightModeManager/FixedwingPositionControl: robustify vehicle command parameter casting 3 years ago
Matthias Grob 6ce3e88f9d vehicle_command: specify what SPEED_TYPEs are for 3 years ago
RomanBapst 3ed929c7b6 addressed review comments 3 years ago
RomanBapst b335710655 vehicle_command: added enum for speed types 3 years ago
RomanBapst d41de33a85 FlightModeManager: handle MAV_CMD_DO_CHANGE_SPEED 3 years ago
RomanBapst ca657f36ef FixedWingPositionControl: handle VEHICLE_CMD_DO_CHANGE_SPEED 3 years ago
RomanBapst 36e32ecd7b navigator: stop handling speed changes via reposition triplet 3 years ago
Junwoo Hwang 35613df210 uORB : Don't automatically include message name as default topic name in uORBTopics source files, to handle case where user doesn't use default messgae name for multi topic definition in .msg file 3 years ago
alexklimaj 4fc161192a Add ARK CANnode board config 3 years ago
Daniel Agar 0a0987a6e0 ROMFS: move px4flow start to rc.sensors 3 years ago
Daniel Agar 1d66f2cf83 posix: HRT hrt_lock() sem_wait try again if error returned 3 years ago
Matthias Grob 10f927ae2b MulticopterPositionControl: remove unused return value parameters_update() 3 years ago
Daniel Agar c30475b04b
Update submodule GPSDrivers to latest Tue Apr 12 12:38:56 UTC 2022 3 years ago
PX4 BuildBot 5e6fb9b537 Update submodule sitl_gazebo to latest Tue Apr 12 12:38:53 UTC 2022 3 years ago
Daniel Agar 8166a500ac
Update world_magnetic_model to latest Mon Apr 11 11:14:11 UTC 2022 (#19475) 3 years ago
Daniel Agar bb2ea574aa ekf2: properly reset IMU biases on calibration change (non-multi-EKF) 3 years ago
Daniel Agar 8f891332f1
boards: px4_fmu-v2_multicopter disable load_mon to save flash 3 years ago
bresch 76a59d5c66 Tools: add drag fusion tuning script 3 years ago
Daniel Agar 04f37222f8 ekf2: fix IMU missed perf count when not using multi-EKF 3 years ago
PX4 BuildBot f2c5d70d3a Update submodule mavlink to latest Sun Apr 10 12:39:00 UTC 2022 3 years ago
Silvan Fuhrer 6096620828 ROMFS: remove duplicate setting of NAV_LOITER_RAD to 80 3 years ago
Silvan Fuhrer c7023e5879 Increase NAV_LOITER_RAD and RTL_LOITER_RAD to 80m each 3 years ago
Nicolas MARTIN eb1bb4335b
commander: fix enable_failsafe reason (#19391) 3 years ago
Daniel Agar 091fca701e
px4io: input_rc only publish new successful decodes 3 years ago
alexklimaj 017f860f44 Add I2C retries in INA226 to prevent publishing 0's on a single read failure 3 years ago
Ryan Johnston 777540bd02
boards/matek/gnss-m9n-f4: RM3100 orientation fix 3 years ago
Ryan Johnston c585758f67
boards/matek/gnss-m9n-f4: IMU orientation update 3 years ago
Jacob Dahl 3bffe3087d use new safety_button topic for uavcannode Button publishing 3 years ago
Matthias Grob fe26ee244d modeCheck: allow arming in land mode for MAVSDK compatibility 3 years ago
Ramon Roche 889a5aa0b1 ci: build and deploy kakuteh7 3 years ago
Daniel Agar 77a37c26bf rc_update: further tighten timing requirements for valid data 3 years ago
Daniel Agar 98623f69a3 update mavlink submodule to latest 3 years ago
Julian Oes a5bd65b923 mavlink: set correct param capability 3 years ago
Matthias Grob 92adc71424 ArmStateMachine: port over unit tests to functional gtests 3 years ago
Matthias Grob f968a5947d ArmStateMachine: port arming_state_names into the class 3 years ago
Matthias Grob 074080c816 Commander: separate out arm state machine to class 3 years ago
Daniel Agar 6e9c673262
boards: omnibus_f4sd_ekf2 disable frsky telemetry to save flash (and fix build) 3 years ago
Thomas Stastny e4b11c49c3
mathlib: add second order reference model filter with optional rate feedback (#19246) 3 years ago
Igor Misic 80aef942cd safety and safety button: refactoring #19413 3 years ago
Jacob Dahl 1f17a1470a uavcan: update safety button 3 years ago
Daniel Agar 8c3ba7adb4 commander: silence GPS no longer validity PX4_WARN 3 years ago
Alessandro Simovic 47b08fd698 precland: save flash space 3 years ago
Hovergames 457130fb69 Support for NXP UWB position sensor 3 years ago
Beat Küng 3381a5914d holybro/kakuteh7: fix BOARD_FLASH_SIZE 3 years ago
Matthias Grob dd28c3e019 battery: update average current also when no capacity is configured 3 years ago
Matthias Grob 13c3eae6d0 battery: use mechanism to keep an up to date armed state 3 years ago
Silvan Fuhrer 3f6ab5ea19 battery: improve flight time remaining improvements 3 years ago
Beat Küng 6652718354 metadata.cmake: enable ethernet parameters 3 years ago
alessandro 8af0eeae46
1011_iris_irlock: require precland (#19431) 3 years ago
stmoon 179820cead boards: px4_fmu_v5x_rtps disable common telemetry modules to save flash 3 years ago
Daniel Agar 803cc6814f
boards: px4_fmu-v2_fixedwing disable drivers/camera_trigger to save flash 3 years ago
Daniel Agar f0be554857
boards: px4_fmu-v5_uavcanv0periph disable modules to save flash 3 years ago
Matthias Grob 3aee2497bb commander_params: add precision land option for mode switch 3 years ago
David Sidrane d6db06faf3 px_update_git_header:Extract latest release tag 3 years ago
Daniel Agar 82c1ffb8f8
boards: px4_fmu-v5_stackcheck disable common telemetry modules to save flash 3 years ago
Alex Mikhalev 9e57c5d217 tunes: Print warning if there is a tune error 3 years ago
Alex Mikhalev f6cda64f0d tunes: Fixed unspecified behaviour 3 years ago
Kabir Mohammed d3b3de7159 mavlink: Use round instead of ceil on BATTERY_STATUS percentage 3 years ago
CUAVmengxiao 1870b9245b fmu-v5: add macro definitions for different version revisions 3 years ago
CUAVmengxiao f540335998 spi: get the correct version revision 3 years ago
CUAVmengxiao c0d5ae2f9f fmu-v5: Add support for ICM-42688-P 3 years ago
Matthias Grob 7cd57b4415 FlightTaskOrbit: alert user about exceeded radius (mavlink_log) 3 years ago
Matthias Grob 3e8d2fea94 FlightTaskOrbit: alert user about exceeded radius (events) 3 years ago
Matthias Grob 8ad44ee128 FlightModeManager: remove needless space at the end of invalid task error string 3 years ago
Matthias Grob 9bdde98a68 FlightModeManager: refactor flight task switch result condition for vehicle commands 3 years ago
Matthias Grob ffaef906c4 FlightModeManager: don't ack with result failed when parameters are invalid 3 years ago
Matthias Grob fc0be6c4fc FlightModeManager: switch to failsafe task if orbit is rejected 3 years ago
RomanBapst 18074dec5a simulator: fix conversion from hPa to Pa 3 years ago
Daniel Agar 8a552fac78 uavcannode: publish RelPosHeading (from sensor_gnss_relative) 3 years ago
Daniel Agar 84e796c385 drives/gps: add new sensor_gnsss_relative msg 3 years ago
Daniel Agar dfe13e16e8
boards: px4_fmu-v2_multicopter disable distance_sensor/tfmini to save flash 3 years ago
Daniel Agar 67920f089b
boards: px4_fmu-v5x_rtps disable unused systemcmds and examples to save flash 3 years ago
Matthias Grob c7f114a26a FlightTaskOrbit: increase radius limit 3 years ago
Matthias Grob d0794c1189 FlightTaskOrbit: don't start Orbit if radius is not in range 3 years ago
Daniel Agar 0595efbd9b sensors/vehicle_magnetometer: publish sensors_status_mag and other minor updates to stay in sync with air data 3 years ago
Daniel Agar 0c31f63896 sensors: add baro calibration and cleanup 3 years ago
Daniel Agar 5800c417c8
boards: px4_fmu-v2_rover disable unused drivers to save flash 3 years ago
Daniel Agar 01eb27c703
Jenkinsfile-compile: skip px4_sitl_rtps for now 3 years ago
Daniel Agar eb666e94a4 bords: omnibus_f4sd move ekf2 from default to new ekf2 board variant 3 years ago
Daniel Agar bc26b73c07 px4io: only publish valid input_rc 3 years ago
Daniel Agar 3d08e031d2 rc_update: improve manual_switches simple protections 3 years ago
Daniel Agar 875a2cc423 commander: remove loop counters and update UI LED control to use monotonic time 3 years ago
Daniel Agar 879622547c commander: only process one vehicle_command/action_request per cycle 3 years ago
Daniel Agar e528eb5dc4
commander: fix status flags usage (condition_global_position_valid->global_position_valid) 3 years ago
Jaeyoung-Lim 106044be38 Initialize global local projection for rovers 3 years ago
Jonas Perolini e31304d7d5
Quadchute param update (#19351) 3 years ago
Jacob Schloss 5ae4cae073
orb_advertise_multi: might return nullptr (#19387) 3 years ago
Daniel Agar 6135bb384b cleanup module callback registration failed errors 3 years ago
Daniel Agar f4c3084c26 init adjustments to ensure used topics are advertised early (primarily for logging) 3 years ago
Matthias Grob e6ed595651 Commander: make last_fail_time_us parameter a reference instead of pointer 3 years ago
Matthias Grob eee4aaee4f Commander: remove dynamic position velocity probation period 3 years ago
David Sidrane 9fe2dfc2e3 px4_fmuv-6x Sensor set 3 3 years ago
Thies Lennart Alff f1ec6ea026 make mavlink atttitude setpoints non-exlusive for offboard setpoints 3 years ago
Daniel Agar 94e30f5efb
boards: delete unused px4_fmu-v2_test 3 years ago
Silvan Fuhrer a7ddaf08c4 vehicle_status_flags.msg: remove condition_ prefix to reduce message size 3 years ago
Silvan Fuhrer c30f2b9493 vehicle_status_flags.msg: remove unused condition_system_returned_to_home 3 years ago
Jaeyoung-Lim 194a281fae Project local coordinates for all fw landing states 3 years ago
Jaeyoung-Lim cb81c6ac8c Address review comments 3 years ago
Jaeyoung-Lim 71bfb9c0de Convert NPFG to local coordinates 3 years ago
Jaeyoung-Lim f804b3516f Remove local planar vector 3 years ago
Jaeyoung Lim 28d34bf095 Convert L1 controller to local coordinates 3 years ago
Matthias Grob 897506267d Sticks: name getThrottle() explicitly about range 3 years ago
Junwoo Hwang 0e5c305163 Stick Verbose Functinos : Make get functions for roll, pitch, yaw and throttle const to specify that it's not changing Sticks' internal variables 3 years ago
Junwoo Hwang f78465428c Stick Verbose Functions : Edit other FlightTasks using checkAndUpdateStickInputs() functions and correct Throttle returned value inverse issue 3 years ago
Junwoo Hwang 8266a4df98 Sticks : Add utility functions to get pitch, roll, throttle and yaw values intuitively and rename ambiguously named function checkAndSetStickInputs() 3 years ago
Matthias Grob db7430aa65 matrix helper: remove needless comment line 3 years ago
Matthias Grob 18629bb535 FlightTaskOrbit: fix tangential yaw stick input for rotation direction changes 3 years ago
Matthias Grob 74c0ae6e55 Functions: add sign from boolean function with unit tests 3 years ago
Matthias Grob e03585ca06 FlightTaskOrbit: remap stick input when vehicle faces tangential 3 years ago
Matthias Grob db1fb6acf7 Commander: no battery time based RTL when already landed 3 years ago
Matthias Grob 69f6092031 mavlink_receiver: remove unused land detection publication 3 years ago
Matthias Grob c1b9b8a1c0 MulticopterLandDetector: correct comment with outdated time constant reference 3 years ago
Matthias Grob b85c4ec475 Commander: rename land detection subscription for consistency 3 years ago
Matthias Grob 4a5a8d59fe matrix helper: add documentation for sign function 3 years ago
Matthias Grob d0abcc1ca3 MatrixHelperTest: add unit tests for the signum function 3 years ago
Matthias Grob 03f836f79d matrix helper: fix sign function zero case 3 years ago
David Sidrane 1a17e9df4d board_hw_rev_ve:Use 97.50% for ADC ref for "High" detection 3 years ago
David Sidrane ebc8ecdee6 board_hw_rev_ve:ADC returns 32 bits 3 years ago
David Sidrane 1c224be8f6 stm32h7:ADC fix CCr Access 3 years ago
RomanBapst 60231bbcb6 navigator: don't reset cruise speed and throttle during a transition as part 3 years ago
Daniel Mesham 06a9be74fa microdds: add xrce client 3 years ago
Konrad e080fab8f6 Set up landing gear logic for tiltrotor and tailsitter VTOL. Gear is set down when in hover mode, esle gear is set up. 3 years ago
Konrad d7de67844f Set up landing gear logic for standard VTOL. Gear is set down when in hover mode, else gear is set up. 3 years ago
Daniel Agar c86d5769ea
boards: px4_fmu-v2_{fixedwing,multicopter} module selection changes to save flash 3 years ago
Daniel Agar 475bd42ab8 sensors: add 2nd static notch and migrate existing parameters 3 years ago
Daniel Agar afeab9587e gyro_fft: peak detection exclude side FFT buckets 3 years ago
Matthias Grob 9ab99a7689 MatrixHelperTest: don't rely on FLOAT_EQ accepting FLT_EPSILON inaccuracy 3 years ago
Thomas Stastny 144697bb6a MatrixHelperTest: correct wrap compare values 3 years ago
benjinne 620f25503c
Add geofence predict param (#17795) 3 years ago
Thomas Debrunner 5b0fc8f507 print_load: Removed unused variable to fix compilation on macos 3 years ago
Daniel Agar 36e6527013 ROMFS: MAV_TYPE cleanup 3 years ago
Matthias Grob cde7b1bc41 Matrix: remove deprecated minimal test framework 3 years ago
Matthias Grob 91493307b9 Matrix: convert vector test to gtest 3 years ago
Matthias Grob 4b63f6b29a Matrix: convert vector assignment test to gtest 3 years ago
Matthias Grob f4b53d2762 Matrix: convert vector3 test to gtest 3 years ago
Matthias Grob ddfd62dfc2 Matrix: convert vector2 test to gtest 3 years ago
Matthias Grob be28aeb3ee Matrix: convert upper right triangle test to gtest 3 years ago
Matthias Grob 4d43aad847 Matrix: convert transpose test to gtest 3 years ago
Matthias Grob b3cc18c6de Matrix: convert square test to gtest 3 years ago
Matthias Grob 555ed9b9d8 Matrix: convert slice test to gtest 3 years ago
Matthias Grob 46df8ab60c Matrix: convert set identity test to gtest 3 years ago
Matthias Grob 831f0e9aac Matrix: convert scalar multiplication test to gtest 3 years ago
Matthias Grob 38d742f1b5 Matrix: convert pseudo inverse test to gtest 3 years ago
Matthias Grob 57e443c4a4 Matrix: convert multiplication test to gtest 3 years ago
Matthias Grob 719898f1e3 Matrix: convert least squares test to gtest 3 years ago
Matthias Grob fddcf342e9 Matrix: convert inverse test to gtest 3 years ago
Matthias Grob f5ec4b2339 Matrix: convert integral test to gtest 3 years ago
Matthias Grob 7c9e28c168 Matrix: convert helper test to gtest 3 years ago
Matthias Grob 0c4c3a917c Matrix: convert hat vee test to gtest 3 years ago
Matthias Grob 8f695a5613 Matrix: convert filter test to gtest 3 years ago
Matthias Grob 79e8152f05 Matrix: convert dual test to gtest 3 years ago
Matthias Grob 62571b6984 Matrix: convert copy to test to gtest 3 years ago
Matthias Grob 35b035e880 Matrix: convert attitude test to gtest 3 years ago
Matthias Grob c33bf5b705 Matrix: convert assignment test to gtest 3 years ago
Matthias Grob fa35635486 Matrix: change naming of sparse vector test 3 years ago
Jukka Laitinen 3d35929f3e Put gyro_fft in kernel by default in protected build 3 years ago
Jukka Laitinen 4658a627d7 Separate i2c and spi board bus configuration into and own library for protected build target 3 years ago
Jukka Laitinen 543c7bd0c5 uORB: Build uorb systemcmd always in kernel side in memory protected build 3 years ago
Jukka Laitinen d167f91eb8 logger/watchdog: Disable watchdog for NuttX protected/kernel builds 3 years ago
Jukka Laitinen 56c6120e83 Use IOCTL for board_read_VBUS_state in NuttX protected builds 3 years ago
Jukka Laitinen 0cf3079401 px4_fmuv5: Implement BOARD_*_LOCKOUT_STATE in protected/kernel builds 3 years ago
Jukka Laitinen 356328056a Add px4_fmu-v5_protected target 3 years ago
Jukka Laitinen 005095d199 Add gran allocator also to user side in protected build 3 years ago
Jukka Laitinen 49b089f149 Add a simple way to launch kernel side modules 3 years ago
Jukka Laitinen c43c71f4af platforms/nuttx/src/px4/common/board_ctrl: Add handlers for vbus & shutdown lockout 3 years ago
Jukka Laitinen 4a74d266be Initialize cxx static variables also in kernel side 3 years ago
Jukka Laitinen c1a7b8df1d Add a px4 userspace initialization in protected build 3 years ago
bresch f3f09c1344 PreFlightCheck: add data timeout detection for mag, baro accel and gyro 3 years ago
bresch 75aa11c955 PreFlightCheck: refactor sensors preflight checks 3 years ago
bresch b1c1163ee4 PreFlightCheck: remove unused device_id argument 3 years ago
bresch 5f1b577b6d PreFlightCheck: mark sensor required if used by an EKF2 instance 3 years ago
stmoon 6d0b11ca99 add custom target for uorb_sources_microcdr_gen 3 years ago
wangwwno1 746c16400a Typo Fix: ChangeWorkQeue 3 years ago
Daniel Agar 4746a19c0c
boards: px4_fmu-v5_stackcheck disable UUV modules to save flash 3 years ago
Daniel Agar 233c7fd293
goertek/spl06: parameters.c add copyright header and fix formatting 3 years ago
Ncerzzk cb23179c50
Add Goertek SPL06 barometer driver (#19229) 3 years ago
Konrad 963f6a91d9 exclude Mixer for Tailsitter with x motor configuration and elevons for fmu-v2 and omnibus to avoid flash size issues 3 years ago
KonradRudin 5f43be9d60 preflight checks: add check for distance sensor (via parameter) 3 years ago
Jukka Laitinen 0d31aadcc3 src/lib/paramters: Add a new interface library for protected build user side 3 years ago
Jukka Laitinen 41a7ae3db2 src/lib/parameters: Refactor common functions to an own file 3 years ago
Daniel Agar 7ef38112d2 ekf2: return saved mag bias variance when not in 3d magnetometer fusion 3 years ago
Daniel Agar 5717434e93 ekf2: initialize GPS drift metrics to NAN rather than 0 3 years ago
alessandro 62d1058cc2 log irlock_report and landing_target_pose messages 3 years ago
Matthias Grob f1e44c6e2a PreFlightCheck: only allow modes suitable for takeoff 3 years ago
Daniel Agar a430f0ccae
ekf2: add simple zero velocity update when vehicle at rest (#19149) 3 years ago
Daniel Agar 3d54d25867
sensor calibration delete temperature (CAL_ACCx_TEMP, CAL_GYROx_TEMP, CAL_MAGx_TEMP) 3 years ago
wangwwno1 aa64789792
sensors/vehicle_imu: Fix Integration Rate greater than Gyro Rate (#19318) 3 years ago
RomanBapst 58a4c38519 rtl: don't fly mission landing if we trigger rtl in hover 3 years ago
bresch 58bd3d0c60 cmake: use elif -> elseif 3 years ago
JunwooHWANG 04f8453f4a
Reduce Beeepr Default volume : 40 -> 20, since it's too loud for TAP_ESC devices from Yuneec (#19311) 3 years ago
Silvan Fuhrer f4c300af25 FlightTaskAuto: Nudging: only set yawrate_sp if WV is disabled or stick out of dead-zone 3 years ago
Alex Klimaj 71850eeda6
mavlink: Add flow control parameters (#19254) 3 years ago
Daniel Agar b66dd5ffa6 adis16470: fix gyro scaling 3 years ago
Roman Bapst 69560bd4f4
Compensate VTOL transition time for air density (#19293) 3 years ago
alessandro 0617fd2b6f fmu-v6x: increase UART5 buffer size 3 years ago
bresch 182980526f commander: allow rearming grace period for arming switch only 3 years ago
wangwwno1 cd5a1e510a
ekf2: typo Fix: pub.advertised() -> pub.advertise() (#19302) 3 years ago
Jacob Dahl 3e21efb721
ina228: fix sign error on CURRENT reading (#19296) 3 years ago
Daniel Agar b7e0f17c6a ekf2: minor position/velocity reset cleanup 3 years ago
Daniel Agar c10ea97967 ekf2: fusion helpers return success/fail and set pos/vel update timestamps centrally (if healthy) 3 years ago
Matthias Grob c4bc062714 helper_functions: generalize unwrapping function 3 years ago
Matthias Grob c86c2db07f helper_functions: simplify unwrap function 3 years ago
Thomas Stastny 5a3aba9c21 matrix: add angle unwrapping method 3 years ago
Matthias Grob 68a0414622 Quaternion: rename function to rotate vectors 3 years ago
Daniel Agar 5affa693f2 uavcan: increase ESC max rate 200->400 Hz 3 years ago
Beat Küng 601c588294 holybro/kakuteh7: disable bluetooth 3 years ago
Beat Küng 047352d049 holybro/kakuteh7: update bootloader binary 3 years ago
Beat Küng 591c95ce2f mixer_module: print actual failsafe value 3 years ago
Bulut Gözübüyük 80c6ab7106 Add support for Omnibus F4 boards with ICM20608G IMUs 3 years ago
Matthias Grob 666cf2326d
mission_block: handle SET_ROI_LOCATION with absolute altitude correctly (#19258) 3 years ago
Daniel Agar 49df00c319
lib/mixer_module: check thrust factor range valid and minor optimization (#19272) 3 years ago
JunwooHWANG 35af604a82
Added RTL Switch Setting for ATL Mantis Edu (#19267) 3 years ago
Daniel Agar 52221b0bb7
vscode: add stlink debug config (#19269) 3 years ago
  1. 6
      .ci/Jenkinsfile-compile
  2. 11
      .ci/Jenkinsfile-hardware
  3. 4
      .github/workflows/compile_nuttx.yml
  4. 4
      .github/workflows/sitl_tests.yml
  5. 3
      .gitmodules
  6. 2
      .vscode/.gitignore
  7. 10
      .vscode/cmake-variants.yaml
  8. 7
      CMakeLists.txt
  9. 3
      Makefile
  10. 2
      ROMFS/cannode/init.d/rcS
  11. 1
      ROMFS/px4fmu_common/init.d-posix/airframes/1011_iris_irlock
  12. 3
      ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic
  13. 3
      ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus
  14. 1
      ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy
  15. 3
      ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol
  16. 5
      ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter
  17. 5
      ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor
  18. 3
      ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop
  19. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover
  20. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover
  21. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1
  22. 2
      ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat
  23. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x
  24. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480
  25. 4
      ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc
  26. 14
      ROMFS/px4fmu_common/init.d-posix/rcS
  27. 2
      ROMFS/px4fmu_common/init.d/airframes/1000_rc_fw_easystar.hil
  28. 1
      ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d
  29. 2
      ROMFS/px4fmu_common/init.d/airframes/1001_rc_quad_x.hil
  30. 5
      ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil
  31. 2
      ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil
  32. 3
      ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard
  33. 2
      ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol
  34. 2
      ROMFS/px4fmu_common/init.d/airframes/13002_firefly6
  35. 3
      ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter
  36. 8
      ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter
  37. 1
      ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad
  38. 1
      ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta
  39. 1
      ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad
  40. 1
      ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger
  41. 2
      ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger
  42. 3
      ROMFS/px4fmu_common/init.d/airframes/13010_claire
  43. 3
      ROMFS/px4fmu_common/init.d/airframes/13012_convergence
  44. 3
      ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad
  45. 4
      ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark
  46. 4
      ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor
  47. 1
      ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo
  48. 4
      ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter
  49. 3
      ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+
  50. 3
      ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw-
  51. 7
      ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli
  52. 2
      ROMFS/px4fmu_common/init.d/airframes/16001_helicopter
  53. 1
      ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2
  54. 3
      ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1
  55. 3
      ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox
  56. 3
      ROMFS/px4fmu_common/init.d/airframes/3033_wingwing
  57. 2
      ROMFS/px4fmu_common/init.d/airframes/4051_s250aq
  58. 2
      ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu
  59. 5
      ROMFS/px4fmu_common/init.d/airframes/4071_ifo
  60. 5
      ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s
  61. 4
      ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor
  62. 2
      ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle
  63. 3
      ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover
  64. 3
      ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx
  65. 3
      ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic
  66. 3
      ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus
  67. 3
      ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x
  68. 9
      ROMFS/px4fmu_common/init.d/airframes/6002_draco_r
  69. 3
      ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+
  70. 3
      ROMFS/px4fmu_common/init.d/airframes/8001_octo_x
  71. 3
      ROMFS/px4fmu_common/init.d/airframes/9001_octo_+
  72. 3
      ROMFS/px4fmu_common/init.d/rc.airship_defaults
  73. 3
      ROMFS/px4fmu_common/init.d/rc.balloon_defaults
  74. 3
      ROMFS/px4fmu_common/init.d/rc.boat_defaults
  75. 5
      ROMFS/px4fmu_common/init.d/rc.fw_defaults
  76. 3
      ROMFS/px4fmu_common/init.d/rc.mc_defaults
  77. 3
      ROMFS/px4fmu_common/init.d/rc.rover_defaults
  78. 62
      ROMFS/px4fmu_common/init.d/rc.sensors
  79. 3
      ROMFS/px4fmu_common/init.d/rc.uuv_defaults
  80. 95
      ROMFS/px4fmu_common/init.d/rc.vehicle_setup
  81. 3
      ROMFS/px4fmu_common/init.d/rc.vtol_defaults
  82. 29
      ROMFS/px4fmu_common/init.d/rcS
  83. 2
      ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix
  84. 6
      ROMFS/px4fmu_test/init.d/rc.sensors
  85. 1
      Tools/astyle/files_to_check_code_style.sh
  86. 30
      Tools/ecl_ekf/analyse_logdata_ekf.py
  87. 5
      Tools/ecl_ekf/analysis/checks.py
  88. 63
      Tools/ecl_ekf/analysis/metrics.py
  89. 109
      Tools/ecl_ekf/analysis/post_processing.py
  90. 56
      Tools/ecl_ekf/batch_process_metadata_ekf.py
  91. 8
      Tools/ecl_ekf/check_level_dict.csv
  92. 12
      Tools/ecl_ekf/check_table.csv
  93. 98
      Tools/ecl_ekf/plotting/pdf_report.py
  94. 1
      Tools/kconfig/cmake_kconfig_lut.txt
  95. 2
      Tools/sitl_gazebo
  96. 5
      boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig
  97. 3
      boards/ark/can-flow/nuttx-config/nsh/defconfig
  98. 3
      boards/ark/can-gps/nuttx-config/nsh/defconfig
  99. 3
      boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig
  100. 6
      boards/ark/cannode/canbootloader.px4board
  101. Some files were not shown because too many files have changed in this diff Show More

6
.ci/Jenkinsfile-compile

@ -28,7 +28,7 @@ pipeline { @@ -28,7 +28,7 @@ pipeline {
]
def base_builds = [
target: ["px4_sitl_rtps"],
target: ["px4_sitl_default"],
image: docker_images.base,
archive: false
]
@ -52,12 +52,14 @@ pipeline { @@ -52,12 +52,14 @@ pipeline {
"cuav_x7pro_default",
"cubepilot_cubeorange_default",
"cubepilot_cubeyellow_default",
"diatone_mamba-f405-mk2_default",
"freefly_can-rtk-gps_canbootloader",
"freefly_can-rtk-gps_default",
"holybro_can-gps-v1_canbootloader",
"holybro_can-gps-v1_default",
"holybro_durandal-v1_default",
"holybro_kakutef7_default",
"holybro_kakuteh7_default",
"holybro_pix32v5_default",
"matek_h743-slim",
"matek_gnss-m9n-f4_canbootloader",
@ -100,9 +102,11 @@ pipeline { @@ -100,9 +102,11 @@ pipeline {
"px4_fmu-v5_uavcanv0periph",
"px4_fmu-v5_uavcanv1",
"px4_fmu-v5x_default",
"px4_fmu-v6c_default",
"px4_fmu-v6u_default",
"px4_fmu-v6x_default",
"px4_io-v2_default",
"sky-drones_smartap-airlink_default",
"spracing_h7extreme_default",
"uvify_core_default"
],

11
.ci/Jenkinsfile-hardware

@ -705,18 +705,21 @@ void quickCalibrate() { @@ -705,18 +705,21 @@ void quickCalibrate() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status || true"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick; sleep 1"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_ACC*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro; sleep 2"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_GYRO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level; sleep 2"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show SENS*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick; sleep 1"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_MAG*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate baro; sleep 5"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_BARO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_*"' // parameters after
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
}

4
.github/workflows/compile_nuttx.yml

@ -20,6 +20,7 @@ jobs: @@ -20,6 +20,7 @@ jobs:
ark_can-flow,
ark_can-gps,
ark_can-rtk-gps,
ark_cannode,
atl_mantis-edu,
av_x-v1,
bitcraze_crazyflie,
@ -29,6 +30,7 @@ jobs: @@ -29,6 +30,7 @@ jobs:
cuav_x7pro,
cubepilot_cubeorange,
cubepilot_cubeyellow,
diatone_mamba-f405-mk2,
freefly_can-rtk-gps,
holybro_can-gps-v1,
holybro_durandal-v1,
@ -58,8 +60,10 @@ jobs: @@ -58,8 +60,10 @@ jobs:
px4_fmu-v4pro,
px4_fmu-v5,
px4_fmu-v5x,
px4_fmu-v6c,
px4_fmu-v6u,
px4_fmu-v6x,
sky-drones_smartap-airlink,
spracing_h7extreme,
uvify_core
]

4
.github/workflows/sitl_tests.yml

@ -29,9 +29,9 @@ jobs: @@ -29,9 +29,9 @@ jobs:
token: ${{ secrets.ACCESS_TOKEN }}
- name: Download MAVSDK
run: wget "https://github.com/mavlink/MAVSDK/releases/download/v$(cat test/mavsdk_tests/MAVSDK_VERSION)/mavsdk_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb"
run: wget "https://github.com/mavlink/MAVSDK/releases/download/v$(cat test/mavsdk_tests/MAVSDK_VERSION)/libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb"
- name: Install MAVSDK
run: dpkg -i "mavsdk_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb"
run: dpkg -i "libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb"
- name: Prepare ccache timestamp
id: ccache_cache_timestamp

3
.gitmodules vendored

@ -64,3 +64,6 @@ @@ -64,3 +64,6 @@
path = src/lib/crypto/libtommath
url = https://github.com/PX4/libtommath.git
branch = px4
[submodule "src/modules/microdds_client/Micro-XRCE-DDS-Client"]
path = src/modules/microdds_client/Micro-XRCE-DDS-Client
url = https://github.com/eProsima/Micro-XRCE-DDS-Client.git

2
.vscode/.gitignore vendored

@ -9,3 +9,5 @@ launch.json @@ -9,3 +9,5 @@ launch.json
ipch/
browse.vc.db*
*.log

10
.vscode/cmake-variants.yaml vendored

@ -121,6 +121,16 @@ CONFIG: @@ -121,6 +121,16 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: ark_can-rtk-gps_canbootloader
ark_cannode_default:
short: ark_cannode_default
buildType: MinSizeRel
settings:
CONFIG: ark_cannode_default
ark_cannode_canbootloader:
short: ark_cannode_canbootloader
buildType: MinSizeRel
settings:
CONFIG: ark_cannode_canbootloader
atl_mantis-edu_default:
short: atl_mantis-edu
buildType: MinSizeRel

7
CMakeLists.txt

@ -412,6 +412,7 @@ endif() @@ -412,6 +412,7 @@ endif()
# subdirectories
#
add_library(parameters_interface INTERFACE)
add_library(kernel_parameters_interface INTERFACE)
include(px4_add_library)
add_subdirectory(src/lib EXCLUDE_FROM_ALL)
@ -434,7 +435,13 @@ add_subdirectory(src/lib/metadata EXCLUDE_FROM_ALL) @@ -434,7 +435,13 @@ add_subdirectory(src/lib/metadata EXCLUDE_FROM_ALL)
# must be the last module before firmware
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)
else()
target_link_libraries(parameters_interface INTERFACE parameters)
endif()
# firmware added last to generate the builtin for included modules
add_subdirectory(platforms/${PX4_PLATFORM})

3
Makefile

@ -325,12 +325,13 @@ px4io_update: px4_io-v2_default cubepilot_io-v2_default @@ -325,12 +325,13 @@ px4io_update: px4_io-v2_default cubepilot_io-v2_default
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5x/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6x/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6c/extras/px4_io-v2_default.bin
# cubepilot_io-v2_default
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin
git status
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
git status
.PHONY: coverity_scan

2
ROMFS/cannode/init.d/rcS

@ -88,7 +88,7 @@ unset BOARD_RC_SENSORS @@ -88,7 +88,7 @@ unset BOARD_RC_SENSORS
# Check for flow sensor
if param compare SENS_EN_PX4FLOW 1
then
px4flow start -X
px4flow start -X &
fi
uavcannode start

1
ROMFS/px4fmu_common/init.d-posix/airframes/1011_iris_irlock

@ -10,6 +10,7 @@ @@ -10,6 +10,7 @@
# enable fusion of landing target velocity
param set-default LTEST_MODE 1
param set-default PLD_HACC_RAD 0.1
param set-default RTL_PLD_MD 2
# Start up Landing Target Estimator module
landing_target_estimator start

3
ROMFS/px4fmu_common/init.d-posix/airframes/1020_uuv_generic

@ -8,8 +8,5 @@ @@ -8,8 +8,5 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix
set MIXER custom

3
ROMFS/px4fmu_common/init.d-posix/airframes/1021_uuv_hippocampus

@ -8,8 +8,5 @@ @@ -8,8 +8,5 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix
set MIXER custom

1
ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy

@ -67,4 +67,3 @@ param set-default PWM_MAIN_FUNC7 107 @@ -67,4 +67,3 @@ param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108
set MIXER skip

3
ROMFS/px4fmu_common/init.d-posix/airframes/1040_standard_vtol

@ -71,7 +71,6 @@ param set-default MPC_XY_VEL_I_ACC 4 @@ -71,7 +71,6 @@ 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 NAV_LOITER_RAD 80
param set-default VT_FWD_THRUST_EN 4
param set-default VT_F_TRANS_THR 0.75
@ -80,7 +79,5 @@ param set-default VT_FW_MOT_OFFID 1234 @@ -80,7 +79,5 @@ param set-default VT_FW_MOT_OFFID 1234
param set-default VT_B_TRANS_DUR 8
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
set MIXER custom

5
ROMFS/px4fmu_common/init.d-posix/airframes/1041_tailsitter

@ -7,6 +7,8 @@ @@ -7,6 +7,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 4
@ -68,7 +70,6 @@ param set-default MPC_XY_VEL_I_ACC 4 @@ -68,7 +70,6 @@ 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 NAV_LOITER_RAD 80
param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_SC 0.5
@ -78,7 +79,5 @@ param set-default VT_TYPE 0 @@ -78,7 +79,5 @@ param set-default VT_TYPE 0
param set-default WV_EN 0
set MAV_TYPE 20
set MIXER_FILE etc/mixers-sitl/quad_x_vtol.main.mix
set MIXER custom

5
ROMFS/px4fmu_common/init.d-posix/airframes/1042_tiltrotor

@ -7,6 +7,8 @@ @@ -7,6 +7,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 3
@ -80,7 +82,6 @@ param set-default MPC_XY_VEL_I_ACC 4 @@ -80,7 +82,6 @@ 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 NAV_LOITER_RAD 80
param set-default VT_B_TRANS_DUR 8
param set-default VT_FWD_THRUST_EN 4
@ -88,7 +89,5 @@ param set-default VT_MOT_ID 1234 @@ -88,7 +89,5 @@ param set-default VT_MOT_ID 1234
param set-default VT_TILT_TRANS 0.6
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER_FILE etc/mixers-sitl/tiltrotor_sitl.main.mix
set MIXER custom

3
ROMFS/px4fmu_common/init.d-posix/airframes/1043_standard_vtol_drop

@ -38,7 +38,6 @@ param set-default MPC_XY_VEL_I_ACC 4 @@ -38,7 +38,6 @@ 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 NAV_LOITER_RAD 80
param set-default VT_FWD_THRUST_EN 4
param set-default VT_F_TRANS_THR 0.75
@ -51,7 +50,5 @@ param set-default RC_MAP_AUX1 8 @@ -51,7 +50,5 @@ param set-default RC_MAP_AUX1 8
param set-default RC_MAP_AUX2 9
param set-default RC_MAP_AUX3 10
set MAV_TYPE 22
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
set MIXER custom

2
ROMFS/px4fmu_common/init.d-posix/airframes/1060_rover

@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 201 @@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101
set MAV_TYPE 10
set MIXER_FILE skip

2
ROMFS/px4fmu_common/init.d-posix/airframes/1061_r1_rover

@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 101 @@ -37,6 +37,4 @@ param set-default PWM_MAIN_FUNC2 101
param set-default PWM_MAIN_FUNC6 102
param set-default PWM_MAIN_FUNC7 102
set MAV_TYPE 10
set MIXER_FILE skip

4
ROMFS/px4fmu_common/init.d-posix/airframes/1062_tf-r1

@ -10,6 +10,8 @@ @@ -10,6 +10,8 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default MAV_TYPE 10
param set-default GND_L1_DIST 5
param set-default GND_SP_CTRL_MODE 1
param set-default GND_SPEED_D 3
@ -33,6 +35,4 @@ param set-default CBRK_AIRSPD_CHK 162128 @@ -33,6 +35,4 @@ param set-default CBRK_AIRSPD_CHK 162128
param set-default GND_MAX_ANG 0.6
param set-default GND_WHEEL_BASE 3.0
set MAV_TYPE 10
set MIXER_FILE etc/mixers-sitl/rover_ackermann_sitl.main.mix

2
ROMFS/px4fmu_common/init.d-posix/airframes/1070_boat

@ -47,6 +47,4 @@ param set-default CA_R_REV 3 @@ -47,6 +47,4 @@ param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
set MAV_TYPE 11
set MIXER skip

4
ROMFS/px4fmu_common/init.d-posix/airframes/3011_hexarotor_x

@ -9,6 +9,8 @@ @@ -9,6 +9,8 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default MAV_TYPE 13
param set-default MC_PITCHRATE_P 0.1
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCH_P 6.0
@ -24,6 +26,4 @@ param set-default TRIG_MODE 4 @@ -24,6 +26,4 @@ param set-default TRIG_MODE 4
param set-default MNT_MODE_IN 4
param set-default MNT_DO_STAB 2
set MAV_TYPE 13
set MIXER hexa_x

4
ROMFS/px4fmu_common/init.d-posix/airframes/6011_typhoon_h480

@ -7,6 +7,8 @@ @@ -7,6 +7,8 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default MAV_TYPE 13
param set-default MC_PITCHRATE_P 0.0800
param set-default MC_PITCHRATE_I 0.0400
param set-default MC_PITCHRATE_D 0.0010
@ -26,6 +28,4 @@ param set-default MNT_MODE_IN 4 @@ -26,6 +28,4 @@ param set-default MNT_MODE_IN 4
param set-default MNT_MODE_OUT 2
param set-default MAV_PROTO_VER 2
set MAV_TYPE 13
set MIXER hexa_x

4
ROMFS/px4fmu_common/init.d-posix/airframes/6012_typhoon_h480_ctrlalloc

@ -7,6 +7,8 @@ @@ -7,6 +7,8 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default MAV_TYPE 13
param set-default SYS_CTRL_ALLOC 1
param set-default MC_PITCHRATE_P 0.0800
@ -58,7 +60,5 @@ param set-default PWM_MAIN_FUNC4 104 @@ -58,7 +60,5 @@ param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 106
set MAV_TYPE 13
set MIXER skip
set MIXER_AUX none

14
ROMFS/px4fmu_common/init.d-posix/rcS

@ -24,7 +24,6 @@ fi @@ -24,7 +24,6 @@ fi
# initialize script variables
set IO_PRESENT no
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
@ -224,6 +223,13 @@ rc_update start @@ -224,6 +223,13 @@ rc_update start
manual_control start
sensors start
commander start
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
navigator start
# Try to start the micrortps_client with UDP transport if module exists
@ -253,12 +259,6 @@ then @@ -253,12 +259,6 @@ then
gyro_calibration start
fi
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
#user defined mavlink streams for instances can be in PATH
. px4-rc.mavlink

2
ROMFS/px4fmu_common/init.d/airframes/1000_rc_fw_easystar.hil

@ -61,6 +61,8 @@ param set-default HIL_ACT_FUNC6 400 @@ -61,6 +61,8 @@ param set-default HIL_ACT_FUNC6 400
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
# disable some checks to allow to fly
# - with usb
param set-default CBRK_USB_CHK 197848

1
ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d

@ -36,4 +36,5 @@ param set-default MC_PITCHRATE_P 0.19 @@ -36,4 +36,5 @@ param set-default MC_PITCHRATE_P 0.19
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCHRATE_D 0.004
param set-default MC_YAW_P 4
set MIXER quad_w

2
ROMFS/px4fmu_common/init.d/airframes/1001_rc_quad_x.hil

@ -15,6 +15,8 @@ set MIXER quad_x @@ -15,6 +15,8 @@ set MIXER quad_x
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15

5
ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil

@ -49,7 +49,6 @@ param set-default MPC_Z_VEL_MAX_DN 1.5 @@ -49,7 +49,6 @@ param set-default MPC_Z_VEL_MAX_DN 1.5
param set-default NAV_ACC_RAD 5
param set-default NAV_DLL_ACT 2
param set-default NAV_LOITER_RAD 80
param set-default RTL_DESCEND_ALT 10
param set-default RTL_RETURN_ALT 30
@ -95,6 +94,8 @@ param set-default HIL_ACT_FUNC8 203 @@ -95,6 +94,8 @@ param set-default HIL_ACT_FUNC8 203
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
# disable some checks to allow to fly
# - with usb
param set-default CBRK_USB_CHK 197848
@ -104,7 +105,7 @@ param set-default CBRK_SUPPLY_CHK 894281 @@ -104,7 +105,7 @@ param set-default CBRK_SUPPLY_CHK 894281
param set-default COM_PREARM_MODE 0
param set-default CBRK_IO_SAFETY 22027
set MAV_TYPE 22
param set-default MAV_TYPE 22
set MIXER standard_vtol_hitl

2
ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil

@ -47,7 +47,7 @@ param set-default HIL_ACT_FUNC6 201 @@ -47,7 +47,7 @@ param set-default HIL_ACT_FUNC6 201
param set-default HIL_ACT_REV 32
param set-default MAV_TYPE 19
set MAV_TYPE 19
set MIXER vtol_tailsitter_duo_sat
set PWM_OUT 1234

3
ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard

@ -54,7 +54,8 @@ param set-default PWM_AUX_DIS5 950 @@ -54,7 +54,8 @@ param set-default PWM_AUX_DIS5 950
param set-default VT_TYPE 2
param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
set MAV_TYPE 22
param set-default MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT

2
ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol

@ -19,7 +19,6 @@ @@ -19,7 +19,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 19
param set-default MC_ROLL_P 6
@ -38,7 +37,6 @@ param set-default VT_IDLE_PWM_MC 1080 @@ -38,7 +37,6 @@ param set-default VT_IDLE_PWM_MC 1080
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_ID 12
param set-default VT_TYPE 0
set MAV_TYPE 19
set MIXER vtol_tailsitter_duo

2
ROMFS/px4fmu_common/init.d/airframes/13002_firefly6

@ -23,6 +23,7 @@ @@ -23,6 +23,7 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_P 0.19
@ -45,7 +46,6 @@ param set-default VT_TILT_TRANS 0.5 @@ -45,7 +46,6 @@ param set-default VT_TILT_TRANS 0.5
param set-default VT_TILT_FW 0.9
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER firefly6
set MIXER_AUX firefly6

3
ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter

@ -13,6 +13,8 @@ @@ -13,6 +13,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
param set-default CA_AIRFRAME 4
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
@ -38,7 +40,6 @@ param set-default PWM_MAIN_MAX 2000 @@ -38,7 +40,6 @@ param set-default PWM_MAIN_MAX 2000
param set-default VT_MOT_ID 1234
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 0
set MAV_TYPE 20
set MIXER quad_x_vtol

8
ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter

@ -7,8 +7,8 @@ @@ -7,8 +7,8 @@
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 4
# @output MAIN4 motor 5
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output MAIN5 elevon left
# @output MAIN6 elevon right
# @output MAIN7 canard surface
@ -22,13 +22,13 @@ @@ -22,13 +22,13 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
param set-default PWM_MAIN_MAX 2000
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 0
set MAV_TYPE 20
set MIXER quad_+_vtol
set PWM_OUT 1234

1
ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad

@ -52,7 +52,6 @@ param set-default VT_MOT_ID 1234 @@ -52,7 +52,6 @@ param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT

1
ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta

@ -41,7 +41,6 @@ param set-default VT_FW_MOT_OFFID 1234 @@ -41,7 +41,6 @@ param set-default VT_FW_MOT_OFFID 1234
param set-default VT_F_TRANS_THR 0.75
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_delta

1
ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad

@ -33,7 +33,6 @@ param set-default VT_MOT_ID 1234 @@ -33,7 +33,6 @@ param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAVVT

1
ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger

@ -46,7 +46,6 @@ param set-default VT_IDLE_PWM_MC 1080 @@ -46,7 +46,6 @@ param set-default VT_IDLE_PWM_MC 1080
param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT

2
ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger

@ -77,8 +77,6 @@ param set-default VT_TRANS_MIN_TM 5 @@ -77,8 +77,6 @@ param set-default VT_TRANS_MIN_TM 5
param set-default VT_TRANS_TIMEOUT 30
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT

3
ROMFS/px4fmu_common/init.d/airframes/13010_claire

@ -13,6 +13,8 @@ @@ -13,6 +13,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default PWM_AUX_DISARM 1000
param set-default PWM_AUX_MAX 2000
param set-default PWM_AUX_MIN 1000
@ -28,7 +30,6 @@ param set-default VT_TILT_MC 0.08 @@ -28,7 +30,6 @@ param set-default VT_TILT_MC 0.08
param set-default VT_TILT_TRANS 0.5
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER claire
set MIXER_AUX claire

3
ROMFS/px4fmu_common/init.d/airframes/13012_convergence

@ -22,6 +22,8 @@ @@ -22,6 +22,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default CBRK_AIRSPD_CHK 162128
param set-default FW_ARSP_MODE 1
@ -64,7 +66,6 @@ param set-default VT_TRANS_MIN_TM 1.2 @@ -64,7 +66,6 @@ param set-default VT_TRANS_MIN_TM 1.2
param set-default VT_TRANS_P2_DUR 1.3
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER vtol_convergence

3
ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad

@ -22,6 +22,8 @@ @@ -22,6 +22,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 22
param set-default BAT1_CAPACITY 23000
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.0025
@ -134,7 +136,6 @@ param set-default VT_TRANS_TIMEOUT 22 @@ -134,7 +136,6 @@ param set-default VT_TRANS_TIMEOUT 22
param set-default VT_F_TRANS_RAMP 4
param set-default COM_RC_OVERRIDE 0
set MAV_TYPE 22
set MIXER deltaquad
set MIXER_AUX pass

4
ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark

@ -23,6 +23,8 @@ @@ -23,6 +23,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 22
param set-default BAT1_N_CELLS 6
param set-default FW_AIRSPD_MAX 30
@ -94,8 +96,6 @@ param set-default VT_PSHER_RMP_DT 2 @@ -94,8 +96,6 @@ param set-default VT_PSHER_RMP_DT 2
param set-default VT_TRANS_MIN_TM 4
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER babyshark
set MIXER_AUX pass

4
ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor

@ -27,6 +27,8 @@ @@ -27,6 +27,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default VT_IDLE_PWM_MC 1100
param set-default VT_TYPE 1
param set-default VT_MOT_ID 1234
@ -57,8 +59,6 @@ param set-default CA_SV_CS3_TRQ_Y 1.0 @@ -57,8 +59,6 @@ param set-default CA_SV_CS3_TRQ_Y 1.0
param set-default CA_SV_CS3_TYPE 4
param set-default CA_SV_TL_COUNT 4
set MAV_TYPE 21
set MIXER quad_x
set MIXER_AUX vtol_TTTTAAER

1
ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo

@ -31,7 +31,6 @@ param set-default PWM_AUX_DIS5 950 @@ -31,7 +31,6 @@ param set-default PWM_AUX_DIS5 950
param set-default VT_TYPE 2
param set-default VT_MOT_ID 12345678
param set-default VT_FW_MOT_OFFID 12345678
set MAV_TYPE 22
set MIXER octo_cox
set MIXER_AUX vtol_AAERT

4
ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter

@ -19,6 +19,8 @@ @@ -19,6 +19,8 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 19
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_COUNT 2
param set-default VT_TYPE 0
@ -37,8 +39,6 @@ param set-default CA_SV_CS1_TRQ_P 0.5 @@ -37,8 +39,6 @@ param set-default CA_SV_CS1_TRQ_P 0.5
param set-default CA_SV_CS1_TRQ_Y -0.5
param set-default CA_SV_CS1_TYPE 6
param set-default MAV_TYPE 19
set MAV_TYPE 19
set MIXER vtol_tailsitter_duo
set PWM_OUT 1234

3
ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+

@ -18,4 +18,7 @@ @@ -18,4 +18,7 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_TRICOPTER 15
param set-default MAV_TYPE 15
set MIXER tri_y_yaw+

3
ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw-

@ -18,4 +18,7 @@ @@ -18,4 +18,7 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_TRICOPTER 15
param set-default MAV_TYPE 15
set MIXER tri_y_yaw-

7
ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli

@ -17,7 +17,9 @@ @@ -17,7 +17,9 @@
#
. ${R}etc/init.d/rc.mc_defaults
set MIXER coax
# MAV_TYPE_COAXIAL 3
param set-default MAV_TYPE 3
param set-default MC_ROLLRATE_P 0.17
param set-default MC_ROLLRATE_I 0.05
@ -36,6 +38,9 @@ param set-default PWM_MAIN_RATE 400 @@ -36,6 +38,9 @@ param set-default PWM_MAIN_RATE 400
param set-default RTL_RETURN_ALT 30
param set-default RTL_DESCEND_ALT 10
set MIXER coax
# This is the gimbal pass mixer
set MIXER_AUX pass

2
ROMFS/px4fmu_common/init.d/airframes/16001_helicopter

@ -20,7 +20,7 @@ @@ -20,7 +20,7 @@
. ${R}etc/init.d/rc.mc_defaults
# Configure as helicopter (number 4 defined in commander_helper.cpp)
set MAV_TYPE 4
param set-default MAV_TYPE 4
set MIXER blade130

1
ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2

@ -41,5 +41,6 @@ param set-default FW_R_LIM 40 @@ -41,5 +41,6 @@ param set-default FW_R_LIM 40
param set-default FW_P_LIM_MAX 25
param set-default FW_P_LIM_MIN -5
param set-default FW_P_RMAX_NEG 20
set MIXER TF-G2
set MIXER_AUX pass

3
ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1

@ -24,8 +24,5 @@ param set-default MAV_0_CONFIG 102 @@ -24,8 +24,5 @@ param set-default MAV_0_CONFIG 102
param set-default GPS_UBX_DYNMODEL 8
param set-default SER_TEL2_BAUD 9600
set MAV_TYPE 8
param set MAV_TYPE ${MAV_TYPE}
set MIXER IO_pass
set MIXER_AUX pass

3
ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox

@ -26,7 +26,7 @@ @@ -26,7 +26,7 @@
# @board px4_fmu-v2 exclude
#
set VEHICLE_TYPE mc
. ${R}etc/init.d/rc.mc_defaults
param set-default NAV_ACC_RAD 2
@ -39,6 +39,7 @@ param set-default PWM_MAIN_RATE 400 @@ -39,6 +39,7 @@ param set-default PWM_MAIN_RATE 400
param set-default RTL_DESCEND_ALT 10
param set-default RTL_RETURN_ALT 30
set MIXER dodeca_top_cox
set MIXER_AUX dodeca_bottom_cox

3
ROMFS/px4fmu_common/init.d/airframes/3033_wingwing

@ -41,9 +41,6 @@ param set-default FW_RR_P 0.04 @@ -41,9 +41,6 @@ param set-default FW_RR_P 0.04
param set-default PWM_MAIN_DISARM 1000
# Configure this as plane.
set MAV_TYPE 1
# Set mixer.
set MIXER fw_generic_wing

2
ROMFS/px4fmu_common/init.d/airframes/4051_s250aq

@ -24,8 +24,6 @@ @@ -24,8 +24,6 @@
set MIXER quad_s250aq
set MAV_TYPE 2
param set-default ATT_BIAS_MAX 0
param set-default CBRK_IO_SAFETY 22027

2
ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu

@ -164,6 +164,8 @@ param set-default RC_MAP_AUX2 5 @@ -164,6 +164,8 @@ param set-default RC_MAP_AUX2 5
param set-default RC_MAP_AUX3 10
param set-default RC_MAP_AUX4 8
param set-default RC_MAP_FLTMODE 6
param set-default RC_MAP_RETURN_SW 7
param set-default RC1_TRIM 1000

5
ROMFS/px4fmu_common/init.d/airframes/4071_ifo

@ -21,10 +21,7 @@ @@ -21,10 +21,7 @@
# @board cuav_x7pro exclude
#
set VEHICLE_TYPE mc
set MIXER quad_x
set PWM_OUT 1234
. ${R}etc/init.d/rc.mc_defaults
# Attitude & rate gains
param set-default MC_ROLLRATE_D 0.0013

5
ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s

@ -21,10 +21,7 @@ @@ -21,10 +21,7 @@
# @maintainer Hyon Lim <lim@uvify.com>
#
set VEHICLE_TYPE mc
set MIXER quad_x
set PWM_OUT 1234
. ${R}etc/init.d/rc.mc_defaults
# Attitude & rate gains
param set-default MC_ROLLRATE_D 0.0013

4
ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor

@ -24,10 +24,6 @@ @@ -24,10 +24,6 @@
. ${R}etc/init.d/rc.mc_defaults
# Configure this as Quadrotor
# set MAV_TYPE 14
# Set mixer
set MIXER tilt_quad
set MIXER_AUX tilt_quad

2
ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle

@ -48,8 +48,6 @@ param set-default NAV_ACC_RAD 0.5 @@ -48,8 +48,6 @@ param set-default NAV_ACC_RAD 0.5
param set-default PWM_MAIN_DISARM 1500
param set-default PWM_MAIN_MAX 2000
param set-default PWM_MAIN_MIN 1000
# Configure this as rover
set MAV_TYPE 10
# Set mixer
set MIXER rover_generic

3
ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover

@ -76,9 +76,6 @@ param set-default RBCLW_SER_CFG 104 @@ -76,9 +76,6 @@ param set-default RBCLW_SER_CFG 104
# Start this driver after setting parameters, because the driver uses some of those parameters.
# roboclaw start /dev/ttyS3
# Configure this as rover
set MAV_TYPE 10
# Set mixer
set MIXER generic_diff_rover

3
ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx

@ -65,9 +65,6 @@ param set-default PWM_MAIN_MIN4 970 @@ -65,9 +65,6 @@ param set-default PWM_MAIN_MIN4 970
# Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
# Configure this as rover
set MAV_TYPE 10
# Set mixer
set MIXER rover_diff_and_servo

3
ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic

@ -16,7 +16,4 @@ @@ -16,7 +16,4 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER uuv_x

3
ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus

@ -16,7 +16,4 @@ @@ -16,7 +16,4 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER uuv_x

3
ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x

@ -23,6 +23,9 @@ @@ -23,6 +23,9 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_HEXAROTOR 13
param set-default MAV_TYPE 13
param set-default CA_ROTOR_COUNT 6
param set-default CA_ROTOR0_PX 0.0
param set-default CA_ROTOR0_PY 0.5

9
ROMFS/px4fmu_common/init.d/airframes/6002_draco_r

@ -27,9 +27,8 @@ @@ -27,9 +27,8 @@
. ${R}etc/init.d/rc.mc_defaults
set MIXER hexa_x
set PWM_OUT 12345678
# MAV_TYPE_HEXAROTOR 13
param set-default MAV_TYPE 13
###############################################
# Attitude & rate gains
@ -120,3 +119,7 @@ param set-default MAV_1_MODE 2 @@ -120,3 +119,7 @@ param set-default MAV_1_MODE 2
param set-default MAV_1_FORWARD 1
param set-default MAV_1_RATE 800000
param set-default SER_TEL2_BAUD 921600
set MIXER hexa_x
set PWM_OUT 12345678

3
ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+

@ -23,6 +23,9 @@ @@ -23,6 +23,9 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_HEXAROTOR 13
param set-default MAV_TYPE 13
param set-default CA_ROTOR_COUNT 6
param set-default CA_ROTOR0_PX 0.5
param set-default CA_ROTOR0_PY 0.0

3
ROMFS/px4fmu_common/init.d/airframes/8001_octo_x

@ -25,6 +25,9 @@ @@ -25,6 +25,9 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_OCTOROTOR 14
param set-default MAV_TYPE 14
param set-default CA_ROTOR_COUNT 8
param set-default CA_ROTOR0_KM -0.05
param set-default CA_ROTOR0_PX 0.46

3
ROMFS/px4fmu_common/init.d/airframes/9001_octo_+

@ -25,6 +25,9 @@ @@ -25,6 +25,9 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_OCTOROTOR 14
param set-default MAV_TYPE 14
set MIXER octo_+
set PWM_OUT 12345678

3
ROMFS/px4fmu_common/init.d/rc.airship_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE airship
# MAV_TYPE_AIRSHIP 7
param set-default MAV_TYPE 7
#
# This is the gimbal pass mixer.
#

3
ROMFS/px4fmu_common/init.d/rc.balloon_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE fw
# MAV_TYPE_FREE_BALLOON 8
param set-default MAV_TYPE 8
#
# Default parameters for balloon UAVs.
#

3
ROMFS/px4fmu_common/init.d/rc.boat_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE rover
# MAV_TYPE_SURFACE_BOAT 11
param set-default MAV_TYPE 11
#
# Default parameters for UGVs.
#

5
ROMFS/px4fmu_common/init.d/rc.fw_defaults

@ -7,14 +7,15 @@ @@ -7,14 +7,15 @@
set VEHICLE_TYPE fw
# MAV_TYPE_FIXED_WING 1
param set-default MAV_TYPE 1
#
# Default parameters for fixed wing UAVs.
#
param set-default COM_POS_FS_DELAY 5
param set-default COM_POS_FS_EPH 15
param set-default COM_POS_FS_EPV 30
param set-default COM_POS_FS_GAIN 0
param set-default COM_POS_FS_PROB 1
param set-default COM_VEL_FS_EVH 5
# Disable preflight disarm to not interfere with external launching
param set-default COM_DISARM_PRFLT -1

3
ROMFS/px4fmu_common/init.d/rc.mc_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE mc
# MAV_TYPE_QUADROTOR 2
param set-default MAV_TYPE 2
if param compare IMU_GYRO_RATEMAX 400
then
param set-default IMU_GYRO_RATEMAX 800

3
ROMFS/px4fmu_common/init.d/rc.rover_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE rover
# MAV_TYPE_GROUND_ROVER 10
param set-default MAV_TYPE 10
#
# Default parameters for UGVs.
#

62
ROMFS/px4fmu_common/init.d/rc.sensors

@ -58,6 +58,11 @@ then @@ -58,6 +58,11 @@ then
pga460 start
fi
if param greater -s SENS_EN_TFI2C 0
then
tfmini_i2c start -X
fi
# Lightware i2c lidar sensor
if param greater -s SENS_EN_SF1XX 0
then
@ -83,18 +88,24 @@ then @@ -83,18 +88,24 @@ then
teraranger start -X
fi
# Possible external pmw3901 optical flow sensor
if param greater -s SENS_EN_PMW3901 0
# paa3905 optical flow sensor (external SPI)
if param greater -s SENS_EN_PAA3905 0
then
pmw3901 -S start
paa3905 -S start
fi
# Possible external paw3902 optical flow sensor
# paw3902 optical flow sensor (external SPI)
if param greater -s SENS_EN_PAW3902 0
then
paw3902 -S start
fi
# pmw3901 optical flow sensor (external SPI)
if param greater -s SENS_EN_PMW3901 0
then
pmw3901 -S start
fi
# vl53l1x i2c distance sensor
if param compare -s SENS_EN_VL53L1X 1
then
@ -123,30 +134,36 @@ fi @@ -123,30 +134,36 @@ fi
# Sensirion SDP3X differential pressure sensor external I2C
if param compare -s SENS_EN_SDP3X 1
then
if ! sdp3x_airspeed start -X
if ! sdp3x start -X
then
# try another common address
sdp3x_airspeed start -X -a 0x22
sdp3x start -X -a 0x22
fi
fi
# SHT3x temperature and hygrometer sensor, external I2C
if param compare -s SENS_EN_SHT3X 1
# TE MS4515 differential pressure sensor external I2C
if param compare -s SENS_EN_MS4515 1
then
sht3x start -X
sht3x start -X -a 0x45
ms4515 start -X
fi
# TE MS4525 differential pressure sensor external I2C
if param compare -s SENS_EN_MS4525 1
# TE MS4525DO differential pressure sensor external I2C
if param compare -s SENS_EN_MS4525DO 1
then
ms4525_airspeed start -X
ms4525do start -X
fi
# TE MS5525 differential pressure sensor external I2C
if param compare -s SENS_EN_MS5525 1
# TE MS5525DSO differential pressure sensor external I2C
if param compare -s SENS_EN_MS5525DS 1
then
ms5525_airspeed start -X
ms5525dso start -X
fi
# SHT3x temperature and hygrometer sensor, external I2C
if param compare -s SENS_EN_SHT3X 1
then
sht3x start -X
sht3x start -X -a 0x45
fi
# IR-LOCK sensor external I2C
@ -155,6 +172,13 @@ then @@ -155,6 +172,13 @@ then
irlock start -X
fi
# SPL06 sensor external I2C
if param compare -s SENS_EN_SPL06 1
then
spl06 -X start
spl06 -X -a 0x77 start
fi
# PCF8583 counter (RPM sensor)
if param compare -s SENS_EN_PCF8583 1
then
@ -179,9 +203,3 @@ then @@ -179,9 +203,3 @@ then
# start last (wait for possible icm20948 passthrough mode)
ak09916 -X -q start
fi
###############################################################################
# End Optional drivers #
###############################################################################
sensors start

3
ROMFS/px4fmu_common/init.d/rc.uuv_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE uuv
# MAV_TYPE_SUBMARINE 12
param set-default MAV_TYPE 12
param set-default PWM_MAIN_MAX 1950
param set-default PWM_MAIN_MIN 1050
param set-default PWM_MAIN_DISARM 1500

95
ROMFS/px4fmu_common/init.d/rc.vehicle_setup

@ -12,19 +12,9 @@ if [ $VEHICLE_TYPE = fw ] @@ -12,19 +12,9 @@ if [ $VEHICLE_TYPE = fw ]
then
if [ $MIXER = none ]
then
# Set default mixer for fixed wing if not defined.
set MIXER AERT
echo "FW mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 1 if not defined.
set MAV_TYPE 1
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@ -42,41 +32,6 @@ then @@ -42,41 +32,6 @@ then
echo "MC mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 2 if not defined.
set MAV_TYPE 2
# Use mixer to detect vehicle type
if [ $MIXER = coax ]
then
set MAV_TYPE 3
fi
if [ $MIXER = hexa_x -o $MIXER = hexa_+ ]
then
set MAV_TYPE 13
fi
if [ $MIXER = hexa_cox ]
then
set MAV_TYPE 13
fi
if [ $MIXER = octo_x -o $MIXER = octo_+ ]
then
set MAV_TYPE 14
fi
if [ $MIXER = octo_cox -o $MIXER = octo_cox_w ]
then
set MAV_TYPE 14
fi
if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ]
then
set MAV_TYPE 15
fi
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@ -91,19 +46,9 @@ if [ $VEHICLE_TYPE = rover ] @@ -91,19 +46,9 @@ if [ $VEHICLE_TYPE = rover ]
then
if [ $MIXER = none ]
then
# Set default mixer for UGV if not defined.
set MIXER rover_generic
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 10 if not defined.
set MAV_TYPE 10
echo "rover mixer undefined"
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@ -121,25 +66,6 @@ then @@ -121,25 +66,6 @@ then
echo "VTOL mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 19 if not defined.
set MAV_TYPE 19
# Use mixer to detect vehicle type.
if [ $MIXER = firefly6 ]
then
set MAV_TYPE 21
fi
if [ $MIXER = quad_x_pusher_vtol ]
then
set MAV_TYPE 22
fi
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@ -157,15 +83,6 @@ then @@ -157,15 +83,6 @@ then
echo "Airship mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 7 if not defined.
set MAV_TYPE 7
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@ -183,19 +100,11 @@ then @@ -183,19 +100,11 @@ then
echo "UUV mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set default MAV_TYPE to submarine if not defined
set MAV_TYPE 12
fi
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard vtol apps.
. ${R}etc/init.d/rc.uuv_apps
fi

3
ROMFS/px4fmu_common/init.d/rc.vtol_defaults

@ -7,6 +7,9 @@ @@ -7,6 +7,9 @@
set VEHICLE_TYPE vtol
# MAV_TYPE_VTOL_FIXEDROTOR 22
param set-default MAV_TYPE 22
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_YAW_TMT 10

29
ROMFS/px4fmu_common/init.d/rcS

@ -29,7 +29,6 @@ set IOFW "/etc/extras/px4_io-v2_default.bin" @@ -29,7 +29,6 @@ set IOFW "/etc/extras/px4_io-v2_default.bin"
set IO_PRESENT no
set LOGGER_ARGS ""
set LOGGER_BUF 8
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
@ -406,9 +405,17 @@ else @@ -406,9 +405,17 @@ else
battery_status start
fi
sensors start
commander start
fi
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
# Pre-takeoff continuous magnetometer calibration
if param compare -s MBE_ENABLE 1
then
@ -459,13 +466,6 @@ else @@ -459,13 +466,6 @@ else
fi
fi
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
#
# Play the startup tune (if not disabled or there is an error)
#
@ -493,12 +493,6 @@ else @@ -493,12 +493,6 @@ else
gimbal start
fi
# Check for flow sensor
if param compare -s SENS_EN_PX4FLOW 1
then
px4flow start -X
fi
# Blacksheep telemetry
if param compare -s TEL_BST_EN 1
then
@ -515,6 +509,12 @@ else @@ -515,6 +509,12 @@ else
gyro_calibration start
fi
# Check for px4flow sensor
if param compare -s SENS_EN_PX4FLOW 1
then
px4flow start -X &
fi
#
# Optional board supplied extras: rc.board_extras
#
@ -573,7 +573,6 @@ unset IO_PRESENT @@ -573,7 +573,6 @@ unset IO_PRESENT
unset IOFW
unset LOGGER_ARGS
unset LOGGER_BUF
unset MAV_TYPE
unset MIXER
unset MIXER_AUX
unset MIXER_FILE

2
ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
Mixer for Tailsitter with x motor configuration and elevons
===========================================================
# @board px4_fmu-v2 exclude
# @board omnibus_f4sd exclude
This file defines a single mixer for tailsitter with motors in X configuration. All controls
are mixed 100%.

6
ROMFS/px4fmu_test/init.d/rc.sensors

@ -16,15 +16,15 @@ if board_adc start @@ -16,15 +16,15 @@ if board_adc start
then
fi
if sdp3x_airspeed start -X
if sdp3x start -X
then
fi
if ms5525_airspeed start -X
if ms5525dso start -X
then
fi
if ms4525_airspeed start -X
if ms4525do start -X
then
fi

1
Tools/astyle/files_to_check_code_style.sh

@ -27,4 +27,5 @@ exec find boards msg src platforms test \ @@ -27,4 +27,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/modules/microdds_client/Micro-XRCE-DDS-Client -prune -o \
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN

30
Tools/ecl_ekf/analyse_logdata_ekf.py

@ -11,7 +11,7 @@ from pyulog import ULog @@ -11,7 +11,7 @@ from pyulog import ULog
from analysis.detectors import InAirDetector, PreconditionError
from analysis.metrics import calculate_ecl_ekf_metrics
from analysis.checks import perform_ecl_ekf_checks
from analysis.post_processing import get_estimator_check_flags
from analysis.post_processing import get_gps_check_fail_flags
def analyse_ekf(
ulog: ULog, check_levels: Dict[str, float], multi_instance: int = 0,
@ -40,6 +40,11 @@ def analyse_ekf( @@ -40,6 +40,11 @@ def analyse_ekf(
except:
raise PreconditionError('could not find estimator_status instance', multi_instance)
try:
estimator_status_flags = ulog.get_dataset('estimator_status_flags', multi_instance).data
except:
raise PreconditionError('could not find estimator_status_flags instance', multi_instance)
try:
_ = ulog.get_dataset('estimator_innovations', multi_instance).data
except:
@ -61,14 +66,14 @@ def analyse_ekf( @@ -61,14 +66,14 @@ def analyse_ekf(
'in_air_transition_time': round(in_air.take_off + in_air.log_start, 2),
'on_ground_transition_time': round(in_air.landing + in_air.log_start, 2)}
control_mode, innov_flags, gps_fail_flags = get_estimator_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
sensor_checks, innov_fail_checks = find_checks_that_apply(
control_mode, estimator_status,
estimator_status_flags, estimator_status,
pos_checks_when_sensors_not_fused=pos_checks_when_sensors_not_fused)
metrics = calculate_ecl_ekf_metrics(
ulog, innov_flags, innov_fail_checks, sensor_checks, in_air, in_air_no_ground_effects,
ulog, estimator_status_flags, innov_fail_checks, sensor_checks, in_air, in_air_no_ground_effects,
multi_instance, red_thresh=red_thresh, amb_thresh=amb_thresh)
check_status, master_status = perform_ecl_ekf_checks(
@ -78,12 +83,12 @@ def analyse_ekf( @@ -78,12 +83,12 @@ def analyse_ekf(
def find_checks_that_apply(
control_mode: dict, estimator_status: dict, pos_checks_when_sensors_not_fused: bool = False) ->\
estimator_status_flags: dict, estimator_status: dict, pos_checks_when_sensors_not_fused: bool = False) ->\
Tuple[List[str], List[str]]:
"""
finds the checks that apply and stores them in lists for the std checks and the innovation
fail checks.
:param control_mode:
:param estimator_status_flags:
:param estimator_status:
:param b_pos_only_when_sensors_fused:
:return: a tuple of two lists that contain strings for the std checks and for the innovation
@ -97,7 +102,7 @@ def find_checks_that_apply( @@ -97,7 +102,7 @@ def find_checks_that_apply(
innov_fail_checks.append('posv')
# Magnetometer Sensor Checks
if (np.amax(control_mode['yaw_aligned']) > 0.5):
if (np.amax(estimator_status_flags['cs_yaw_align']) > 0.5):
sensor_checks.append('mag')
innov_fail_checks.append('magx')
@ -106,13 +111,14 @@ def find_checks_that_apply( @@ -106,13 +111,14 @@ def find_checks_that_apply(
innov_fail_checks.append('yaw')
# Velocity Sensor Checks
if (np.amax(control_mode['using_gps']) > 0.5):
if (np.amax(estimator_status_flags['cs_gps']) > 0.5):
sensor_checks.append('vel')
innov_fail_checks.append('vel')
innov_fail_checks.append('velh')
innov_fail_checks.append('velv')
# Position Sensor Checks
if (pos_checks_when_sensors_not_fused or (np.amax(control_mode['using_gps']) > 0.5)
or (np.amax(control_mode['using_evpos']) > 0.5)):
if (pos_checks_when_sensors_not_fused or (np.amax(estimator_status_flags['cs_gps']) > 0.5)
or (np.amax(estimator_status_flags['cs_ev_pos']) > 0.5)):
sensor_checks.append('pos')
innov_fail_checks.append('posh')
@ -128,7 +134,7 @@ def find_checks_that_apply( @@ -128,7 +134,7 @@ def find_checks_that_apply(
innov_fail_checks.append('hagl')
# optical flow sensor checks
if (np.amax(control_mode['using_optflow']) > 0.5):
if (np.amax(estimator_status_flags['cs_opt_flow']) > 0.5):
innov_fail_checks.append('ofx')
innov_fail_checks.append('ofy')

5
Tools/ecl_ekf/analysis/checks.py

@ -55,7 +55,7 @@ def perform_imu_checks( @@ -55,7 +55,7 @@ def perform_imu_checks(
# perform the vibration check
imu_status['imu_vibration_check'] = 'Pass'
for imu_vibr_metric in ['imu_coning', 'imu_hfdang', 'imu_hfdvel']:
for imu_vibr_metric in ['imu_coning', 'imu_hfgyro', 'imu_hfaccel']:
mean_metric = '{:s}_mean'.format(imu_vibr_metric)
peak_metric = '{:s}_peak'.format(imu_vibr_metric)
if imu_metrics[mean_metric] > check_levels['{:s}_warn'.format(mean_metric)] \
@ -123,7 +123,8 @@ def perform_sensor_innov_checks( @@ -123,7 +123,8 @@ def perform_sensor_innov_checks(
('magy', 'magy_fail_percentage', 'mag'),
('magz', 'magz_fail_percentage', 'mag'),
('yaw', 'yaw_fail_percentage', 'yaw'),
('vel', 'vel_fail_percentage', 'vel'),
('velh', 'vel_fail_percentage', 'vel'),
('velv', 'vel_fail_percentage', 'vel'),
('posh', 'pos_fail_percentage', 'pos'),
('tas', 'tas_fail_percentage', 'tas'),
('hagl', 'hagl_fail_percentage', 'hagl'),

63
Tools/ecl_ekf/analysis/metrics.py

@ -11,7 +11,7 @@ import numpy as np @@ -11,7 +11,7 @@ import numpy as np
from analysis.detectors import InAirDetector
def calculate_ecl_ekf_metrics(
ulog: ULog, innov_flags: Dict[str, float], innov_fail_checks: List[str],
ulog: ULog, estimator_status_flags: Dict[str, float], innov_fail_checks: List[str],
sensor_checks: List[str], in_air: InAirDetector, in_air_no_ground_effects: InAirDetector,
multi_instance: int = 0, red_thresh: float = 1.0, amb_thresh: float = 0.5) -> Tuple[dict, dict, dict, dict]:
@ -20,7 +20,7 @@ def calculate_ecl_ekf_metrics( @@ -20,7 +20,7 @@ def calculate_ecl_ekf_metrics(
red_thresh=red_thresh, amb_thresh=amb_thresh)
innov_fail_metrics = calculate_innov_fail_metrics(
innov_flags, innov_fail_checks, in_air, in_air_no_ground_effects)
estimator_status_flags, innov_fail_checks, in_air, in_air_no_ground_effects)
imu_metrics = calculate_imu_metrics(ulog, multi_instance, in_air_no_ground_effects)
@ -90,10 +90,10 @@ def calculate_sensor_metrics( @@ -90,10 +90,10 @@ def calculate_sensor_metrics(
def calculate_innov_fail_metrics(
innov_flags: dict, innov_fail_checks: List[str], in_air: InAirDetector,
estimator_status_flags: dict, innov_fail_checks: List[str], in_air: InAirDetector,
in_air_no_ground_effects: InAirDetector) -> dict:
"""
:param innov_flags:
:param estimator_status_flags:
:param innov_fail_checks:
:param in_air:
:param in_air_no_ground_effects:
@ -103,17 +103,18 @@ def calculate_innov_fail_metrics( @@ -103,17 +103,18 @@ def calculate_innov_fail_metrics(
innov_fail_metrics = dict()
# calculate innovation check fail metrics
for signal_id, signal, result in [('posv', 'posv_innov_fail', 'hgt_fail_percentage'),
('magx', 'magx_innov_fail', 'magx_fail_percentage'),
('magy', 'magy_innov_fail', 'magy_fail_percentage'),
('magz', 'magz_innov_fail', 'magz_fail_percentage'),
('yaw', 'yaw_innov_fail', 'yaw_fail_percentage'),
('vel', 'vel_innov_fail', 'vel_fail_percentage'),
('posh', 'posh_innov_fail', 'pos_fail_percentage'),
('tas', 'tas_innov_fail', 'tas_fail_percentage'),
('hagl', 'hagl_innov_fail', 'hagl_fail_percentage'),
('ofx', 'ofx_innov_fail', 'ofx_fail_percentage'),
('ofy', 'ofy_innov_fail', 'ofy_fail_percentage')]:
for signal_id, signal, result in [('posv', 'reject_ver_pos', 'hgt_fail_percentage'),
('magx', 'reject_mag_x', 'magx_fail_percentage'),
('magy', 'reject_mag_y', 'magy_fail_percentage'),
('magz', 'reject_mag_z', 'magz_fail_percentage'),
('yaw', 'reject_yaw', 'yaw_fail_percentage'),
('velh', 'reject_hor_vel', 'vel_fail_percentage'),
('velv', 'reject_ver_vel', 'vel_fail_percentage'),
('posh', 'reject_hor_pos', 'pos_fail_percentage'),
('tas', 'reject_airspeed', 'tas_fail_percentage'),
('hagl', 'reject_hagl', 'hagl_fail_percentage'),
('ofx', 'reject_optflow_x', 'ofx_fail_percentage'),
('ofy', 'reject_optflow_y', 'ofy_fail_percentage')]:
# only run innov fail checks, if they apply.
if signal_id in innov_fail_checks:
@ -125,7 +126,7 @@ def calculate_innov_fail_metrics( @@ -125,7 +126,7 @@ def calculate_innov_fail_metrics(
in_air_detector = in_air
innov_fail_metrics[result] = calculate_stat_from_signal(
innov_flags, 'estimator_status', signal, in_air_detector,
estimator_status_flags, 'estimator_status_flags', signal, in_air_detector,
lambda x: 100.0 * np.mean(x > 0.5))
return innov_fail_metrics
@ -144,17 +145,27 @@ def calculate_imu_metrics(ulog: ULog, multi_instance, in_air_no_ground_effects: @@ -144,17 +145,27 @@ def calculate_imu_metrics(ulog: ULog, multi_instance, in_air_no_ground_effects:
imu_metrics[result] = calculate_stat_from_signal(
estimator_status_data, 'estimator_status', signal, in_air_no_ground_effects, np.median)
# calculates peak and mean for IMU vibration checks
for signal, result in [('vibe[0]', 'imu_coning'),
('vibe[1]', 'imu_hfdang'),
('vibe[2]', 'imu_hfdvel')]:
peak = calculate_stat_from_signal(
estimator_status_data, 'estimator_status', signal, in_air_no_ground_effects, np.amax)
if peak > 0.0:
imu_metrics['{:s}_peak'.format(result)] = peak
imu_metrics['{:s}_mean'.format(result)] = calculate_stat_from_signal(
estimator_status_data, 'estimator_status', signal,
in_air_no_ground_effects, np.mean)
for imu_status_instance in range(4):
try:
vehicle_imu_status_data = ulog.get_dataset('vehicle_imu_status', imu_status_instance).data
if vehicle_imu_status_data['accel_device_id'][0] == estimator_status_data['accel_device_id'][0]:
for signal, result in [('gyro_coning_vibration', 'imu_coning'),
('gyro_vibration_metric', 'imu_hfgyro'),
('accel_vibration_metric', 'imu_hfaccel')]:
peak = calculate_stat_from_signal(vehicle_imu_status_data, 'vehicle_imu_status', signal, in_air_no_ground_effects, np.amax)
if peak > 0.0:
imu_metrics['{:s}_peak'.format(result)] = peak
imu_metrics['{:s}_mean'.format(result)] = calculate_stat_from_signal(vehicle_imu_status_data, 'vehicle_imu_status', signal, in_air_no_ground_effects, np.mean)
except:
pass
# IMU bias checks
estimator_states_data = ulog.get_dataset('estimator_states', multi_instance).data

109
Tools/ecl_ekf/analysis/post_processing.py

@ -7,115 +7,6 @@ from typing import Tuple @@ -7,115 +7,6 @@ from typing import Tuple
import numpy as np
def get_estimator_check_flags(estimator_status: dict) -> Tuple[dict, dict, dict]:
"""
:param estimator_status:
:return:
"""
control_mode = get_control_mode_flags(estimator_status)
innov_flags = get_innovation_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
return control_mode, innov_flags, gps_fail_flags
def get_control_mode_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
:return:
"""
control_mode = dict()
# extract control mode metadata from estimator_status.control_mode_flags
# 0 - true if the filter tilt alignment is complete
# 1 - true if the filter yaw alignment is complete
# 2 - true if GPS measurements are being fused
# 3 - true if optical flow measurements are being fused
# 4 - true if a simple magnetic yaw heading is being fused
# 5 - true if 3-axis magnetometer measurement are being fused
# 6 - true if synthetic magnetic declination measurements are being fused
# 7 - true when the vehicle is airborne
# 8 - true when wind velocity is being estimated
# 9 - true when baro height is being fused as a primary height reference
# 10 - true when range finder height is being fused as a primary height reference
# 11 - true when range finder height is being fused as a primary height reference
# 12 - true when local position data from external vision is being fused
# 13 - true when yaw data from external vision measurements is being fused
# 14 - true when height data from external vision measurements is being fused
# 15 - true when synthetic sideslip measurements are being fused
# 16 - true true when the mag field does not match the expected strength
# 17 - true true when the vehicle is operating as a fixed wing vehicle
# 18 - true when the magnetometer has been declared faulty and is no longer being used
# 19 - true true when airspeed measurements are being fused
# 20 - true true when protection from ground effect induced static pressure rise is active
# 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough
# 22 - true when yaw (not ground course) data from a GPS receiver is being fused
# 23 - true when the in-flight mag field alignment has been completed
# 24 - true when local earth frame velocity data from external vision measurements are being fused
# 25 - true when we are using a synthesized measurement for the magnetometer Z component
control_mode['tilt_aligned'] = ((2 ** 0 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['yaw_aligned'] = ((2 ** 1 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_gps'] = ((2 ** 2 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_optflow'] = ((2 ** 3 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_magyaw'] = ((2 ** 4 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_mag3d'] = ((2 ** 5 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_magdecl'] = ((2 ** 6 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['airborne'] = ((2 ** 7 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['estimating_wind'] = ((2 ** 8 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_barohgt'] = ((2 ** 9 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_rnghgt'] = ((2 ** 10 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_gpshgt'] = ((2 ** 11 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evpos'] = ((2 ** 12 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evyaw'] = ((2 ** 13 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evhgt'] = ((2 ** 14 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fuse_beta'] = ((2 ** 15 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_field_disturbed'] = ((2 ** 16 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fixed_wing'] = ((2 ** 17 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_fault'] = ((2 ** 18 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fuse_aspd'] = ((2 ** 19 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['gnd_effect'] = ((2 ** 20 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['rng_stuck'] = ((2 ** 21 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['gps_yaw'] = ((2 ** 22 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_aligned_in_flight'] = ((2 ** 23 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['ev_vel'] = ((2 ** 24 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['synthetic_mag_z'] = ((2 ** 25 & estimator_status['control_mode_flags']) > 0) * 1
return control_mode
def get_innovation_check_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
:return:
"""
innov_flags = dict()
# innovation_check_flags summary
# 0 - true if velocity observations have been rejected
# 1 - true if horizontal position observations have been rejected
# 2 - true if true if vertical position observations have been rejected
# 3 - true if the X magnetometer observation has been rejected
# 4 - true if the Y magnetometer observation has been rejected
# 5 - true if the Z magnetometer observation has been rejected
# 6 - true if the yaw observation has been rejected
# 7 - true if the airspeed observation has been rejected
# 8 - true if synthetic sideslip observation has been rejected
# 9 - true if the height above ground observation has been rejected
# 10 - true if the X optical flow observation has been rejected
# 11 - true if the Y optical flow observation has been rejected
innov_flags['vel_innov_fail'] = ((2 ** 0 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['posh_innov_fail'] = ((2 ** 1 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['posv_innov_fail'] = ((2 ** 2 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magx_innov_fail'] = ((2 ** 3 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magy_innov_fail'] = ((2 ** 4 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magz_innov_fail'] = ((2 ** 5 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['yaw_innov_fail'] = ((2 ** 6 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['tas_innov_fail'] = ((2 ** 7 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['sli_innov_fail'] = ((2 ** 8 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['hagl_innov_fail'] = ((2 ** 9 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['ofx_innov_fail'] = ((2 ** 10 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['ofy_innov_fail'] = ((2 ** 11 & estimator_status['innovation_check_flags']) > 0) * 1
return innov_flags
def get_gps_check_fail_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:

56
Tools/ecl_ekf/batch_process_metadata_ekf.py

@ -48,7 +48,7 @@ for filename in os.listdir(metadata_directory): @@ -48,7 +48,7 @@ for filename in os.listdir(metadata_directory):
# # print out the check levels
# print('\n'+'The following metadata loaded from '+filename+' were used'+'\n')
# val = population_data.get(filename, {}).get('imu_hfdang_mean')
# val = population_data.get(filename, {}).get('imu_hfgyro_mean')
# print(val)
# Open pdf file for plotting
@ -90,10 +90,10 @@ population_results = { @@ -90,10 +90,10 @@ population_results = {
'ofy_fail_pct_avg':[float('NaN'),'The mean percentage of innovation test fails for the Y axis optical flow sensor'],
'imu_coning_max_avg':[float('NaN'),'The mean of the maximum in-flight values of the IMU delta angle coning vibration level (mrad)'],
'imu_coning_mean_avg':[float('NaN'),'The mean of the mean in-flight value of the IMU delta angle coning vibration level (mrad)'],
'imu_hfdang_max_avg':[float('NaN'),'The mean of the maximum in-flight values of the IMU high frequency delta angle vibration level (mrad)'],
'imu_hfdang_mean_avg':[float('NaN'),'The mean of the mean in-flight value of the IMU delta high frequency delta angle vibration level (mrad)'],
'imu_hfdvel_max_avg':[float('NaN'),'The mean of the maximum in-flight values of the IMU high frequency delta velocity vibration level (m/s)'],
'imu_hfdvel_mean_avg':[float('NaN'),'The mean of the mean in-flight value of the IMU delta high frequency delta velocity vibration level (m/s)'],
'imu_hfgyro_max_avg':[float('NaN'),'The mean of the maximum in-flight values of the IMU high frequency gyro vibration level (rad/s)'],
'imu_hfgyro_mean_avg':[float('NaN'),'The mean of the mean in-flight value of the IMU delta high frequency gyro vibration level (rad/s)'],
'imu_hfaccel_max_avg':[float('NaN'),'The mean of the maximum in-flight values of the IMU high frequency accel vibration level (m/s/s)'],
'imu_hfaccel_mean_avg':[float('NaN'),'The mean of the mean in-flight value of the IMU delta high frequency accel vibration level (m/s/s)'],
'obs_ang_median_avg':[float('NaN'),'The mean of the median in-flight value of the output observer angular tracking error magnitude (mrad)'],
'obs_vel_median_avg':[float('NaN'),'The mean of the median in-flight value of the output observer velocity tracking error magnitude (m/s)'],
'obs_pos_median_avg':[float('NaN'),'The mean of the median in-flight value of the output observer position tracking error magnitude (m)'],
@ -360,54 +360,54 @@ if (len(result1) > 0 and len(result2) > 0): @@ -360,54 +360,54 @@ if (len(result1) > 0 and len(result2) > 0):
plt.close(8)
# IMU high frequency delta angle vibration levels
temp = np.asarray([population_data[k].get('imu_hfdang_peak') for k in found_keys])
temp = np.asarray([population_data[k].get('imu_hfgyro_peak') for k in found_keys])
result1 = 1000.0 * temp[np.isfinite(temp)]
temp = np.asarray([population_data[k].get('imu_hfdang_mean') for k in found_keys])
temp = np.asarray([population_data[k].get('imu_hfgyro_mean') for k in found_keys])
result2 = 1000.0 * temp[np.isfinite(temp)]
if (len(result1) > 0 and len(result2) > 0):
population_results['imu_hfdang_max_avg'][0] = np.mean(result1)
population_results['imu_hfdang_mean_avg'][0] = np.mean(result2)
population_results['imu_hfgyro_max_avg'][0] = np.mean(result1)
population_results['imu_hfgyro_mean_avg'][0] = np.mean(result2)
plt.figure(9,figsize=(20,13))
plt.subplot(2,1,1)
plt.hist(result1)
plt.title("Gaussian Histogram - IMU HF Delta Angle Vibration Peak")
plt.xlabel("imu_hfdang_max (mrad)")
plt.title("Gaussian Histogram - IMU HF Gyroscope Vibration Peak")
plt.xlabel("imu_hfgyro_max (rad/s)")
plt.ylabel("Frequency")
plt.subplot(2,1,2)
plt.hist(result2)
plt.title("Gaussian Histogram - IMU HF Delta Angle Vibration Mean")
plt.xlabel("imu_hfdang_mean (mrad)")
plt.title("Gaussian Histogram - IMU HF Gyroscope Vibration Mean")
plt.xlabel("imu_hfgyro_mean (rad/s)")
plt.ylabel("Frequency")
pp.savefig()
plt.close(9)
# IMU high frequency delta velocity vibration levels
temp = np.asarray([population_data[k].get('imu_hfdvel_peak') for k in found_keys])
# IMU high frequency accel vibration levels
temp = np.asarray([population_data[k].get('imu_hfaccel_peak') for k in found_keys])
result1 = temp[np.isfinite(temp)]
temp = np.asarray([population_data[k].get('imu_hfdvel_mean') for k in found_keys])
temp = np.asarray([population_data[k].get('imu_hfaccel_mean') for k in found_keys])
result2 = temp[np.isfinite(temp)]
if (len(result1) > 0 and len(result2) > 0):
population_results['imu_hfdvel_max_avg'][0] = np.mean(result1)
population_results['imu_hfdvel_mean_avg'][0] = np.mean(result2)
population_results['imu_hfaccel_max_avg'][0] = np.mean(result1)
population_results['imu_hfaccel_mean_avg'][0] = np.mean(result2)
plt.figure(10,figsize=(20,13))
plt.subplot(2,1,1)
plt.hist(result1)
plt.title("Gaussian Histogram - IMU HF Delta Velocity Vibration Peak")
plt.xlabel("imu_hfdvel_max (m/s)")
plt.title("Gaussian Histogram - IMU HF Accelerometer Vibration Peak")
plt.xlabel("imu_hfaccel_max (m/s/s)")
plt.ylabel("Frequency")
plt.subplot(2,1,2)
plt.hist(result2)
plt.title("Gaussian Histogram - IMU HF Delta Velocity Vibration Mean")
plt.xlabel("imu_hfdvel_mean (m/s)")
plt.title("Gaussian Histogram - IMU HF Accelerometer Vibration Mean")
plt.xlabel("imu_hfaccel_mean (m/s/s)")
plt.ylabel("Frequency")
pp.savefig()
@ -535,12 +535,12 @@ single_log_results = { @@ -535,12 +535,12 @@ single_log_results = {
'hgt_sensor_status':['Pass','Height sensor check summary. This sensor data can be sourced from either Baro, GPS, range fidner or external vision system. A Fail result indicates a significant error that caused a significant reduction in vehicle navigation performance was detected. A Warning result indicates that error levels higher than normal were detected but these errors did not significantly impact navigation performance. A Pass result indicates that no amonalies were detected and no further investigation is required'],
'hgt_test_max':[float('NaN'),'The maximum in-flight value of the height sensor innovation consistency test ratio.'],
'hgt_test_mean':[float('NaN'),'The mean in-flight value of the height sensor innovation consistency test ratio.'],
'imu_coning_mean':[float('NaN'),'Mean in-flight value of the IMU delta angle coning vibration metric (rad)'],
'imu_coning_peak':[float('NaN'),'Peak in-flight value of the IMU delta angle coning vibration metric (rad)'],
'imu_hfdang_mean':[float('NaN'),'Mean in-flight value of the IMU delta angle high frequency vibration metric (rad)'],
'imu_hfdang_peak':[float('NaN'),'Peak in-flight value of the IMU delta angle high frequency vibration metric (rad)'],
'imu_hfdvel_mean':[float('NaN'),'Mean in-flight value of the IMU delta velocity high frequency vibration metric (m/s)'],
'imu_hfdvel_peak':[float('NaN'),'Peak in-flight value of the IMU delta velocity high frequency vibration metric (m/s)'],
'imu_coning_mean':[float('NaN'),'Mean in-flight value of the IMU delta angle coning vibration metric (rad^2)'],
'imu_coning_peak':[float('NaN'),'Peak in-flight value of the IMU delta angle coning vibration metric (rad^2)'],
'imu_hfgyro_mean':[float('NaN'),'Mean in-flight value of the IMU gyro high frequency vibration metric (rad/s)'],
'imu_hfgyro_peak':[float('NaN'),'Peak in-flight value of the IMU gyro high frequency vibration metric (rad/s)'],
'imu_hfaccel_mean':[float('NaN'),'Mean in-flight value of the IMU accel high frequency vibration metric (m/s/s)'],
'imu_hfaccel_peak':[float('NaN'),'Peak in-flight value of the IMU accel high frequency vibration metric (m/s/s)'],
'imu_sensor_status':['Pass','IMU sensor check summary. A Fail result indicates a significant error that caused a significant reduction in vehicle navigation performance was detected. A Warning result indicates that error levels higher than normal were detected but these errors did not significantly impact navigation performance. A Pass result indicates that no amonalies were detected and no further investigation is required'],
'in_air_transition_time':[float('NaN'),'The time in seconds measured from startup that the EKF transtioned into in-air mode. Set to a nan if a transition event is not detected.'],
'mag_percentage_amber':[float('NaN'),'The percentage of in-flight consolidated magnetic field sensor innovation consistency test values > 0.5.'],

8
Tools/ecl_ekf/check_level_dict.csv

@ -21,10 +21,10 @@ hagl_amber_warn_pct,5.0 @@ -21,10 +21,10 @@ hagl_amber_warn_pct,5.0
tas_amber_warn_pct,5.0
imu_coning_peak_warn,1.8E-5
imu_coning_mean_warn,3.6E-6
imu_hfdang_peak_warn,3.0E-3
imu_hfdang_mean_warn,6.0E-4
imu_hfdvel_peak_warn,9.0E-2
imu_hfdvel_mean_warn,1.8E-2
imu_hfgyro_peak_warn,12
imu_hfgyro_mean_warn,2.4
imu_hfaccel_peak_warn,360
imu_hfaccel_mean_warn,72
obs_ang_err_median_warn,8.0E-3
obs_vel_err_median_warn,0.05
obs_pos_err_median_warn,0.15

1 check_id threshold
21 tas_amber_warn_pct 5.0
22 imu_coning_peak_warn 1.8E-5
23 imu_coning_mean_warn 3.6E-6
24 imu_hfdang_peak_warn imu_hfgyro_peak_warn 3.0E-3 12
25 imu_hfdang_mean_warn imu_hfgyro_mean_warn 6.0E-4 2.4
26 imu_hfdvel_peak_warn imu_hfaccel_peak_warn 9.0E-2 360
27 imu_hfdvel_mean_warn imu_hfaccel_mean_warn 1.8E-2 72
28 obs_ang_err_median_warn 8.0E-3
29 obs_vel_err_median_warn 0.05
30 obs_pos_err_median_warn 0.15

12
Tools/ecl_ekf/check_table.csv

@ -49,12 +49,12 @@ hagl_test_mean, The mean in-flight value of the height above ground sensor innov @@ -49,12 +49,12 @@ hagl_test_mean, The mean in-flight value of the height above ground sensor innov
ofx_fail_percentage, The percentage of in-flight recorded failure events for the optical flow sensor X-axis innovation consistency test.
ofy_fail_percentage, The percentage of in-flight recorded failure events for the optical flow sensor Y-axis innovation consistency test.
filter_faults_max, Largest recorded value of the filter internal fault bitmask. Should always be zero.
imu_coning_peak, Peak in-flight value of the IMU delta angle coning vibration metric (rad)
imu_coning_mean, Mean in-flight value of the IMU delta angle coning vibration metric (rad)
imu_hfdang_peak, Peak in-flight value of the IMU delta angle high frequency vibration metric (rad)
imu_hfdang_mean, Mean in-flight value of the IMU delta angle high frequency vibration metric (rad)
imu_hfdvel_peak, Peak in-flight value of the IMU delta velocity high frequency vibration metric (m/s)
imu_hfdvel_mean, Mean in-flight value of the IMU delta velocity high frequency vibration metric (m/s)
imu_coning_peak, Peak in-flight value of the IMU delta angle coning vibration metric (rad^2)
imu_coning_mean, Mean in-flight value of the IMU delta angle coning vibration metric (rad^2)
imu_hfgyro_peak, Peak in-flight value of the IMU accel high frequency vibration metric (rad/s)
imu_hfgyro_mean, Mean in-flight value of the IMU accel high frequency vibration metric (rad/s)
imu_hfaccel_peak, Peak in-flight value of the IMU accel high frequency vibration metric (m/s/s)
imu_hfaccel_mean, Mean in-flight value of the IMU accel high frequency vibration metric (m/s/s)
output_obs_ang_err_median, Median in-flight value of the output observer angular error (rad)
output_obs_vel_err_median, Median in-flight value of the output observer velocity error (m/s)
output_obs_pos_err_median, Median in-flight value of the output observer position error (m)

1 check_id check_description
49 ofx_fail_percentage The percentage of in-flight recorded failure events for the optical flow sensor X-axis innovation consistency test.
50 ofy_fail_percentage The percentage of in-flight recorded failure events for the optical flow sensor Y-axis innovation consistency test.
51 filter_faults_max Largest recorded value of the filter internal fault bitmask. Should always be zero.
52 imu_coning_peak Peak in-flight value of the IMU delta angle coning vibration metric (rad) Peak in-flight value of the IMU delta angle coning vibration metric (rad^2)
53 imu_coning_mean Mean in-flight value of the IMU delta angle coning vibration metric (rad) Mean in-flight value of the IMU delta angle coning vibration metric (rad^2)
54 imu_hfdang_peak imu_hfgyro_peak Peak in-flight value of the IMU delta angle high frequency vibration metric (rad) Peak in-flight value of the IMU accel high frequency vibration metric (rad/s)
55 imu_hfdang_mean imu_hfgyro_mean Mean in-flight value of the IMU delta angle high frequency vibration metric (rad) Mean in-flight value of the IMU accel high frequency vibration metric (rad/s)
56 imu_hfdvel_peak imu_hfaccel_peak Peak in-flight value of the IMU delta velocity high frequency vibration metric (m/s) Peak in-flight value of the IMU accel high frequency vibration metric (m/s/s)
57 imu_hfdvel_mean imu_hfaccel_mean Mean in-flight value of the IMU delta velocity high frequency vibration metric (m/s) Mean in-flight value of the IMU accel high frequency vibration metric (m/s/s)
58 output_obs_ang_err_median Median in-flight value of the output observer angular error (rad)
59 output_obs_vel_err_median Median in-flight value of the output observer velocity error (m/s)
60 output_obs_pos_err_median Median in-flight value of the output observer position error (m)

98
Tools/ecl_ekf/plotting/pdf_report.py

@ -11,7 +11,7 @@ import numpy as np @@ -11,7 +11,7 @@ import numpy as np
from matplotlib.backends.backend_pdf import PdfPages
from pyulog import ULog
from analysis.post_processing import magnetic_field_estimates_from_states, get_estimator_check_flags
from analysis.post_processing import magnetic_field_estimates_from_states, get_gps_check_fail_flags
from plotting.data_plots import TimeSeriesPlot, InnovationPlot, ControlModeSummaryPlot, \
CheckFlagsPlot
from analysis.detectors import PreconditionError
@ -33,6 +33,11 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -33,6 +33,11 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find estimator_status instance', multi_instance)
try:
estimator_status_flags = ulog.get_dataset('estimator_status_flags', multi_instance).data
except:
raise PreconditionError('could not find estimator_status_flags instance', multi_instance)
try:
estimator_states = ulog.get_dataset('estimator_states', multi_instance).data
except:
@ -68,12 +73,13 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -68,12 +73,13 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find innovation data')
control_mode, innov_flags, gps_fail_flags = get_estimator_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
status_time = 1e-6 * estimator_status['timestamp']
status_flags_time = 1e-6 * estimator_status_flags['timestamp']
b_finishes_in_air, b_starts_in_air, in_air_duration, in_air_transition_time, \
on_ground_transition_time = detect_airtime(control_mode, status_time)
on_ground_transition_time = detect_airtime(estimator_status_flags, status_flags_time)
with PdfPages(output_plot_filename) as pdf_pages:
@ -173,9 +179,9 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -173,9 +179,9 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot control mode summary A
data_plot = ControlModeSummaryPlot(
status_time, control_mode, [['tilt_aligned', 'yaw_aligned'],
['using_gps', 'using_optflow', 'using_evpos'], ['using_barohgt', 'using_gpshgt',
'using_rnghgt', 'using_evhgt'], ['using_magyaw', 'using_mag3d', 'using_magdecl']],
status_flags_time, estimator_status_flags, [['cs_tilt_align', 'cs_yaw_align'],
['cs_gps', 'cs_opt_flow', 'cs_ev_pos'], ['cs_baro_hgt', 'cs_gps_hgt',
'cs_rng_hgt', 'cs_ev_hgt'], ['cs_mag_hdg', 'cs_mag_3d', 'cs_mag_dec']],
x_label='time (sec)', y_labels=['aligned', 'pos aiding', 'hgt aiding', 'mag aiding'],
annotation_text=[['tilt alignment', 'yaw alignment'], ['GPS aiding', 'optical flow aiding',
'external vision aiding'], ['Baro aiding', 'GPS aiding', 'rangefinder aiding',
@ -188,7 +194,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -188,7 +194,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot control mode summary B
# construct additional annotations for the airborne plot
airborne_annotations = list()
if np.amin(np.diff(control_mode['airborne'])) > -0.5:
if np.amin(np.diff(estimator_status_flags['cs_in_air'])) > -0.5:
airborne_annotations.append(
(on_ground_transition_time, 'air to ground transition not detected'))
else:
@ -197,7 +203,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -197,7 +203,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
if in_air_duration > 0.0:
airborne_annotations.append(((in_air_transition_time + on_ground_transition_time) / 2,
'duration = {:.1f} sec'.format(in_air_duration)))
if np.amax(np.diff(control_mode['airborne'])) < 0.5:
if np.amax(np.diff(estimator_status_flags['cs_in_air'])) < 0.5:
airborne_annotations.append(
(in_air_transition_time, 'ground to air transition not detected'))
else:
@ -205,7 +211,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -205,7 +211,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
(in_air_transition_time, 'in-air at {:.1f} sec'.format(in_air_transition_time)))
data_plot = ControlModeSummaryPlot(
status_time, control_mode, [['airborne'], ['estimating_wind']],
status_flags_time, estimator_status_flags, [['cs_in_air'], ['cs_wind']],
x_label='time (sec)', y_labels=['airborne', 'estimating wind'], annotation_text=[[], []],
additional_annotation=[airborne_annotations, []],
plot_title='EKF Control Status - Figure B', pdf_handle=pdf_pages)
@ -214,15 +220,15 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -214,15 +220,15 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot innovation_check_flags summary
data_plot = CheckFlagsPlot(
status_time, innov_flags, [['vel_innov_fail', 'posh_innov_fail'], ['posv_innov_fail',
'hagl_innov_fail'],
['magx_innov_fail', 'magy_innov_fail', 'magz_innov_fail',
'yaw_innov_fail'], ['tas_innov_fail'], ['sli_innov_fail'],
['ofx_innov_fail',
'ofy_innov_fail']], x_label='time (sec)',
status_flags_time, estimator_status_flags, [['reject_hor_vel', 'reject_hor_pos'], ['reject_ver_vel', 'reject_ver_pos',
'reject_hagl'],
['reject_mag_x', 'reject_mag_y', 'reject_mag_z',
'reject_yaw'], ['reject_airspeed'], ['reject_sideslip'],
['reject_optflow_x',
'reject_optflow_y']], x_label='time (sec)',
y_labels=['failed', 'failed', 'failed', 'failed', 'failed', 'failed'],
y_lim=(-0.1, 1.1),
legend=[['vel NED', 'pos NE'], ['hgt absolute', 'hgt above ground'],
legend=[['vel NE', 'pos NE'], ['vel D', 'hgt absolute', 'hgt above ground'],
['mag_x', 'mag_y', 'mag_z', 'yaw'], ['airspeed'], ['sideslip'],
['flow X', 'flow Y']],
plot_title='EKF Innovation Test Fails', annotate=False, pdf_handle=pdf_pages)
@ -250,18 +256,32 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -250,18 +256,32 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.save()
data_plot.close()
# Plot the EKF IMU vibration metrics
scaled_estimator_status = {'vibe[0]': 1000. * estimator_status['vibe[0]'],
'vibe[1]': 1000. * estimator_status['vibe[1]'],
'vibe[2]': estimator_status['vibe[2]']
}
data_plot = CheckFlagsPlot(
status_time, scaled_estimator_status, [['vibe[0]'], ['vibe[1]'], ['vibe[2]']],
x_label='time (sec)', y_labels=['Del Ang Coning (mrad)', 'HF Del Ang (mrad)',
'HF Del Vel (m/s)'], plot_title='IMU Vibration Metrics',
pdf_handle=pdf_pages, annotate=True)
data_plot.save()
data_plot.close()
for imu_status_instance in range(4):
try:
vehicle_imu_status_data = ulog.get_dataset('vehicle_imu_status', imu_status_instance).data
imu_status_time = 1e-6 * vehicle_imu_status_data['timestamp']
if vehicle_imu_status_data['accel_device_id'][0] == estimator_status['accel_device_id'][0]:
scaled_estimator_status = {'delta_angle_coning_metric': 1000. * vehicle_imu_status_data['delta_angle_coning_metric'],
'gyro_vibration_metric': vehicle_imu_status_data['gyro_vibration_metric'],
'accel_vibration_metric': vehicle_imu_status_data['accel_vibration_metric']
}
data_plot = CheckFlagsPlot(
imu_status_time, scaled_estimator_status, [['delta_angle_coning_metric'], ['gyro_vibration_metric'], ['accel_vibration_metric']],
x_label='time (sec)',
y_labels=['Del Ang Coning (mrad^2)', 'HF Gyro (rad/s)', 'HF accel (m/s/s)'],
plot_title='IMU Vibration Metrics',
pdf_handle=pdf_pages, annotate=True)
data_plot.save()
data_plot.close()
except:
pass
# Plot the EKF output observer tracking errors
scaled_innovations = {
@ -330,33 +350,33 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str @@ -330,33 +350,33 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.close()
def detect_airtime(control_mode, status_time):
def detect_airtime(estimator_status_flags, status_flags_time):
# define flags for starting and finishing in air
b_starts_in_air = False
b_finishes_in_air = False
# calculate in-air transition time
if (np.amin(control_mode['airborne']) < 0.5) and (np.amax(control_mode['airborne']) > 0.5):
in_air_transtion_time_arg = np.argmax(np.diff(control_mode['airborne']))
in_air_transition_time = status_time[in_air_transtion_time_arg]
elif (np.amax(control_mode['airborne']) > 0.5):
in_air_transition_time = np.amin(status_time)
if (np.amin(estimator_status_flags['cs_in_air']) < 0.5) and (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
in_air_transtion_time_arg = np.argmax(np.diff(estimator_status_flags['cs_in_air']))
in_air_transition_time = status_flags_time[in_air_transtion_time_arg]
elif (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
in_air_transition_time = np.amin(status_flags_time)
print('log starts while in-air at ' + str(round(in_air_transition_time, 1)) + ' sec')
b_starts_in_air = True
else:
in_air_transition_time = float('NaN')
print('always on ground')
# calculate on-ground transition time
if (np.amin(np.diff(control_mode['airborne'])) < 0.0):
on_ground_transition_time_arg = np.argmin(np.diff(control_mode['airborne']))
on_ground_transition_time = status_time[on_ground_transition_time_arg]
elif (np.amax(control_mode['airborne']) > 0.5):
on_ground_transition_time = np.amax(status_time)
if (np.amin(np.diff(estimator_status_flags['cs_in_air'])) < 0.0):
on_ground_transition_time_arg = np.argmin(np.diff(estimator_status_flags['cs_in_air']))
on_ground_transition_time = status_flags_time[on_ground_transition_time_arg]
elif (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
on_ground_transition_time = np.amax(status_flags_time)
print('log finishes while in-air at ' + str(round(on_ground_transition_time, 1)) + ' sec')
b_finishes_in_air = True
else:
on_ground_transition_time = float('NaN')
print('always on ground')
if (np.amax(np.diff(control_mode['airborne'])) > 0.5) and (np.amin(np.diff(control_mode['airborne'])) < -0.5):
if (np.amax(np.diff(estimator_status_flags['cs_in_air'])) > 0.5) and (np.amin(np.diff(estimator_status_flags['cs_in_air'])) < -0.5):
if ((on_ground_transition_time - in_air_transition_time) > 0.0):
in_air_duration = on_ground_transition_time - in_air_transition_time
else:

1
Tools/kconfig/cmake_kconfig_lut.txt

@ -139,6 +139,7 @@ mc_hover_thrust_estimator,CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y @@ -139,6 +139,7 @@ mc_hover_thrust_estimator,CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
mc_pos_control,CONFIG_MODULES_MC_POS_CONTROL=y
mc_rate_control,CONFIG_MODULES_MC_RATE_CONTROL=y
micrortps_bridge,CONFIG_MODULES_MICRORTPS_BRIDGE=y
microdds_client,CONFIG_MODULES_MICRODDS_CLIENT=y
navigator,CONFIG_MODULES_NAVIGATOR=y
px4iofirmware,CONFIG_MODULES_PX4IOFIRMWARE=y
rc_update,CONFIG_MODULES_RC_UPDATE=y

2
Tools/sitl_gazebo

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 25138e803ee8525ee5fe4e6d511506e88e3f819c
Subproject commit 48440d7b5c78a21182415266334981f1163f4b2c

5
boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig

@ -130,8 +130,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632 @@ -130,8 +130,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDIO_BLOCKSETUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@ -174,7 +173,7 @@ CONFIG_STM32_SPI1=y @@ -174,7 +173,7 @@ CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI4=y
CONFIG_STM32_SPI4_DMA=y
CONFIG_STM32_SPI4_DMA_BUFFER=1024
CONFIG_STM32_SPI4_DMA_BUFFER=512
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_SPI_DMATHRESHOLD=8
CONFIG_STM32_TIM10=y

3
boards/ark/can-flow/nuttx-config/nsh/defconfig

@ -105,8 +105,7 @@ CONFIG_SCHED_LPWORK=y @@ -105,8 +105,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

3
boards/ark/can-gps/nuttx-config/nsh/defconfig

@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y @@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

3
boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig

@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y @@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

6
boards/ark/cannode/canbootloader.px4board

@ -0,0 +1,6 @@ @@ -0,0 +1,6 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
CONFIG_BOARD_ROMFSROOT=""
CONFIG_BOARD_CONSTRAINED_MEMORY=y
CONFIG_DRIVERS_BOOTLOADERS=y
CONFIG_NSH_BUILTIN_APPS=y

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

Loading…
Cancel
Save