Commit Graph

33395 Commits

Author SHA1 Message Date
Samuel Sadok ee75ebac8c
Adds Smart Return To Home capability by recording the flight path in a memory optimimized format. This means the UAV can return to home by using only known-good flight paths.
The flight graph is stored as a series of delta elements at 1m resolution and a list of nodes. Both lists share the same buffer. Each delta element takes up 2 bytes or sometimes 6 bytes if the delta is large. The path can consist of multiple disconnected segments, in which case the gaps are stored as delta elements with a jump-bit set.

Once in a while or when required the graph is consolidated, which means:
 - Points that lie roughly in a line are replaced by a single line
 - Points that lie close to previously recorded lines are pruned
 - For lines that pass close to each other a node element is created

Furthermore:
 - The graph is recorded at a higher precision closer to home
 - If the graph becomes full, the overall precision is reduced and the whole graph is re-consolidated
 - If the graph becomes full once more, all data is removed except for the shortest path home at that moment. One of these actions is repeated at each subsequent fill-up.

Path finding information is generated/refreshed on demand and stored in the nodes. During return-to-home, the best direction to home is continuously evaluated by using the information stored in the nodes.

The graph recording and path finding is implemented in navigator/tracker.cpp.
The graph based return-to-home is implemented in navigator/smart_rtl.cpp.
2020-10-04 12:16:45 -04:00
Daniel Agar eabbd19c1c commander: PreFlightCheck param_find all parameters immediately
- this ensures the relevant parameters are marked active immediately
before parameter sync
 - fixes https://github.com/PX4/Firmware/issues/15872
2020-10-03 14:43:21 -04:00
blazczak 57da61dc17
posix-configs/rpi: Fix mavlink over UART (/dev/ttyAMA0)
UART is the primary interface for telemetry radio: https://docs.emlid.com/navio2/ardupilot/hardware-setup/#uart-radio

Check first if /dev/ttyUSB0 exists (https://docs.emlid.com/navio2/ardupilot/hardware-setup/#usb-radio); if not, fall back to configuring over UART (/dev/ttyAMA0).

Use stricter check for character special file (-c) rather than just file (-f).

'console=serial0,115200' needs to be removed from /cmdline.txt as additional configuration step. This should be documented in the Navio2 section of docs.px4.io. Presumably, this is already performed as part of the Raspberry Pi OS prebuilt image Emlid spins.
2020-10-03 10:51:27 -04:00
Beat Küng 91fa2002e3 kakutef7: fix output ordering
Regression from d2254c2e44, I overlooked that they were defined in
reverse order.
2020-10-03 10:45:30 -04:00
Daniel Agar 8ee0c62e57
examples: add Gyro FFT using CMSIS 5 on Cortex-m (#15104)
- this is a work in progress experiment to compute real time FFTs from raw gyro FIFO data on Cortex-m hardware (stm32f4/f7/h7, etc)
2020-10-02 11:47:27 -04:00
Daniel Agar 23aa9ac70f cmake nuttx add STM32H7 debug helpers 2020-10-02 11:31:18 -04:00
Alex Mikhalev c648d52909 uavcan: Increase uavcan main stack size
I observed stack overflows when executing `uavcan params list`, so the
stack size probably needs to be increased.

Signed-off-by: Alex Mikhalev <alexmikhalevalex@gmail.com>
2020-10-02 01:31:27 -04:00
SalimTerryLi 25eca31e3a
New board Scumaker AirPi HAT for Raspberry Pi B series 2020-10-01 11:22:47 -04:00
Nicolas MARTIN 967f741a0e
commander: add parameter COM_REARM_GRACE to optionally disable re-arming grace period 2020-10-01 11:20:08 -04:00
Daniel Agar c1936dab1f commander: accel & gyro subsystem health set within IMU check 2020-09-30 12:17:48 -04:00
Daniel Agar 25c537bae9 commander: don't impose additional timeouts in sensor checks
- the sensors hub is responsible for sensor timeouts
2020-09-30 12:17:48 -04:00
CarlOlsson 98c8cbb27f ekf2: fix odom body rate sign bug 2020-09-30 11:34:37 -04:00
Julian Oes b454095776 commander: fix switch to loiter
Sometimes, the mission_result timestamp is the same as the
internal_state timestamp which would meant that we would not switch to
LOITER even though the takeoff is clearly done at that point.
2020-09-30 08:23:16 -04:00
David Sidrane 46f0388fc7 Reanable BL Update - Reverts b5267c06073023893d5a11b9011ef009b5291097 2020-09-29 23:44:24 -04:00
David Sidrane 68703135c3 bl_update:Respect page size if it matters
Track Changes in NuttX stm32h7 flash driver:
   The STM32H7 flash driver uses up_progmem_pagesize to
   describe minimum write size to satify the block size
   requierment for ECC.

   Therefore, the image size needs to be padded to a multiple
   of up_progmem_pagesize()
2020-09-29 23:44:24 -04:00
JaeyoungLim ff6b82cb6b
Replace xacro macros to jinja templates for multivehicle (#15831)
This commit switches xacro macros to jinja templates for multivehicle simulations.
2020-09-29 15:45:57 +02:00
JaeyoungLim 9d3e159e65
Make mavsdk test runner handle generated sdf files (#15797)
Update sitl_gazebo
Fix indent errors
Fix syntax error
Fix indentation errors
Fix syntax errors
use autopep8
2020-09-29 15:44:58 +02:00
Daniel Agar c9c20666a2
sensors: sanity check differential pressure temperature (#15845)
- if valid temperature unavailable then use ICAO Standard Atmosphere 15 degrees celcius
2020-09-29 09:35:34 -04:00
Nicolas Martin da4d0e650a mc_pos_control: fix acc Z sign 2020-09-29 13:09:51 +02:00
Daniel Agar 24ffed827f
ROMFS: 50000_generic_ground_vehicle remove fmu-v2 exclude
- this allows px4_fmu-v2_rover to function until we have a better mechanism for including or excluding ROMFS dependencies #15711
2020-09-28 22:43:28 -04:00
David Sidrane 59f20a26eb motor_params:Move to mixer_module
sensors having mixer_module creates a dependency on sensors for
   the param MOT_SLEW_MAX. Things that do not uses sensors.
   IE. PWM only device should not have to include them.
2020-09-28 20:47:40 -04:00
Daniel Agar f1feaf45d3
EKF2: move vehicle_odometry publish to method 2020-09-28 18:34:49 -04:00
Daniel Agar faccb0d948
Jenkins: HIL script minor improvements
- periodically send newline while checking for output or command completion (back to nsh prompt)
 - mtd test
 - fix adc test (now board_adc)
2020-09-28 16:41:28 -04:00
JaeyoungLim c342ab91b3 Fix the world path being corrupting when spawning none-default world
This fixes a bug, where the world file path was being corrupted when using non-default world paths
2020-09-28 13:07:29 -04:00
JaeyoungLim f7356d0286 Update jsbsim_bridge to latest master 2020-09-28 13:05:20 -04:00
Daniel Agar fe6a1ce882
simulator: fix airspeed temperature
- HIL_SENSOR temperature is only being sent with barometer data
2020-09-28 12:56:56 -04:00
Daniel Agar 828134c56f
sensor_calibration: add link dependencies 2020-09-28 12:26:38 -04:00
David Sidrane 529d816a39 px4_fmu-v6x:Support ETM Hardware Trace 2020-09-28 10:59:39 -04:00
PX4 BuildBot 1822a678f6 Update submodule ecl to latest Mon Sep 28 12:39:19 UTC 2020
- ecl in PX4/Firmware (2b34fec0844646d13a57f78dbbed44b53813919e): 6b99ea2a60
    - ecl current upstream: 4c2355a638
    - Changes: 6b99ea2a60...4c2355a638

    4c2355a 2020-09-25 Daniel Agar - EKF: use GPS to lookup declination from WMM before full GPS checks pass
2020-09-28 10:58:33 -04:00
Daniel Agar cf26f24387
msg: add quaternion euler angle pretty print 2020-09-28 10:13:43 -04:00
justas- bb77f55f7b motor_test: Use 1-based motor indexing.
Motors in Px4 ecosystem are indexed using 1-based indexing (Airframe reference, dshot command, etc.) motor_test command is 0-based. This PR changes motor_test to use 1-based indexing.

This PR refers to Github issue #15721.
2020-09-28 10:59:41 +02:00
flochir ec7108892b
batt_smbus: fix potential hardfault by checking buffer sizes (#15789)
* Added buffer length check to SMBus::block_read (triggered hardfault in batt_smbus module by writing beyond buffer end due to device returning longer byte_count than requested/expected)

Co-authored-by: Florian Olbrich <florian.olbrich@scarabot.de>
Co-authored-by: Daniel Agar <daniel@agar.ca>
Co-authored-by: BazookaJoe1900 <BazookaJoe1900@gmail.com>
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2020-09-28 09:41:40 +02:00
Daniel Agar 6a08e16351
Update submodule mavlink v2.0 to latest Sat Sep 26 15:30:19 UTC 2020
- mavlink v2.0 in PX4/Firmware (aab65cdc3261a4ca315d5b91d65e0dd3e39940d0): 09524c98db
    - mavlink v2.0 current upstream: e3d00c4436
    - Changes: 09524c98db...e3d00c4436

Co-authored-by: PX4 BuildBot <bot@px4.io>
2020-09-26 13:14:25 -04:00
PX4 BuildBot 6df50cb74f Update submodule ecl to latest Sat Sep 26 15:30:31 UTC 2020
- ecl in PX4/Firmware (5784cb6e5eb74fcf07f3da058692c7c2320851b9): fab242a81f
    - ecl current upstream: 6b99ea2a60
    - Changes: fab242a81f...6b99ea2a60

    6b99ea2 2020-09-24 Daniel Agar - ECL standalone build improve ECL_INFO/WARN/DEBUG
5879eaa 2020-09-25 bresch - ekf: fix variable length array error
99aafba 2020-09-14 Daniel Agar - README: remove obsolete build status
2020-09-26 13:13:51 -04:00
Tanja Baumann b5ebdb8e41
add system command to get and set system time
* add system_time command for all boards
2020-09-26 13:09:01 -04:00
PX4 BuildBot b5df4f76cc Update submodule nuttx to latest Sat Sep 26 15:30:26 UTC 2020
- nuttx in PX4/Firmware (59f5b841a6646a7ae514ae1139ba18c3f787ceb3): a8b7ca869e
    - nuttx current upstream: 0fe69f6cc0
    - Changes: a8b7ca869e...0fe69f6cc0

    0fe69f6cc0 2020-09-25 David Sidrane - [BACKPORT] stm32f7:serial Bug Fix: Ensure next buffer is processed
2020-09-26 09:47:03 -07:00
Jacob Dahl a24488328f
Move GPS blending from ekf2 to sensors module
- new sensors work item that subscribes to N x sensor_gps and publishes vehicle_gps_position
 - blending is now configurable with SENS_GPS_MASK and SENS_GPS_TAU

Co-authored-by: Jacob Crabill <jacob@volans-i.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
2020-09-25 23:28:31 -04:00
Daniel Agar e792c46f20
mavlink: increase stack 2650 -> 2848 bytes (#15821) 2020-09-25 21:42:02 -04:00
Daniel Agar f37d0a85e2
Jenkins: remove remaining SITL tests (MC_avoidance/MC_safe_landing)
- MC_avoidance and MC_safe_landing are currently failing intermittently and will be migrated to Github Actions
2020-09-25 12:28:26 -04:00
Daniel Agar 861e06dfd7
mavlink: handle receiving GENERATOR_STATUS
- only published (ORB_ID(generator_status)) and logged for now
2020-09-25 11:36:58 -04:00
Daniel Agar c57a48682e
Tools: ecl analysis handle estimator_innovations/estimator_innovation_variances size inconsistencies 2020-09-25 10:35:01 -04:00
Daniel Agar 2ccf664e95 commander: disarm from safety relax land detector timeout
- ensure land detector is updated before safety is checked
2020-09-25 09:41:53 -04:00
jaeyoung 1dbd7df83b Switch VERBOSE to VERBOSE_SIM
This changes the environment variable `VERBOSE` to `VERBOSE_SIM`, to explicitly state that it configures the verbose output of the simulation
2020-09-25 10:42:35 +02:00
Daniel Agar 60252dde08 Jenkins: SITL tests disable ninja build to reduce build parallelism
- test slaves have limited memory
2020-09-24 15:56:57 -04:00
Daniel Agar bbdc57a662 cmake: remove sitl_gazebo build -j2
- allow ninja build to automatically determine parallelism
2020-09-24 15:56:57 -04:00
Matthias Grob bcbc761bf6 Revert "Change defaults for MPC_LAND_ALT"
This reverts commit 59bd3e9f6e.
2020-09-24 19:18:58 +02:00
Daniel Agar 0dc8bb9c86
uORB: increase ORB_MULTI_MAX_INSTANCES 4 -> 10
- put more realistic bounds on maximum number of battery instances, gps, etc
2020-09-24 11:01:28 -04:00
Daniel Agar f04f0c89ca boards: CUAV Nora/X7pro fix BOARD_DSHOT_MOTOR_ASSIGNMENT
- BOARD_DSHOT_MOTOR_ASSIGNMENT isn't needed if there's no remapping
2020-09-24 10:53:54 -04:00
Daniel Agar 762d925d20 boards: cubepilot orange/yellow fix BOARD_DSHOT_MOTOR_ASSIGNMENT 2020-09-24 10:53:54 -04:00
Matthias Grob 5d47a4c9e0
Commander: fix rc override threshold scaling (#15807)
Improve parameter description for threshold
and lower the threshold a bit.
2020-09-24 14:52:19 +02:00