Compare commits

..

153 Commits

Author SHA1 Message Date
Daniel Agar
7c2eb9aa27 ekf2: preserve max variance ratio across all states 2024-07-25 17:01:39 -04:00
sbtjagu
85b6b0a406
ackermann: added delay comand support (#23445) 2024-07-25 17:13:30 +02:00
oravla5
b76c1c97b3 ekf2: Optical flow enabled by default 2024-07-25 10:01:35 +02:00
Daniel Agar
fd72578e98 ekf2: avoid constraining parameters every iteration 2024-07-25 09:51:35 +02:00
Silvan Fuhrer
ebcfb5348c Navigator: increase stack by 40 bytes
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-25 09:22:23 +02:00
Peter van der Perk
4ca3e1b6e6 mr_canhubk3: add netman in default.px4board 2024-07-24 11:39:44 -04:00
Peter van der Perk
af36c0b6ec mr_canhubk3: generate mtd_net when file is missing 2024-07-24 11:39:44 -04:00
David Sidrane
b38305dd21 CONFIG_BOARD_ROOT_PATH is not dependant on Logger only 2024-07-24 11:39:44 -04:00
David Sidrane
ab82c24e3e systemcmds:Use CONFIG_BOARD_ROOT_PATH instead of string constant 2024-07-24 11:39:44 -04:00
David Sidrane
54b20f1ff3 mavlink:Use CONFIG_BOARD_ROOT_PATH instead of string constant 2024-07-24 11:39:44 -04:00
David Sidrane
ea92c7ffcc lib:Use CONFIG_BOARD_ROOT_PATH instead of string constant 2024-07-24 11:39:44 -04:00
David Sidrane
d0d9aaa6e9 drivers:Use CONFIG_BOARD_ROOT_PATH instead of string constant 2024-07-24 11:39:44 -04:00
David Sidrane
3fa9cda505 platforms/common:Use CONFIG_BOARD_ROOT_PATH instead of string constant 2024-07-24 11:39:44 -04:00
Peter van der Perk
a99cc0a20b Remove unused kconfig symbol 2024-07-24 11:39:44 -04:00
Peter van der Perk
46e43ec725 Decouple filepaths from rcS/MTD 2024-07-24 11:39:44 -04:00
bresch
79e0e00d8c ekf2: block process noise increment without constraining the variance
The wind variance can be reset to a value larger than the wind init
variance (e.g.: when the reset occurs when flying close to the N or E
axis). Constraining the variance after a covariance initialization would
artificially increase the correlation and could destabilize the filter.
2024-07-24 17:11:53 +02:00
Marco Hauswirth
39abd87949
set best sensor to -1 after last sensor fails (#23425) 2024-07-24 11:24:07 +02:00
Stockton Slack
36d89df0a7 Fix load monitoring inconsistency bug 2024-07-22 10:33:39 +02:00
Daniel Agar
9ff6c4bf28 remove newlines 2024-07-19 18:25:43 -04:00
alexklimaj
b46b2cdf54 airframes: droneblocks dexi 5 default to CRSF on RC input with telemetry 2024-07-19 18:23:25 -04:00
Daniel Agar
85de0ff227 boards: move ARK fmu-v6x/pi6x to dedicated RC drivers 2024-07-19 15:42:05 -04:00
Daniel Agar
3a3f04c0f4 drivers/rc: new standalone ghst_rc driver
- extracted from monolithic drivers/rc_input which will eventually be
   dropped once all drivers migrated and boards updated
2024-07-19 15:42:05 -04:00
Daniel Agar
7a6c4f0bfa drivers/rc: new standalone sbus_rc driver
- extracted from monolithic drivers/rc_input which will eventually be
   dropped once all drivers migrated and boards updated
2024-07-19 15:42:05 -04:00
Daniel Agar
561dceea7b drivers/rc: new standalone dsm_rc driver
- extracted from monolithic drivers/rc_input which will eventually be
   dropped once all drivers migrated and boards updated
2024-07-19 15:42:05 -04:00
chfriedrich98
aa0dda7443 ackermann: fix naming conventions 2024-07-19 14:43:40 +02:00
chfriedrich98
f8bebd9e41 ackermann: implement pure pursuit lib 2024-07-19 14:43:40 +02:00
Matthias Grob
f2bca92221 Fix duplicate newlines at the end of files 2024-07-19 14:33:36 +02:00
Matthias Grob
7f14110bb1 Fix missing newlines at the end of files 2024-07-19 14:33:36 +02:00
Matthias Grob
fe3cd4b0cb Add check for missing or duplicate newlines at the end of files 2024-07-19 14:33:36 +02:00
Roman Bapst
1b9f1b78e5
Added support for resetting wind states to external observation (#23277)
* added support for resetting wind states to external observation

Signed-off-by: RomanBapst <bapstroman@gmail.com>

* moved wind related functions into separate file

Signed-off-by: RomanBapst <bapstroman@gmail.com>

* added VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE

Signed-off-by: RomanBapst <bapstroman@gmail.com>

* correctly compute variances

Signed-off-by: RomanBapst <bapstroman@gmail.com>

* ekf2: implement wind reset

Signed-off-by: RomanBapst <bapstroman@gmail.com>

* only allow VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE during wind dead-reckoning
and increase horizontal velocity variance to allow velocity states to move
towards solution that is aligned with the newly set wind

Signed-off-by: RomanBapst <bapstroman@gmail.com>

* only reset wind on ground

* still use wind reset using airspeed when it wasn't initialized

* exclude func for rover, change reset interface

* handle wind reset in drag-fusion

* replace state reset with variance reset in sideslip/drag fusion

* remove resetWind function

---------

Signed-off-by: RomanBapst <bapstroman@gmail.com>
Co-authored-by: Marco Hauswirth <marco.hauswirth@auterion.com>
2024-07-19 14:33:08 +02:00
Daniel Agar
ca9948a84d msgs/EstimatorStatus.msg rename mag_test_ratio -> hdg_test_ratio
- this is used for more than just mag
2024-07-18 16:39:18 +02:00
Daniel Agar
eac14b7db2 ekf2/commander: simplify navigation filter preflight checks
- remove commander test ratio "tuning knobs" (COM_ARM_EKF_{HGT,POS,VEL,YAW})
   - these are effectively redundant with the actual tuning (noise & gate)
     in the estimator, plus most users have no idea why they'd be
     adjusting these other than to silence an annoying preflight complaint
 - remove ekf2 "PreFlightChecker" with hard coded innovation limits
 - ekf2 preflight innovation flags are now simply if any active source
   exceeds half the limit preflight
2024-07-18 16:39:18 +02:00
chfriedrich98
a42dc2165c add pure pursuit library 2024-07-18 13:25:05 +02:00
chfriedrich98
08c790217d battery: increase max value for battery thresholds 2024-07-18 09:46:58 +02:00
chfriedrich98
5083ec52ec battery: migrate parameters in .c file to .yaml file 2024-07-18 09:46:58 +02:00
Daniel Agar
f8f8ddc101 ekf2: optical flow update last hor vel timestamp on success 2024-07-17 14:46:48 -04:00
Daniel Agar
691fdf713c ekf2: airspeed update last hor vel timestamp if successfully updating all states 2024-07-17 14:46:48 -04:00
Daniel Agar
57c1ba545f ekf2: fake_hgt don't use fuseVerticalPosition helper
- fake_hgt shouldn't update _time_last_hgt_fuse
2024-07-17 14:46:48 -04:00
Daniel Agar
6fe0fa6d63 ekf2: fake_pos don't use fuseHorizontalPosition helper
- fake_pos shouldn't update _time_last_hor_pos_fuse
2024-07-17 14:46:48 -04:00
Daniel Agar
c5c27a87f1
ekf2: track last terrain fuse time and update logic 2024-07-17 10:16:32 -04:00
chfriedrich98
8c4620b77e
battery: simplify battery scale calculation (#23417) 2024-07-17 12:22:52 +02:00
bresch
81575049df ekf2: reword EKF2_GPS_CHECK param 2024-07-16 10:15:19 -04:00
Daniel Agar
f832ae688d ekf2: require valid filter vz for GPS vspeed check 2024-07-16 10:15:19 -04:00
bresch
20c0d3a096 ekf2: enable all GNSS checks by default 2024-07-16 10:15:19 -04:00
bazooka joe
b48aca10a0 mc_position_control: avoid calculating arw if not needed 2024-07-16 13:30:40 +02:00
Daniel Agar
397ff4a102 ekf2: sideslip symforce increase epsilon to avoid 1/e^2 numerical issues 2024-07-16 11:10:58 +02:00
Daniel Agar
13b62a74d6 ekf2: optical flow adjust jacobian epsilon to avoid numerical issues
- in the generated code there's a 1 / eps^2 term if the height and
   terrain estimates are the same
2024-07-16 11:10:58 +02:00
Claudio Chies
76cf54c948 adapted UORB Description to match MAVLink 2024-07-16 11:07:03 +02:00
Jacob Dahl
aa8a9e3a06 laser scan subscription optional 2024-07-16 11:07:03 +02:00
Jacob Dahl
fe5a07a96d gz: added x500_lidar model for publishing obstacle_distance 2024-07-16 11:07:03 +02:00
Daniel Agar
48f1687d3a ekf2: cleanup legacy EKF solution_status_flags 2024-07-16 10:11:27 +02:00
Daniel Agar
1cd7d54170
ekf2: consolidate GNSS yaw in gnss_yaw_control.cpp and fix naming (GPS->GNSS)
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2024-07-15 12:50:51 -04:00
bresch
9d6c2baa90 ekf2-flow: only allow flow when in range
Also, as the flow makes the link between range and horizontal velocity,
only allow it to start if at least one of the two is known. Otherwise
the EKF will struggle to estimate both values at the same time.
2024-07-15 11:40:33 -04:00
Daniel Agar
8e5f28f834 ekf2: rng only reset vz as a last resort 2024-07-15 11:39:56 -04:00
Daniel Agar
80ee622f77 ekf2: baro only reset vz as a last resort 2024-07-15 11:39:56 -04:00
Daniel Agar
40349fa3dc ekf2: EV velocity control should own vertical velocity reset if height failing 2024-07-15 11:39:56 -04:00
Daniel Agar
177613eb68 ekf2: GNSS velocity control should own vertical velocity reset if height faiing
- GNSS height control using the velocity sample directly is ignoring
   potential position offsets
2024-07-15 11:39:56 -04:00
PX4 BuildBot
9bbfc8715e Update submodule mavlink to latest Mon Jul 15 12:39:00 UTC 2024
- mavlink in PX4/Firmware (abcf9ca6f0aadc91b203342db689f07630ec0e3a): da3223ff93
    - mavlink current upstream: d65952bacc
    - Changes: da3223ff93...d65952bacc

    d65952ba 2024-07-05 Peter Barker - common.xml: correct description of GLOBAL_POSIITON_INT.relative_alt frame (#2131)
5fc2ff8e 2024-06-26 Hamish Willee - Add multiplier field to docs, if present (#2125)
a13d2317 2024-06-26 Roman Bapst - Added MAV_CMD_EXTERNAL_WIND_ESTIMATE to development (#2122)
d8af87fd 2024-06-19 jokalode - Update common.xml (#2116)
2024-07-15 11:18:19 -04:00
Daniel Agar
e03aef616c
ekf2: add terrain/dist_bottom reset deltas (vehicle_local_position/vehicle_global_position) 2024-07-15 10:25:42 -04:00
Daniel Agar
a5a67315fd ekf2: optical flow magnitude check compensated
- additionally don't use flow for reset if magnitude isn't acceptable
2024-07-15 09:46:59 -04:00
Boris
be551097e0 mc_wind_estimator_tuning: Changed Quaternion package installed by requirements.txt 2024-07-15 11:40:12 +02:00
Daniel Agar
dc5f8118b0 ekf2: range finder cleanup duplicate logic 2024-07-15 11:37:36 +02:00
KonradRudin
59b96f4968
tecs: fast descend: do not shut down throttle while still climbing (#23397) 2024-07-15 10:42:43 +02:00
Liu1
b1b0032b8d
BMP581: Add Bosch BMP581 barometer (#23064)
* BMP581: Add Bosch BMP581 barometer

* Copyright:fix copyright header year

* style: not use pointers and Bool returns, Check the failed condition return

* delay: Replace usleep() with ScheduleDelayed()

* definitions: Delete unused definitions

* comment: Delet redundant comments

* constants: Change to uppercase

* BMP581: run make format
2024-07-14 14:08:20 -08:00
Matthias Grob
e2b31454a3 SubscriptionInterval: move updated, update, copy function to a cpp file
Saves 17.3 kilobytes of flash 😮
2024-07-12 23:26:24 +02:00
Claudio Chies
33be5d8356
Survey - fix of survey tracking problem on steep slopes (#23371)
* initial working

* incoperated review
2024-07-11 14:54:22 +02:00
Daniel Agar
9124a7b471 ekf2: add IMU delta_ang_dt/delta_vel_dt safety constrain before pushing into buffer 2024-07-10 21:20:47 -04:00
Daniel Agar
ac77049c47 ekf2: directly use IMU sample to find corresponding aid source sample
- I think this helps make it clear we're using a sensor sample
   corresponding with a particular IMU sample
2024-07-10 21:20:47 -04:00
Daniel Agar
f93dc61770 ekf2: use bias corrected angular velocity
- avoid unnecessarily storing _ang_rate_delayed_raw
2024-07-10 21:20:47 -04:00
Julian Oes
20137bea40 boards: add console build for Cube Orange(+)
This adds a build variant which enables the serial console, and
therefore disables the ADSB receiver.
2024-07-10 21:14:08 -04:00
Claudio Chies
57e303b11b bugfix for failing actions 2024-07-10 21:12:55 -04:00
PX4 BuildBot
e0ea91fc27 Update submodule gz to latest Thu Jul 11 00:39:09 UTC 2024
- gz in PX4/Firmware (2c3401dc8367a860cbbabc5e77898ff206f554aa): 881558c8c2
    - gz current upstream: 312cd002ff
    - Changes: 881558c8c2...312cd002ff

    312cd00 2024-07-08 chfriedrich98 - Add rover ackermann model (#46)
2024-07-10 21:05:57 -04:00
chfriedrich98
c391509c23 ackermann: add SITL airframe 2024-07-10 21:04:59 -04:00
Matthias Grob
2c3401dc83
uORB: SubscriptionInterval fix timestamp wrapping when initializing less than the interval time after boot (#23384)
* SubscriptionInterval: ensure _last_update is never before timer start
2024-07-10 12:43:31 -04:00
Daniel Agar
75bb339d94 ekf2: remove warning events logging
- some of these warning flags aren't even being used, and most of the rest we can figure out from other sources
2024-07-10 10:43:55 -04:00
Daniel Agar
c29b4ff87e ekf2: apply astyle formatting and enforce 2024-07-10 10:43:55 -04:00
chfriedrich98
3fe609f769 exclude 4017 from v5x to save flash 2024-07-10 12:06:48 +02:00
chfriedrich98
03ff837c50 ackermann: new features and improvements
added return mode support, slew rates for actuators, new ackermann specific message, improved cornering slow down effect and fixed logging issue.
2024-07-10 12:06:48 +02:00
Daniel Agar
223397c20e ekf2: always add accel/gyro bias process noise
- continue adding accel/gyro bias process noise even if inhibited
2024-07-10 11:49:01 +02:00
Marco Hauswirth
419652b9fe
EKF2: Spoofing GPS check (#23366)
* estimator gps check fail flag for spoofing

* warn whenever spoofing state changes to true, use default hysteresis to completely stop fusion

* dont introduce more GPS namings, GNSS instead

* flash: exclude mantis for cuav_x7pro
2024-07-09 16:31:11 +02:00
Daniel Agar
62ff39a669
ekf2: EV vel (body) update last fuse timestamps
- these are set by the NED fuseVelocity() helper so also need to be set in the body frame velocity case
2024-07-09 10:16:12 -04:00
Daniel Agar
5d08b97fd7 ekf2: add vehicle_local_position dist_bottom_var 2024-07-09 10:10:01 -04:00
Daniel Agar
3e3b886b5d ekf2: add terrain estimator_status_flags 2024-07-09 10:10:01 -04:00
Daniel Agar
64a6971bdb ekf2: only limit opt flow HAGL if range only terrain
- increase HALG limit from 75%->90% of sensor max
2024-07-09 10:10:01 -04:00
Daniel Agar
c56f84fe8a ekf2: range, check if terrain valid for reset on fusion timeout 2024-07-09 10:10:01 -04:00
Daniel Agar
e52025cc20 ekf2: optical flow fusion timeout only reset if quality is good 2024-07-09 10:10:01 -04:00
Daniel Agar
6be06ecbb3 ekf2: optical flow failing also reset terrain if needed 2024-07-09 10:10:01 -04:00
Daniel Agar
ea8f14b883 ekf2: optical flow logic, timeout if bad_tilt, etc
- previously we could get stuck with optical flow still technically
   active (_control_status.flags.opt_flow=true), but nothing being
updated due to excessive tilt, etc
2024-07-09 10:10:01 -04:00
Daniel Agar
8bf15b01c4 ekf2: optical flow don't compute innovation variance twice
- collapse updateOptFlow() and startFlowFusion() to avoid recomputing H
 - this is a relatively expensive call we can easily avoid with the
   right structure
2024-07-09 10:10:01 -04:00
Daniel Agar
f709ed409d ekf2: optical flow stop reset all flags 2024-07-09 10:10:01 -04:00
Daniel Agar
9dfd82ab06 ekf2: optical flow remove _flow_data_ready flag 2024-07-09 10:10:01 -04:00
Daniel Agar
7047f9441c ekf2: fix calcOptFlowBodyRateComp() gyro bias
- adjust flow sample gyro_rate immediately after popping from ring
   buffer
 - always update flow gyro bias (calcOptFlowBodyRateComp()) regardless
   of flow quality or magnitude
2024-07-09 10:10:01 -04:00
Daniel Agar
4d324da9f8 ekf2: update flow aid src status every sample 2024-07-09 10:10:01 -04:00
Daniel Agar
bcd666b3f8 ekf2: fix optical flow start logic
- remove fallthrough that enables flow regardless of success
 - add appropriate start messages for each case
2024-07-09 10:10:01 -04:00
Daniel Agar
bf4e564b23 ekf2: resetTerrainToFlow() reset aid src status appropriately 2024-07-09 10:10:01 -04:00
Daniel Agar
ced609daa8 ekf2: flow fusion start require valid fusion 2024-07-09 10:10:01 -04:00
Daniel Agar
1df8f3f9d2 ekf2: resetFlowFusion() reset aid src status appropriately 2024-07-09 10:10:01 -04:00
Roman Bapst
8221940b60
Added pitot tube icing detection (#23206)
* lib: add FilteredDerivative class

* AirspeedValidator: add first principle check

- filters throttle, pitch and airspeed rate, and triggers
if the airspeed rate is negative even though the vehicle
is pitching down and giving high throttle.
Check has to fail for duration defined by ASPD_FP_T_WINDOW
to trigger an airspeed failure.

* AirspeedValidator: define constants for first principle check

* FilteredDerivative: set initialised to false if sample interval is invalid

* airspeed_selector: improved comment

* increase IAS derivative filter time constant from 4 to 5

* use legacy parameter handling for FW_PSP_OFF

* handle FW_THR_MAX as well

* ROMFS/airframes: exclude some airframes for v6x and v4pro to save flash on them

---------

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: RomanBapst <bapstroman@gmail.com>
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-09 11:16:40 +02:00
Julian Oes
a35cecece4 gnss: add missing include
Breaks CLion otherwise.
2024-07-08 20:38:40 -04:00
Peter van der Perk
6bd81f38a6
imxrt dshot timing fix (#23365)
* imxrt: Change PLL settings for more accurate dshot timing
* Update NuttX submodule
2024-07-08 12:57:15 -04:00
Silvan Fuhrer
77709c2948 FW Position control: clean up param descriptions
Mostly to save flash, but also to improve generally.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-08 16:44:09 +02:00
Claudio Chies
aed0fd41cf
SIH - change how LAT and LON is used for Takeoff location (#23363)
change how lat long is used for SIH
2024-07-08 14:51:08 +02:00
Marco Hauswirth
4bc0286eb8
fix error from refactring commit, fix reset on ground (#23370) 2024-07-08 13:55:05 +02:00
Marco Hauswirth
e04c53241a
EKF2: reset position by fusion (#23279)
* reset position by fusion

* handle local_pos_valid for fixed wing in gnss denied

* [WIP] ekf2: setEkfGlobalOrigin respect current height reference and vertical position aiding

* global origin, also reset vertical pos without gps as ref

* fix wo gnss, that bitcraze ci passes

* revert some changes as requested

* remove duplicate reset messages

* undo unrelated whitespace changes, I'll fix it everywhere in a followup

* [SQUASH] ekf2: add vehicle_command_ack

* resetGlobalPosToExternalObservation consolidate logic

* remove gnss check from local_pos validation check

* reset when  0<accuracy<1, otherwise fuse

* replace gps param with flag

* ekf2: dead reckon time exceeded, respect ZUPT preflight if air data or optical flow expected

* subtract timeout from last inertial dead-reck, change fake pos conditions, save flash

---------

Co-authored-by: Daniel Agar <daniel@agar.ca>
2024-07-07 22:43:55 +02:00
Peter van der Perk
ac1effa32a fmu-v6xrt: MTD use full FRAM (32KB) 2024-07-05 10:25:08 -04:00
Ryan Johnston
fd8df2e84d
Update int_res_est_replay.py (#23351)
Pulls cell count, min voltage and max voltage from log file but still allows for over-rides. Also added debug info to tell user what what it found in the log and what it is using

Co-authored-by: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com>
2024-07-05 11:04:45 +02:00
Marco Hauswirth
a1f43636f3
ekf2: EV fusion in body frame (#23191) 2024-07-04 21:17:19 -04:00
Silvan Fuhrer
1f33abb4e9
battery_status.msg: remove unused fields (#22938)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-04 11:57:26 +02:00
PonomarevDA
4c5ce7af6b Cyphal: add feedback for 8 ESC 2024-07-03 13:02:18 -04:00
PonomarevDA
8569eeb90c Cyphal: add *type registers for ESC 2024-07-03 13:02:18 -04:00
PonomarevDA
f81e36a3a0 Cyphal: optimize ESC setpoint 2024-07-03 13:02:18 -04:00
PonomarevDA
41bd6c92e2 Cyphal: add zubax.telega.CompactFeedback 2024-07-03 13:02:18 -04:00
PonomarevDA
515543b1c5 Cyphal: divide EscClient into 2 publishers, so setpoint and readiness are 2 different ports now 2024-07-03 13:02:18 -04:00
Dmitry Ponomarev
52476633a8 Cyphal: use actual time instead of transfer id in uptime field of heartbeat 2024-07-03 13:02:18 -04:00
Dmitry Ponomarev
b063202b45 Cyphal: remove setpoint scaling to 8192 2024-07-03 13:02:18 -04:00
Dmitry Ponomarev
d3480d1302 Cyphal: add port.List 2024-07-03 13:02:18 -04:00
Matthias Grob
c8c46788ed Autostart: load airframes with priority ROMFS -> SD card 2024-07-03 18:32:16 +02:00
Thomas Frans
c0663ee85c gnss(septentrio): fix line lenghth of module documentation 2024-07-03 11:21:34 -04:00
Thomas Frans
e27b252433 gnss(septentrio): fix incorrect heading offset configuration
Heading offset was configured as radians but should be configured as
degrees on Septentrio receivers. The parameter was already in degrees
but the configuration logic was changing it into radians. Also allow the
entire allowed range of heading offset values for Septentrio receivers.
2024-07-03 11:21:34 -04:00
Thomas Frans
49dc896d20 gnss(septentrio): fix broken heading
Heading wasn't working because of an incorrect check during parsing.
2024-07-03 11:21:34 -04:00
Thomas Frans
bfbbf2ff6f gnss(septentrio): improve SEP_DUMP_COMM parameter documentation
The documentation for `SEP_DUMP_COMM` was quite unclear and users had to
use the user guide to find out what exactly it did. The new
documentation tries to make the purpose clearer.
2024-07-03 11:21:34 -04:00
Thomas Frans
7bb239637e gnss(septentrio): fix error on driver start with same device paths
This fixes an incorrect check of the device paths during instantiation
of the Septentrio driver that caused the driver to start and not print
an error message.
2024-07-03 11:21:34 -04:00
Thomas Frans
522a25a410 gnss(septentrio): first batch of bugfixes after internal testing
Internal testing revealed usability issues. Those and some other
problems are fixed.
2024-07-03 11:21:34 -04:00
Silvan Fuhrer
33701aa3d5 BatteryStatus: remove voltage_filtered_a
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-03 16:41:49 +02:00
Silvan Fuhrer
c2ae6a7e24 BatteryStatus: remove current_filtered_a
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-03 16:41:49 +02:00
zhangteng0526
e03e0261a1 Fix buffer overflow in mavlink_receive.cpp 2024-07-03 08:11:32 +02:00
chfriedrich98
f65653a391 battery: add internal resistance estimation 2024-07-02 19:05:13 +02:00
chfriedrich98
71029689e7 battery: add replay file for internal resistance estimation 2024-07-02 19:05:13 +02:00
Silvan Fuhrer
6d549811bc fmu v3: disable GYRO_FFT to save flash
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-07-02 11:44:54 -04:00
Marco Hauswirth
3880073716
ekf2: fix timeout after gps failure (#23346) 2024-07-02 10:38:49 -04:00
Daniel Agar
0742d356f5
ekf2: more conservative clipping checks for bad_acc_clipping fault status (#23337)
- track accel clipping count per axis
 - only set bad_acc_clipping fault_status if at least one axis is
   clipping continuously or if all have been clipping at warning level
 - Note: this doesn't impact the clipping projections that boost the
   accel process noise, pause bias estimation, and skip gravity fusion
   on a per sample basis
2024-06-28 16:45:08 -04:00
bluedisk
408d8abe95
Tools/setup: fix the wrong - deprecated - expression in the requirements.txt
- Fixes matplotlib version expression from ">=3.0.*" ro ">=3.0" which is the right syntax

Fixes issue #23329

Co-authored-by: lee wonwoo <leewonwoo@leeui-MacBookPro.local>
2024-06-28 10:20:26 -04:00
Alex Klimaj
053b4a4423
drivers/uavcan: GNSS set system time based on fix_type instead of valid_pos_cov 2024-06-27 21:35:45 -04:00
Peter van der Perk
58f7c3e9c9
NuttX with imxrt1170 soc vdd backport (#23333) 2024-06-27 16:21:45 -04:00
PX4 BuildBot
8b26e5e252 Update submodule libevents to latest Thu Jun 27 12:39:19 UTC 2024
- libevents in PX4/Firmware (4e3561cad8d24fefe66d266e969652d7ab20162b): 8d5c44661b
    - libevents current upstream: 9474657606
    - Changes: 8d5c44661b...9474657606

    9474657 2024-06-13 Beat Küng - cmake: add namespaced target & installation include dir
9f2e68d 2024-06-12 Beat Küng - CMakeLists: set CMAKE_CXX_STANDARD if not set
3204e8f 2024-06-12 Beat Küng - parser.h: use std::vector<EventArgumentDefinition>::size_type
eab8144 2024-04-29 Beat Küng - fix parser: avoid signed to unsigned conversion
159f83e 2024-04-29 Beat Küng - cpp: only enable Wall and others for GCC
2024-06-27 16:21:20 -04:00
Matthias Grob
e4446adba1 Add check for high RAM usage
We had a case where someone took off with an experimental
system with 100% RAM usage on the embedded system
without noticing. This lead to problems during flight.

Since we already have a CPU load check it seems natural
to also check the reported RAM usage.
2024-06-27 11:20:22 +02:00
Daniel Agar
30b854da35
ekf2: verbose logging control (new EKF2_LOG_VERBOSE)
- new parameter EKF2_LOG_VERBOSE to enable (currently enabled by default)
 - force advertise topics immediately (based on EKF2_LOG_VERBOSE and per aid source configuration)
 - logger optionally log all estimator topics at minimal rate
2024-06-27 01:10:57 -04:00
Patrik Dominik Pordi
8070c70f2c
uxrce_dds_client: dds_topics.yaml add vehicle_land_detected
- px4_msgs::msg::VehicleLandDetected has been added to dds_topics.yaml
2024-06-27 01:10:04 -04:00
Daniel Agar
78fd9a15f8 flight_mode_manager: delete unused avoidance waypoint 2024-06-27 01:08:16 -04:00
Daniel Agar
338bcc6ca3 ekf2: disable EKF2_EV_CTRL and EKF2_AGP_CTRL by default 2024-06-26 17:10:28 -04:00
alexklimaj
9cc4e2ac01 boards ark pi6x add vl53l0x 2024-06-26 17:09:37 -04:00
Silvan Fuhrer
1ae96d6509 EKF2: fix builds without CONFIG_EKF2_RANGE_FINDER
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-06-26 11:05:38 +02:00
bresch
a50ef2eb5e ekf2-terrain: make terrain validity based on uncertainty
When using optical flow for terrain aiding, we cannot assume that the
terrain estimate is valid if flow is fused as is can only be observed
during motion. When no direct observation is available, the terrain is
assumed to be valid if its 1sigma uncertainty is < 10% of the hagl.
2024-06-26 11:05:38 +02:00
bresch
a665764b0e ekf2: remove unused EKF2_TERR_MASK 2024-06-26 11:05:38 +02:00
bresch
7903ddf5df ekf2-terrain: terrain is not a separate estimator 2024-06-26 11:05:38 +02:00
bresch
9001c23926 ekf2: clean up hagl vs terrain naming
Terrain is the state: terrain vertical position
Hagl (height above ground level) is the vertical distance between the
vertical position and the terrain vertical position
2024-06-26 11:05:38 +02:00
bresch
68980b59e2 ekf2: add terrain state 2024-06-26 11:05:38 +02:00
KonradRudin
09f066a73a
mission: skip a vtol takoff mission item if already in air (#23319)
* mission: skip a vtol takoff mission item if already in air and a fixed wing

* MissionBase: also skip FW takeoff when already in-air

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

* mission: use setNextMissionItem to skip vtol takeoff when already in air

* mission: Only skip the VTOL takeoff in air for mission and rtl mission

If flying RTL mission reverse it must still include the takeoff point.

---------

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
2024-06-25 16:33:45 +02:00
Nate
6fd0e98a69 Correct units of CRSF GPS altitude
Bug fix to correct returning mm units of altitude to m.
2024-06-24 12:27:21 +02:00
David Sidrane
e8e8a60ca8 NuttX with backport of stm32h7 No phy 2024-06-24 06:12:12 -04:00
Matthias Grob
8cc7c99b59
mavlink: report generator error (#23313)
Without this flag the command silently succeeds even though the logs contains
an error. It's much more developer friendly to fail early in case of an error.
The log path is then also shown in the console output.
2024-06-24 10:00:03 +02:00
Daniel Agar
30ce560e3a ekf2: mag control reset filtered test ratio on start (if aligning yaw) 2024-06-20 13:41:54 -04:00
Daniel Agar
dcb1103299 ekf2: move estimator_status test ratios to filtered values 2024-06-20 13:41:54 -04:00
600 changed files with 11189 additions and 6046 deletions

View File

@ -16,6 +16,7 @@ jobs:
matrix:
check: [
"check_format",
"check_newlines",
"tests",
"tests_coverage",
"px4_fmu-v2_default stack_check",

View File

@ -54,4 +54,3 @@ jobs:
AWS_REGION: 'us-west-1'
SOURCE_DIR: 'build/${{ matrix.target }}/_metadata/'
DEST_DIR: 'Firmware/${{ env.version }}/${{ matrix.target }}/'

View File

@ -11,6 +11,8 @@ on:
jobs:
build:
runs-on: ubuntu-latest
env:
ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true
strategy:
fail-fast: false
matrix:

View File

@ -11,6 +11,8 @@ on:
jobs:
build:
runs-on: ubuntu-latest
env:
ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true
strategy:
fail-fast: false
matrix:

View File

@ -2,4 +2,4 @@
{
"name": "PX4 detect"
}
]
]

11
Kconfig
View File

@ -185,6 +185,17 @@ menu "Serial ports"
string "EXT2 tty port"
endmenu
menu "File paths"
config BOARD_ROOT_PATH
string "PX4 Root file path"
default "/fs/microsd"
config BOARD_PARAM_FILE
string "Parameter file"
default "/fs/mtd_params"
endmenu
menu "drivers"
source "src/drivers/Kconfig"
endmenu

View File

@ -379,9 +379,9 @@ doxygen:
@$(PX4_MAKE) -C "$(SRC_DIR)"/build/doxygen
@touch "$(SRC_DIR)"/build/doxygen/Documentation/.nojekyll
# Astyle
# Style
# --------------------------------------------------------------------
.PHONY: check_format format
.PHONY: check_format format check_newlines
check_format:
$(call colorecho,'Checking formatting with astyle')
@ -392,6 +392,10 @@ format:
$(call colorecho,'Formatting with astyle')
@"$(SRC_DIR)"/Tools/astyle/check_code_style_all.sh --fix
check_newlines:
$(call colorecho,'Checking for missing or duplicate newlines at the end of files')
@"$(SRC_DIR)"/Tools/astyle/check_newlines.sh
# Testing
# --------------------------------------------------------------------
.PHONY: tests tests_coverage tests_mission tests_mission_coverage tests_offboard tests_avoidance

View File

@ -120,6 +120,7 @@ add_custom_command(
${romfs_gen_root_dir}/init.d/rc.serial
${romfs_gen_root_dir}/init.d/rc.autostart
${romfs_gen_root_dir}/init.d/rc.autostart.post
${romfs_gen_root_dir}/init.d/rc.filepaths
${romfs_copy_stamp}
COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}/*
COMMAND ${CMAKE_COMMAND} -E tar xf ${romfs_tar_file}
@ -131,6 +132,9 @@ add_custom_command(
--rc-dir ${romfs_gen_root_dir}/init.d
--serial-ports ${board_serial_ports} ${added_arguments}
--config-files ${module_config_files} #--verbose
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/filepaths/generate_config.py
--rc-dir ${romfs_gen_root_dir}/init.d
--params-file ${CONFIG_BOARD_PARAM_FILE}
COMMAND ${CMAKE_COMMAND} -E touch ${romfs_copy_stamp}
WORKING_DIRECTORY ${romfs_gen_root_dir}
DEPENDS ${romfs_tar_file}
@ -320,6 +324,7 @@ add_custom_target(romfs_gen_files_target
DEPENDS
${romfs_copy_stamp}
${romfs_gen_root_dir}/init.d/rc.serial
${romfs_gen_root_dir}/init.d/rc.filepaths
romfs_extras.stamp
)

View File

@ -21,25 +21,14 @@ set R /
#
ver all
if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params
then
set PARAM_FILE /fs/mtd_params
fi
if mft query -q -k MTD -s MTD_PARAMETERS -v /dev/eeeprom0
then
set PARAM_FILE /dev/eeeprom0
fi
if mft query -q -k MTD -s MTD_PARAMETERS -v /mnt/qspi/params
then
set PARAM_FILE /mnt/qspi/params
fi
# Load param file location from kconfig
. ${R}etc/init.d/rc.filepaths
#
# Load parameters.
#
param select $PARAM_FILE
if ! param load
then
param reset_all

View File

@ -29,4 +29,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

View File

@ -30,4 +30,3 @@ param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default EKF2_RNG_A_HMAX 10

View File

@ -94,4 +94,3 @@ param set-default CA_METHOD 0
# disable attitude failure detection
param set-default FD_FAIL_P 0
param set-default FD_FAIL_R 0

View File

@ -12,4 +12,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

View File

@ -30,4 +30,3 @@ param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default LPE_FUSION 242

View File

@ -18,4 +18,3 @@ param set-default LPE_FUSION 132
# AEQ: External heading set to use vision input
param set-default ATT_EXT_HDG_M 1

View File

@ -41,4 +41,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104

View File

@ -61,4 +61,3 @@ param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 106
param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108

View File

@ -68,5 +68,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@ -71,4 +71,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@ -55,4 +55,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@ -54,4 +54,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@ -55,4 +55,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@ -62,4 +62,3 @@ param set-default PWM_MAIN_FUNC7 202
param set-default PWM_MAIN_FUNC8 203
param set-default PWM_MAIN_FUNC9 206
param set-default PWM_MAIN_REV 256

View File

@ -78,4 +78,3 @@ param set-default VT_FWD_THRUST_EN 4
param set-default VT_FWD_THRUST_SC 1
param set-default VT_F_TRANS_THR 0.75
param set-default VT_TYPE 2

View File

@ -75,4 +75,3 @@ param set-default VT_F_TRANS_DUR 1.5
param set-default VT_TYPE 0
param set-default WV_EN 0

View File

@ -88,4 +88,3 @@ param set-default PWM_MAIN_FUNC11 422
param set-default RC_MAP_AUX1 8
param set-default RC_MAP_AUX2 9
param set-default RC_MAP_AUX3 10

View File

@ -31,4 +31,3 @@ param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101

View File

@ -38,4 +38,3 @@ param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101

View File

@ -41,4 +41,3 @@ param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102

View File

@ -64,4 +64,3 @@ param set-default PWM_MAIN_FUNC4 203
param set-default PWM_MAIN_FUNC5 407
param set-default PWM_MAIN_FUNC6 408
param set-default PWM_MAIN_FUNC7 409

View File

@ -69,4 +69,3 @@ param set-default PWM_MAIN_FUNC4 203
param set-default PWM_MAIN_FUNC5 407
param set-default PWM_MAIN_FUNC6 408
param set-default PWM_MAIN_FUNC7 409

View File

@ -36,4 +36,3 @@ param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 201
param set-default PWM_MAIN_FUNC4 103

View File

@ -0,0 +1,47 @@
#!/bin/sh
# @name Rover Ackermann
# @type Rover
# @class Rover
. ${R}etc/init.d/rc.rover_ackermann_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=rover}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=rover_ackermann}
param set-default SIM_GZ_EN 1 # Gazebo bridge
# Rover parameters
param set-default NAV_ACC_RAD 0.5
param set-default RA_ACC_RAD_GAIN 2
param set-default RA_ACC_RAD_MAX 3
param set-default RA_LOOKAHD_GAIN 1
param set-default RA_LOOKAHD_MAX 10
param set-default RA_LOOKAHD_MIN 1
param set-default RA_MAX_ACCEL 1.5
param set-default RA_MAX_JERK 15
param set-default RA_MAX_SPEED 3
param set-default RA_MAX_STR_ANG 0.5236
param set-default RA_MAX_STR_RATE 360
param set-default RA_MISS_VEL_DEF 3
param set-default RA_MISS_VEL_GAIN 5
param set-default RA_MISS_VEL_MIN 1
param set-default RA_SPEED_I 0.01
param set-default RA_SPEED_P 2
param set-default RA_WHEEL_BASE 0.321
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
# Wheels
param set-default SIM_GZ_WH_FUNC1 101
param set-default SIM_GZ_WH_MIN1 0
param set-default SIM_GZ_WH_MAX1 200
param set-default SIM_GZ_WH_DIS1 100
# Steering
param set-default SIM_GZ_SV_FUNC1 201
param set-default SIM_GZ_SV_REV 1

View File

@ -0,0 +1,10 @@
#!/bin/sh
#
# @name Gazebo x500 lidar
#
# @type Quadrotor
#
PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_lidar}
. ${R}etc/init.d-posix/airframes/4001_gz_x500

View File

@ -63,4 +63,3 @@ param set-default PWM_MAIN_FUNC9 422
# Landing gear
param set-default PWM_MAIN_FUNC10 400
param set-default PWM_MAIN_FUNC11 400

View File

@ -119,4 +119,3 @@ param set-default CA_METHOD 0
# disable attitude failure detection
param set-default FD_FAIL_P 0
param set-default FD_FAIL_R 0

View File

@ -83,6 +83,8 @@ px4_add_romfs_files(
4009_gz_r1_rover
4010_gz_x500_mono_cam
4011_gz_lawnmower
4012_gz_rover_ackermann
4013_gz_x500_lidar
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post

View File

@ -15,6 +15,9 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
if [ -n "${PX4_HOME_LON}" ]; then
param set SIH_LOC_LON0 ${PX4_HOME_LON}
fi
if [ -n "${PX4_HOME_ALT}" ]; then
param set SIH_LOC_H0 ${PX4_HOME_ALT}
fi
if simulator_sih start; then

View File

@ -157,6 +157,7 @@ param set-default CBRK_SUPPLY_CHK 894281
# disable check, no CPU load reported on posix yet
param set-default COM_CPU_MAX -1
param set-default COM_RAM_MAX -1
# Don't require RC calibration and configuration
param set-default COM_RC_IN_MODE 1

View File

@ -44,4 +44,3 @@ param set-default CA_ROTOR4_KM -0.05
param set-default CA_ROTOR5_PX 0.25
param set-default CA_ROTOR5_PY -0.433
param set-default CA_ROTOR5_PZ 0.05

View File

@ -119,5 +119,3 @@ param set-default PWM_MAIN_TIM0 50
param set-default PWM_MAIN_DIS1 1500
param set-default PWM_MAIN_DIS2 1500
param set-default PWM_MAIN_DIS4 1500

View File

@ -32,4 +32,3 @@ param set-default CA_SV_TL0_MAXA 45
param set-default CA_SV_TL0_MINA -45
param set-default CA_SV_TL0_TD 90
param set-default CA_SV_TL_COUNT 1

View File

@ -24,5 +24,3 @@ param set-default MC_PITCHRATE_D 0
param set-default MC_PITCHRATE_FF 0.1
param set-default CA_AIRFRAME 10

View File

@ -23,4 +23,3 @@ param set-default MAV_0_MODE 1
param set-default MAV_0_CONFIG 102
param set-default GPS_UBX_DYNMODEL 8
param set-default SER_TEL2_BAUD 9600

View File

@ -72,5 +72,3 @@ param set-default PWM_MAIN_DIS5 1000
param set-default PWM_MAIN_DIS6 1500
param set-default PWM_MAIN_DIS7 1500
param set-default PWM_MAIN_DIS8 1500

View File

@ -66,4 +66,3 @@ param set-default CA_ROTOR11_PX -0.344
param set-default CA_ROTOR11_PY -0.25
param set-default CA_ROTOR11_PZ -0.05
param set-default CA_ROTOR11_KM -0.05

View File

@ -38,4 +38,3 @@ param set-default CA_SV_CS_COUNT 1
param set-default CA_SV_CS0_TRQ_P 1
param set-default CA_R_REV 7

View File

@ -6,6 +6,7 @@
# @class Copter
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v5x exclude
# @board bitcraze_crazyflie exclude
#
# @maintainer Iain Galloway <iain.galloway@nxp.com>

View File

@ -7,6 +7,10 @@
#
# @maintainer
# @board px4_fmu-v2 exclude
# @board cuav_x7pro exclude
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
#
. ${R}etc/init.d/rc.mc_defaults
@ -36,7 +40,6 @@ param set-default COM_RC_LOSS_T 3
# ekf2
param set-default EKF2_TERR_MASK 1
param set-default EKF2_BARO_NOISE 2
param set-default EKF2_BCOEF_X 31.5

View File

@ -12,6 +12,7 @@
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
# @board bitcraze_crazyflie exclude
# @board cuav_x7pro exclude
#

View File

@ -10,6 +10,7 @@
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
# @board bitcraze_crazyflie exclude
# @board cuav_x7pro exclude
#

View File

@ -8,6 +8,7 @@
# @maintainer Oleg Kalachev <okalachev@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board px4_fmu-v4pro exclude
# @board bitcraze_crazyflie exclude
#

View File

@ -25,7 +25,6 @@
param set-default BAT1_CAPACITY 4000
param set-default BAT1_N_CELLS 6
param set-default BAT1_V_EMPTY 3.3
param set-default BAT1_V_LOAD_DROP 0.5
param set-default BAT_AVRG_CURRENT 13
# Square quadrotor X PX4 numbering
@ -69,6 +68,9 @@ param set-default MPC_THR_MIN 0.025
param set-default MPC_VEL_MANUAL 5.0
param set-default MPC_XY_VEL_MAX 8.0
param set-default RC_CRSF_PRT_CFG 300
param set-default RC_CRSF_TEL_EN 1
param set-default RTL_RETURN_ALT 15
param set-default SENS_FLOW_MINHGT 0.0

View File

@ -13,6 +13,7 @@
# @board px4_fmu-v4pro exclude
# @board px4_fmu-v5 exclude
# @board px4_fmu-v5x exclude
# @board px4_fmu-v6x exclude
# @board diatone_mamba-f405-mk2 exclude
#
. ${R}etc/init.d/rc.mc_defaults

View File

@ -48,5 +48,3 @@ param set-default PWM_MAIN_FUNC1 201
param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101

View File

@ -42,4 +42,3 @@ param set-default CA_ROTOR3_KM 0
param set-default CA_ROTOR3_PX 0
param set-default CA_ROTOR3_PY -0.3
param set-default CA_ROTOR3_PZ 0.3

View File

@ -31,5 +31,3 @@ param set-default CA_ROTOR4_PY 0.25
param set-default CA_ROTOR5_PX -0.43
param set-default CA_ROTOR5_PY -0.25
param set-default CA_ROTOR5_KM -0.05

View File

@ -123,4 +123,3 @@ param set-default PWM_MAIN_FUNC6 106
param set-default PWM_MAIN_TIM0 -1
param set-default PWM_MAIN_TIM1 -1
param set-default PWM_MAIN_TIM2 -1

View File

@ -31,5 +31,3 @@ param set-default CA_ROTOR4_PY -0.43
param set-default CA_ROTOR5_PX -0.25
param set-default CA_ROTOR5_PY 0.43
param set-default CA_ROTOR5_KM -0.05

View File

@ -36,5 +36,3 @@ param set-default CA_ROTOR6_PY -0.46
param set-default CA_ROTOR7_KM -0.05
param set-default CA_ROTOR7_PX -0.19
param set-default CA_ROTOR7_PY 0.46

View File

@ -36,4 +36,3 @@ param set-default CA_ROTOR6_PY -0.5
param set-default CA_ROTOR7_KM -0.05
param set-default CA_ROTOR7_PX 0
param set-default CA_ROTOR7_PY 0.5

View File

@ -1,9 +1,6 @@
#!/bin/sh
# Standard apps for a ackermann drive rover.
# Start the attitude and position estimator.
ekf2 start &
# Start rover ackermann drive controller.
rover_ackermann start

View File

@ -120,14 +120,8 @@ then
. $FRC
else
#
# Set the parameter file the board supports params on
# MTD device.
#
if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params
then
set PARAM_FILE /fs/mtd_params
fi
# Load param file location from kconfig
. ${R}etc/init.d/rc.filepaths
# Check if /fs/mtd_params is a valid BSON file
if ! bsondump docsize /fs/mtd_caldata
@ -217,25 +211,31 @@ else
fi
unset BOARD_RC_DEFAULTS
#
# Set parameters and env variables for selected SYS_AUTOSTART.
#
set AUTOSTART_PATH etc/init.d/rc.autostart
# Load airframe configuration based on SYS_AUTOSTART parameter
if ! param compare SYS_AUTOSTART 0
then
if param greater SYS_AUTOSTART 1000000
# rc.autostart directly run the right airframe script which sets the VEHICLE_TYPE
# Look for airframe in ROMFS
. ${R}etc/init.d/rc.autostart
if [ ${VEHICLE_TYPE} == none ]
then
# Use external startup file
# Look for airframe on SD card
if [ $SDCARD_AVAILABLE = yes ]
then
set AUTOSTART_PATH etc/init.d/rc.autostart_ext
. ${R}etc/init.d/rc.autostart_ext
else
echo "ERROR [init] SD card not mounted - trying to load airframe from ROMFS"
echo "ERROR [init] SD card not mounted - can't load external airframe"
fi
fi
. ${R}$AUTOSTART_PATH
if [ ${VEHICLE_TYPE} == none ]
then
echo "ERROR [init] No airframe file found for SYS_AUTOSTART value"
param set SYS_AUTOSTART 0
tune_control play error
fi
fi
unset AUTOSTART_PATH
# Check parameter version and reset upon airframe configuration version mismatch.
# Reboot required because "param reset_all" would reset all "param set" lines from airframe.

View File

@ -45,7 +45,7 @@ function [ center, radii, evecs, v ] = ellipsoid_fit( X, flag, equals )
% * center - ellispoid center coordinates [xc; yc; zc]
% * ax - ellipsoid radii [a; b; c]
% * evecs - ellipsoid radii directions as columns of the 3x3 matrix
% * v - the 9 parameters describing the ellipsoid algebraically:
% * v - the 9 parameters describing the ellipsoid algebraically:
% Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1
%
% Author:
@ -59,7 +59,7 @@ end
if flag == 2 && nargin == 2
equals = 'xy';
end
if size( X, 2 ) ~= 3
error( 'Input data must have three columns!' );
else
@ -69,7 +69,7 @@ else
end
% need nine or more data points
if length( x ) < 9 && flag == 0
if length( x ) < 9 && flag == 0
error( 'Must have at least 9 points to fit a unique ellipsoid' );
end
if length( x ) < 6 && flag == 1
@ -91,7 +91,7 @@ if flag == 0
2 * x .* z, ...
2 * y .* z, ...
2 * x, ...
2 * y, ...
2 * y, ...
2 * z ]; % ndatapoints x 9 ellipsoid parameters
elseif flag == 1
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1
@ -99,7 +99,7 @@ elseif flag == 1
y .* y, ...
z .* z, ...
2 * x, ...
2 * y, ...
2 * y, ...
2 * z ]; % ndatapoints x 6 ellipsoid parameters
elseif flag == 2
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1,
@ -127,7 +127,7 @@ else
% fit sphere in the form A(x^2 + y^2 + z^2) + 2Gx + 2Hy + 2Iz = 1
D = [ x .* x + y .* y + z .* z, ...
2 * x, ...
2 * y, ...
2 * y, ...
2 * z ]; % ndatapoints x 4 sphere parameters
end
@ -170,5 +170,3 @@ else
radii = ( sqrt( gam ./ v( 1:3 ) ) )';
evecs = eye( 3 );
end

19
Tools/astyle/check_newlines.sh Executable file
View File

@ -0,0 +1,19 @@
#!/usr/bin/env bash
return_value=0
# Check if there are files checked in that don't end in a newline (POSIX requirement)
git grep --cached -Il '' | xargs -L1 bash -c 'if test "$(tail -c 1 "$0")"; then echo "No new line at end of $0"; exit 1; fi'
if [ $? -ne 0 ]; then
return_value=1
fi
# Check if there are files checked in that have duplicate newlines at the end (fail trailing whitespace checks)
git grep --cached -Il '' | xargs -L1 bash -c 'if tail -c 2 "$0" | ( read x && read y && [ x"$x" = x ] && [ x"$y" = x ]); then echo "Multiple newlines at the end of $0"; exit 1; fi'
if [ $? -ne 0 ]; then
return_value=1
fi
exit $return_value

View File

@ -18,7 +18,8 @@ exec find boards msg src platforms test \
-path src/lib/events/libevents -prune -o \
-path src/lib/parameters/uthash -prune -o \
-path src/lib/wind_estimator/python/generated -prune -o \
-path src/modules/ekf2/EKF -prune -o \
-path src/modules/ekf2/EKF/python/ekf_derivation/generated -prune -o \
-path src/modules/ekf2/EKF/yaw_estimator/derivation/generated -prune -o \
-path src/modules/gyro_fft/CMSIS_5 -prune -o \
-path src/modules/mavlink/mavlink -prune -o \
-path test/mavsdk_tests/catch2 -prune -o \

View File

@ -170,4 +170,3 @@ if(__name__ == "__main__"):
fs.write(f.read())
except:
pass

View File

@ -139,7 +139,3 @@ def find_checks_that_apply(
innov_fail_checks.append('ofy')
return sensor_checks, innov_fail_checks

View File

@ -54,7 +54,7 @@ def calculate_sensor_metrics(
# calculates peak, mean, percentage above 0.5 std, and percentage above std metrics for
# estimator status variables
for signal, result_id in [('hgt_test_ratio', 'hgt'),
('mag_test_ratio', 'mag'),
('hdg_test_ratio', 'mag'),
('vel_test_ratio', 'vel'),
('pos_test_ratio', 'pos'),
('tas_test_ratio', 'tas'),

View File

@ -84,4 +84,4 @@ def main() -> None:
if __name__ == '__main__':
main()
main()

View File

@ -160,7 +160,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot normalised innovation test levels
# define variables to plot
variables = [['mag_test_ratio'], ['vel_test_ratio', 'pos_test_ratio'], ['hgt_test_ratio']]
variables = [['hdg_test_ratio'], ['vel_test_ratio', 'pos_test_ratio'], ['hgt_test_ratio']]
y_labels = ['mag', 'vel, pos', 'hgt']
legend = [['mag'], ['vel', 'pos'], ['hgt']]
if np.amax(estimator_status['hagl_test_ratio']) > 0.0: # plot hagl test ratio, if applicable
@ -223,7 +223,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.save()
data_plot.close()
# plot innovation_check_flags summary
# plot innovation flags summary
data_plot = CheckFlagsPlot(
status_flags_time, estimator_status_flags, [['reject_hor_vel', 'reject_hor_pos'], ['reject_ver_vel', 'reject_ver_pos',
'reject_hagl'],

View File

@ -0,0 +1,61 @@
#!/usr/bin/env python3
""" Script to generate Serial rc.filepaths for the ROMFS startup script """
import argparse
import os
import sys
try:
from jinja2 import Environment, FileSystemLoader
except ImportError as e:
print("Failed to import jinja2: " + str(e))
print("")
print("You may need to install it using:")
print(" pip3 install --user jinja2")
print("")
sys.exit(1)
try:
import yaml
except ImportError as e:
print("Failed to import yaml: " + str(e))
print("")
print("You may need to install it using:")
print(" pip3 install --user pyyaml")
print("")
sys.exit(1)
parser = argparse.ArgumentParser(description='Generate PX4 ROMFS filepaths')
parser.add_argument('--config-files', type=str, nargs='*', default=[],
help='YAML module config file(s)')
parser.add_argument('--constrained-flash', action='store_true',
help='Reduce verbosity in ROMFS scripts to reduce flash size')
parser.add_argument('--rc-dir', type=str, action='store',
help='ROMFS output directory', default=None)
parser.add_argument('--params-file', type=str, action='store',
help='Parameter output file', default=None)
parser.add_argument('-v', '--verbose', dest='verbose', action='store_true',
help='Verbose Output')
args = parser.parse_args()
verbose = args.verbose
constrained_flash = args.constrained_flash
rc_filepaths_output_dir = args.rc_dir
rc_filepaths_template = 'rc.filepaths.jinja'
jinja_env = Environment(loader=FileSystemLoader(
os.path.dirname(os.path.realpath(__file__))))
# generate the ROMFS script using a jinja template
if rc_filepaths_output_dir is not None:
rc_filepath_output_file = os.path.join(rc_filepaths_output_dir, "rc.filepaths")
if verbose: print("Generating {:}".format(rc_filepath_output_file))
template = jinja_env.get_template(rc_filepaths_template)
with open(rc_filepath_output_file, 'w') as fid:
fid.write(template.render(constrained_flash=constrained_flash, params_file=args.params_file))
else:
raise Exception("--rc-dir needs to be specified")

View File

@ -0,0 +1,6 @@
{# jinja template to generate the serial autostart script. #}
# serial autostart script generated with generate_serial_config.py
set PARAM_FILE {{ params_file }}

View File

@ -243,4 +243,3 @@ def main():
if __name__ == '__main__':
main()

View File

@ -282,4 +282,3 @@ def main():
if __name__ == '__main__':
main()

View File

@ -107,4 +107,4 @@ plt.show()
##plt.plot(airspeed_corrected,(airspeed_corrected-airspeed_raw)/airspeed_corrected)
##plt.xlabel('airspeed [m/s]')
##plt.ylabel('relative error [-]')
##plt.show()
##plt.show()

View File

@ -47,4 +47,4 @@ for field in spec.parsed_fields():
"main_orb_id": @( all_topics.index(name_snake_case) if name_snake_case in all_topics else -1 ),
"dependencies": @( json.dumps(list(set(dependencies))) ),
"name": "@( spec.full_name )"
}
}

View File

@ -1 +1 @@
__all__ = ["srcscanner", "srcparser", "xmlout", "rcout"]
__all__ = ["srcscanner", "srcparser", "xmlout", "rcout"]

View File

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

View File

@ -330,4 +330,3 @@ if serial_params_output_file is not None:
fid.write(template.render(serial_devices=serial_devices,
ethernet_configuration=ethernet_configuration,
commands=commands, serial_ports=serial_ports))

View File

@ -30,4 +30,3 @@ unset PRT
unset PRT_F
unset BAUD_PARAM
unset MAV_ARGS

View File

@ -70,4 +70,3 @@ PARAM_DEFINE_INT32({{ command.port_param_name }}, {{ command.default_port }});
{% endfor -%}
{% endif %}

View File

@ -7,7 +7,7 @@ jinja2>=2.8
jsonschema
kconfiglib
lxml
matplotlib>=3.0.*
matplotlib>=3.0
numpy>=1.13
nunavut>=1.1.0
packaging

@ -1 +1 @@
Subproject commit 881558c8c274d0d9f21970de24333122e050b561
Subproject commit 312cd002ff9602644efef58eef93e447c10dcbe8

View File

@ -24,4 +24,4 @@ q8jVArPNQT4R2erSmKmIGTRkLMG7CzUmwk1taHdSvzcmUyL4uYc5QBSubxat6gWh
+a85AoGBAKgfnjjVoAWWvqEDLpfGPmE8lW+RaS7i5ff6QsSBx7uTEnHq6RNHuVnN
et4pR87yIENeG8jMBiDCj8AGDtUNt9Ps9vWCPrf9HSOYoBUk+gZagU/9N+RBpuCM
egoxtxIHM7HI+XIer+ZnZpVpgr+EoCaL7avx6k/susLQb7tqSBt1
-----END RSA PRIVATE KEY-----
-----END RSA PRIVATE KEY-----

View File

@ -1 +1 @@
{"date": "Tue Nov 3 13:02:09 2020", "public": "4db0c20105552a3cd7fbaf5cba7ab0811b3663db28525edb1436f2578d02b7fd", "private": "734d597e7d8ab0a1d0d64b95083aa6bee34b46b9e6e76dac1e363af114f12d15"}
{"date": "Tue Nov 3 13:02:09 2020", "public": "4db0c20105552a3cd7fbaf5cba7ab0811b3663db28525edb1436f2578d02b7fd", "private": "734d597e7d8ab0a1d0d64b95083aa6bee34b46b9e6e76dac1e363af114f12d15"}

View File

@ -125,4 +125,3 @@ def main():
if __name__ == '__main__':
main()

View File

@ -50,4 +50,3 @@ for json_file in json_files:
except:
print("JSON validation for {:} failed (schema: {:})".format(json_file, schema_file))
raise

View File

@ -65,4 +65,3 @@ for yaml_file in yaml_files:
print(validator.errors)
print("")
raise Exception("Validation of {:} failed".format(yaml_file))

View File

@ -37,4 +37,3 @@ constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(1),
initI2CBusExternal(2),
};

View File

@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BATT_SMBUS=y
@ -31,7 +32,7 @@ CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_RC=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y

View File

@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
@ -20,7 +21,7 @@ CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y
CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_RC=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2

View File

@ -8,4 +8,3 @@ echo "uploading: $PX4_BINARY_FILE"
PX4_BINARY_FILE_SIZE=$(stat -c%s "$PX4_BINARY_FILE")
curl -v -F "image=@$PX4_BINARY_FILE" -H "Expect:" -H "File-Size:$PX4_BINARY_FILE_SIZE" http://192.168.42.1/cgi-bin/upload

View File

@ -374,4 +374,3 @@
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
*/

View File

@ -81,4 +81,3 @@ int BBBlueRcPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs)
return ret;
}

View File

@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@ -105,4 +105,3 @@ __EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@ -0,0 +1 @@
# Same as default, only defconfig is different

View File

@ -12,4 +12,3 @@ icm20948 -s -b 4 -R 10 -M start
# SPI1
ms5611 -s -b 1 start
icm20649 -s -b 1 start

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