Compare commits

...

72 Commits

Author SHA1 Message Date
Matthias Grob 42221483c4 vehicle_status: Remove duplicate failure detector status 2022-07-12 16:07:38 +02:00
Matthias Grob fb455c8f4b vehicle_status: reorder message definition
for readability. No functional changes.
2022-07-12 15:50:49 +02:00
Daniel Agar 19b9b052ab uavcan: GNSS optionally publish RTCMStream or MovingBaselineData 2022-07-12 08:15:15 -04:00
Daniel Agar a73efd9c4f NuttX carry minimal c++ cmath (replacing Matrix stdlib_imports.hpp) 2022-07-12 08:05:06 -04:00
Daniel Agar fe22167512 differential_pressure/sdp3x: sdp3x_main fix 'keep running' regression 2022-07-12 09:11:57 +02:00
RomanBapst a23cb111b7 added comment for cruising throttle only affecting rover
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst b7d6e646cc FixedWingPositionControl: better naming for manual airspeed setpoint
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst c2f5ffdfcd log tecs trim throttle
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst 92cdff6798 TECS: rename airspeed/throttle "cruise" to "trim"
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst b57d3c6d74 TECS: set true airspeed rate setpoint to zero if airspeed is not enabled
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst 6dbea21ef5 TECS: renamed airspeed cruse to airspeed trim & general cleanup
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst c05e0f076b FixedWingPositionControl: do not pass trim throttle via position setpoint triplet
- trim throttle is handled entirely by the position controller
- navigator should use speed setpoints
- added flag gliding_enabled in position setpoint to stills support gliding

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst cae7e1b88b improved trim throttle compensation
- allow compensation based on vehicle weight (parameterized)
- use density for calculating trim throttle compensation instead of pressure
- removed parameter FW_THR_ALT_SCL

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
RomanBapst 461d0561b8 replace FW_THR_CRUISE with FW_THR_TRIM
Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-12 09:07:20 +02:00
marcirsch 226b8a6f90 README: Updated links to point to main branch instead of master. Fixed broken links
Signed-off-by: marcirsch <marcell@auterion.com>
2022-07-12 08:38:05 +02:00
Matthias Grob 10a2b4c9f7 commander_helper: typo in set_tune() description 2022-07-08 14:51:15 +02:00
Junwoo Hwang f66c3914f6 Give priority to power off tune over other tunes (e.g. Battery Low)
Make Power Off tune not interruptable

This solves the case of Low Battery warning tune overriding the power
off tune, as now the Power off tune is not interruptable by any other
tune unless override flag is specified

commander_helper: resolve "redundant boolean literal in ternary expression result"
2022-07-08 14:51:15 +02:00
Junwoo Hwang 652b153383 Cleanup set_tune() functions in the commander_helper
- Existing code was hard to read and quite ambiguous
- Also it allowed constantly re-sending the tune_control request for a
fixed duration tunes like "TUNE_ID_BATTERY_WARNING_SLOW", while not
respecting the tune duration
2022-07-08 14:51:15 +02:00
bresch 3b26c611af mpc: add sideways and backward speed for manual position modes 2022-07-08 14:03:44 +02:00
bresch 1de38c88d9 mpc: use xy stick limiting function from library 2022-07-08 14:03:44 +02:00
Igor Mišić 7e9a45a01a uavcan/sensors/battery: add multiple battery filter instances 2022-07-08 10:03:11 +02:00
Igor Mišić 90e2ac60ce uavcan/sensors/battery: add the option to filter raw data
Useful for power modules that send just pure voltage and current without algorithmic prediction of voltage drop, time estimation, etc.
2022-07-08 10:03:11 +02:00
Igor Mišić 27b65481ba uavcan/sensors/battery: refactoring _battery_status name 2022-07-08 10:03:11 +02:00
Junwoo Hwang 0eeb699af8 Convert add 'Hz' suffix to PWM50, PWM400, ... protocol names
* To avoid confusion as to what the number after the 'PWM' part means
when setting it up in the Actuators Tab
2022-07-08 08:15:13 +02:00
bresch 2f486c37fc ekf2: start airspeed fusion when test ratio is passing only
When wind is already estimated, we don't reset the states using airspeed
data, so it could be that the fusion fails if the airspeed isn't
consistent with the filter (test ratio > 1). In this case, don't start
the fusion.

When wind isn't already estimated, the wind states are reset using
airspeed so the fusion can start regardless of the current test ratio.
2022-07-07 17:39:06 -04:00
Daniel Agar e1933f6ade ROMFS: execute rc.autostart (airframes) before starting dataman 2022-07-07 11:37:39 -04:00
Daniel Agar f591988f32 drivers/actuators: modalai_esc driver
Co-authored-by: Travis Bottalico <travis@modalai.com>
Co-authored-by: akushley <akushley>
2022-07-07 10:32:52 -04:00
Daniel Agar fe9af6769c commander add GPS warnings (GPS invalid if flying and jamming critical) 2022-07-07 10:24:11 -04:00
Daniel Agar 15223009d2 combine sensor_gps + vehicle_gps_position msgs (keeping separate topics) 2022-07-07 10:24:11 -04:00
Junwoo Hwang 32ae00fd44 Move Vehicle Command Result Enum defs to Vehicle Command Ack (#19729)
- As it is always only used for the vehicle command ack message
- It was a duplicate, hence making it error prone for maintainment
- The uORB message comments were updated to make the relationship with
the MAVLink message / enum definitions clear
2022-07-07 16:15:11 +02:00
bresch af4038aa7e ekf2: publish estimator_aid_src_airspeed 2022-07-07 09:42:54 -04:00
bresch 2fd87c47e8 ekf2: use estimator_aid_source_1d message for airspeed fusion
split the fusion process into:
1. updateAirspeed: computes innov, innov_var, obs_var, ...
2. fuseAirspeed: uses data computed in 1. to generate K, H and fuse the
   observation
2022-07-07 09:42:54 -04:00
bresch 503aa87957 ekf2_derivation: create functions to generate innov_var or HK only
This is required when the innovation variance computation and the fusion
are performed in two different functions.
2022-07-07 09:42:54 -04:00
Junwoo Hwang 6225fae1d6 Increase Battery level emergency shutdown time delay
from 300 ms to 60 seconds, to give enough time for the user to configure
the vehicle in the mean time.

This is needed especially when the battery cell count setting is wrong
(when it should be 3, but set to 4 for example), since then whenever you
boot the vehicle, it will shutdown after 300 ms, which leaves the user
puzzled as to exactly what's happening. And it also prevented the user
from changing the Parameter since it's shutting down so quickly.

60 second window is intended to be a reasonable time that will allow the
user to figure out what's going on (via checking the battery level on
QGC, etc) but also not deep discharge the battery to a dangerous level.
2022-07-07 15:09:41 +02:00
Chuck 4528341069 sagetech_mxs: Adding fixes for crashes due to ADSB vehicle list initialization failure
Co-authored-by: cfaber <chuck.faber@sagetech.com>
2022-07-06 21:19:46 -04:00
RomanBapst 44f98ac355 standard: fixed pusher assist in hover
- in hover mode the pusher assist is already set in update_mc_state()

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-06 16:07:55 +02:00
Beat Küng 7022d59a54 ROMFS: fix incremental build for airframe processing
Fixes the error:
Aborting due to missing @type tag in file: 'build/px4_fmu-v5_test/etc/init.d/airframes/11001_hexa_cox'

This can happen due to a change to e.g. board_serial_ports, which changes
the CLI command and triggers a re-execution of the airframe processing.
2022-07-06 07:50:18 -04:00
Beat Küng 6f8663ac62 mcp23009: add drivers__device cmake dependency
needed for device::I2C
2022-07-06 07:50:18 -04:00
RomanBapst 42cd0b4ce0 FlightTaskAuto: don't override landing gear state for takeoff
- this allows landing gear to retract automatically when doing a takeoff
and the vehicle is considered high enough

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-06 11:11:14 +02:00
Thomas Debrunner 42c562b748 gps: Increase param name buffer to address warning in newer gccs (#19876) 2022-07-06 10:20:31 +02:00
Silvan Fuhrer b0490b9f6b ROMFS: assign all 4 tilts to motors to have them all tilt
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-07-06 09:04:52 +02:00
Matthias Grob a3288ff732 Commander: run ekf checks without grace period after boot 2022-07-05 10:35:07 -04:00
Matthias Grob 8deebd07b8 preArmCheck: Shorten messages to to not write "Arming denied!" 2022-07-05 10:35:07 -04:00
bresch 3d01b5aa11 ekf2_derivation: use unsimplified q->rot for observation equations 2022-07-05 14:25:35 +02:00
bresch 28b34a634b ekf2_derivation: do not print null equations 2022-07-05 14:25:35 +02:00
bresch 78dd557b26 ekf2_derivation: automatically replace pow function 2022-07-05 14:25:35 +02:00
bresch 11f78a3686 ekf2_derivation: update generated equations with SymPy 1.10.1 2022-07-05 14:25:35 +02:00
Igor Mišić dff946c39a usr_mcu_version: add missing headers 2022-07-05 09:29:26 +02:00
Igor Mišić 89c287581b boards/px4/fmu-v6c: update to extended hw_ver_rev format 2022-07-05 09:29:26 +02:00
Igor Mišić 4b503c310e Merge PR #19575 (changes to pr-extendend_hw_ver_rev_format)
- 4096 of 3 hex digits each for rev and ver is enough.
    #defines used in SPI versions do not be long format, use use the macro
 - Board provides a prefix and the formatting is sized and built in
 - No need for funky board_get_base_eeprom_mtd_manifest interface
    Original mft is used where the abstraction is done with the MFT interface

Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
2022-07-05 09:29:26 +02:00
Igor Mišić f7d542e720 boards/sky-drones: update to extended hw_ver_rev format 2022-07-05 09:29:26 +02:00
Igor Mišić 4ea8527304 board/fmu-v5x: reverse order for start boards to shorten the command 2022-07-05 09:29:26 +02:00
Igor Mišić 8b77d68028 board/fmu-v5x: add new board version V5X00100001 2022-07-05 09:29:26 +02:00
David Sidrane 00e82c9060 board_hw_eeprom_rev_ver:Versioning hierarchy 2022-07-05 09:29:26 +02:00
Igor Mišić ec1614d156 boards: update id string from V5X{0-a}{0-a} to V5X{xxxx}{xxxx}
boards: new format for hwtypecmp string
boards: update manifest.c to follow the new hw_ver_rev format
2022-07-05 09:29:26 +02:00
David Sidrane 49d63958a8 platforms/common/spi:Support 16 bit of VER and REV 2022-07-05 09:29:26 +02:00
Igor Mišić b938215c2b board_hw_info: add set and get functions for hw_version to/from eeprom 2022-07-05 09:29:26 +02:00
Igor Mišić dd38ced7c4 fmu-v5x: use mtd to get hw info from base EEPROM 2022-07-05 09:29:26 +02:00
Igor Mišić cc63c49a51 px4_manifest: add function declaration for get base EEPROM mtd 2022-07-05 09:29:26 +02:00
Igor Mišić 3463b725a5 px4_manifest: fix px4_mft_s to accept multiple manifests 2022-07-05 09:29:26 +02:00
Igor Mišić 432b664acc px4_mtd: fix instantiation for multiple mtds 2022-07-05 09:29:26 +02:00
Igor Mišić 08a9e49f3e px4_mtd: update eeprom at24c driver to initialize multiple instances 2022-07-05 09:29:26 +02:00
Daniel Agar efde738826 ekf2: update EKF2_EV_DELAY default to 0 2022-07-04 11:44:53 -04:00
Matthias Grob 21f858de1f drv_pwm_output: remove not used anymore define for presumed servo middle position 2022-07-04 16:34:58 +02:00
Matthias Grob af4b8bfd60 linux_pwm_out: sync configuration logic from FMU and IO 2022-07-04 16:34:58 +02:00
Matthias Grob 8ccd40185a PWMOut/px4io: use disarmed values as default failsafe values
to avoid surprises where upon disarm an ESC can suddenly spool up
even though it stops when disarmed and no specific failsafe value is configured.
2022-07-04 16:34:58 +02:00
Michael Schaeuble 85a5dd87cd Remove camera capture GPIO interrupt when the rate is higher than 5kHz
If the capture GPIO is exposed to a signal with high frequency changes, a lot of
interrupts are scheduled and the handling of these call can worst-case
starve flight critical processes leading to a loss of control. Since camera capture
is not flight critical, we now give up the capture
functionality and stop the interrupts to prevent the starvation of other processes.
2022-07-04 11:32:33 +02:00
Igor Mišić 941c47fb19 Remove logging rate limit for pps_capture
In case of a signal issue on the PPS GPIO it is helpful to have logging
data with higher rates.
2022-07-04 11:32:33 +02:00
Michael Schaeuble 5abee359d6 Remove PPS GPIO interrupt when the rate is higher than 20Hz
If the PPS GPIO is exposed to a signal with high frequency changes, a lot of
interrupts are scheduled and the handling of these calls can worst-case
starve flight critical processes leading to a loss of
control. Since PPS is not flight critical, we now give up the PPS
functionality and stop the interrupts to prevent the starvation of other processes.
2022-07-04 11:32:33 +02:00
Jaeyoung-Lim 55eed0e125 Remove multirotor mixer include from MC Ratecontro;
This commit removes multirotormixer includes since it is not being used
2022-07-03 19:20:19 -04:00
Daniel Agar c9b6047124 platforms/nuttx/CMakeLists.txt add STM32H743VI SVD/debug 2022-07-03 11:38:01 -04:00
Daniel Agar 7f76761657 uavcannode: schedule to run on log_message publications
- this is a precaution to minimize message latency and potential lost messages
2022-07-01 09:18:17 -04:00
258 changed files with 7004 additions and 3965 deletions
+33 -33
View File
@@ -6,38 +6,38 @@
[![Slack](/.github/slack.svg)](https://join.slack.com/t/px4/shared_invite/zt-si4xo5qs-R4baYFmMjlrT4rQK5yUnaA)
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/master/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones.
PX4 is highly portable, OS-independent and supports Linux, NuttX and MacOS out of the box.
* Official Website: http://px4.io (License: BSD 3-clause, [LICENSE](https://github.com/PX4/PX4-Autopilot/blob/master/LICENSE))
* [Supported airframes](https://docs.px4.io/master/en/airframes/airframe_reference.html) ([portfolio](http://px4.io/#airframes)):
* [Multicopters](https://docs.px4.io/master/en/frames_multicopter/)
* [Fixed wing](https://docs.px4.io/master/en/frames_plane/)
* [VTOL](https://docs.px4.io/master/en/frames_vtol/)
* [Autogyro](https://docs.px4.io/master/en/frames_autogyro/)
* [Rover](https://docs.px4.io/master/en/frames_rover/)
* [Supported airframes](https://docs.px4.io/main/en/airframes/airframe_reference.html) ([portfolio](http://px4.io/#airframes)):
* [Multicopters](https://docs.px4.io/main/en/frames_multicopter/)
* [Fixed wing](https://docs.px4.io/main/en/frames_plane/)
* [VTOL](https://docs.px4.io/main/en/frames_vtol/)
* [Autogyro](https://docs.px4.io/main/en/frames_autogyro/)
* [Rover](https://docs.px4.io/main/en/frames_rover/)
* many more experimental types (Blimps, Boats, Submarines, High altitude balloons, etc)
* Releases: [Downloads](https://github.com/PX4/PX4-Autopilot/releases)
## Building a PX4 based drone, rover, boat or robot
The [PX4 User Guide](https://docs.px4.io/master/en/) explains how to assemble [supported vehicles](https://docs.px4.io/master/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/master/en/#support) if you need help!
The [PX4 User Guide](https://docs.px4.io/main/en/) explains how to assemble [supported vehicles](https://docs.px4.io/main/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
## Changing code and contributing
This [Developer Guide](https://docs.px4.io/master/en/development/development.html) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle.
This [Developer Guide](https://docs.px4.io/main/en/development/development.html) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle.
Developers should read the [Guide for Contributions](https://docs.px4.io/master/en/contribute/).
See the [forum and chat](https://dev.px4.io/master/en/#support) if you need help!
Developers should read the [Guide for Contributions](https://docs.px4.io/main/en/contribute/).
See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
### Weekly Dev Call
The PX4 Dev Team syncs up on a [weekly dev call](https://dev.px4.io/master/en/contribute/#dev_call).
The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/contribute/).
> **Note** The dev call is open to all interested developers (not just the core dev team). This is a great opportunity to meet the team and contribute to the ongoing development of the platform. It includes a QA session for newcomers. All regular calls are listed in the [Dronecode calendar](https://www.dronecode.org/calendar/).
@@ -88,34 +88,34 @@ This repository contains code supporting Pixhawk standard boards (best supported
* FMUv6X and FMUv6U (STM32H7, 2021)
* Various vendors will provide FMUv6X and FMUv6U based designs Q3/2021
* FMUv5 and FMUv5X (STM32F7, 2019/20)
* [Pixhawk 4 (FMUv5)](https://docs.px4.io/master/en/flight_controller/pixhawk4.html)
* [Pixhawk 4 mini (FMUv5)](https://docs.px4.io/master/en/flight_controller/pixhawk4_mini.html)
* [CUAV V5+ (FMUv5)](https://docs.px4.io/master/en/flight_controller/cuav_v5_plus.html)
* [CUAV V5 nano (FMUv5)](https://docs.px4.io/master/en/flight_controller/cuav_v5_nano.html)
* [Auterion Skynode (FMUv5X)](https://docs.px4.io/master/en/flight_controller/auterion_skynode.html)
* [Pixhawk 4 (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4.html)
* [Pixhawk 4 mini (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4_mini.html)
* [CUAV V5+ (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_plus.html)
* [CUAV V5 nano (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_nano.html)
* [Auterion Skynode (FMUv5X)](https://docs.auterion.com/skynode)
* FMUv4 (STM32F4, 2015)
* [Pixracer](https://docs.px4.io/master/en/flight_controller/pixracer.html)
* [Pixhawk 3 Pro](https://docs.px4.io/master/en/flight_controller/pixhawk3_pro.html)
* [Pixracer](https://docs.px4.io/main/en/flight_controller/pixracer.html)
* [Pixhawk 3 Pro](https://docs.px4.io/main/en/flight_controller/pixhawk3_pro.html)
* FMUv3 (STM32F4, 2014)
* [Pixhawk 2](https://docs.px4.io/master/en/flight_controller/pixhawk-2.html)
* [Pixhawk Mini](https://docs.px4.io/master/en/flight_controller/pixhawk_mini.html)
* [CUAV Pixhack v3](https://docs.px4.io/master/en/flight_controller/pixhack_v3.html)
* [Pixhawk 2](https://docs.px4.io/main/en/flight_controller/pixhawk-2.html)
* [Pixhawk Mini](https://docs.px4.io/main/en/flight_controller/pixhawk_mini.html)
* [CUAV Pixhack v3](https://docs.px4.io/main/en/flight_controller/pixhack_v3.html)
* FMUv2 (STM32F4, 2013)
* [Pixhawk](https://docs.px4.io/master/en/flight_controller/pixhawk.html)
* [Pixfalcon](https://docs.px4.io/master/en/flight_controller/pixfalcon.html)
* [Pixhawk](https://docs.px4.io/main/en/flight_controller/pixhawk.html)
* [Pixfalcon](https://docs.px4.io/main/en/flight_controller/pixfalcon.html)
### Manufacturer and Community supported
* [Holybro Durandal](https://docs.px4.io/master/en/flight_controller/durandal.html)
* [Hex Cube Orange](https://docs.px4.io/master/en/flight_controller/cubepilot_cube_orange.html)
* [Hex Cube Yellow](https://docs.px4.io/master/en/flight_controller/cubepilot_cube_yellow.html)
* [Holybro Durandal](https://docs.px4.io/main/en/flight_controller/durandal.html)
* [Hex Cube Orange](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_orange.html)
* [Hex Cube Yellow](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_yellow.html)
* [Airmind MindPX V2.8](http://www.mindpx.net/assets/accessories/UserGuide_MindPX.pdf)
* [Airmind MindRacer V1.2](http://mindpx.net/assets/accessories/mindracer_user_guide_v1.2.pdf)
* [Bitcraze Crazyflie 2.0](https://docs.px4.io/master/en/complete_vehicles/crazyflie2.html)
* [Omnibus F4 SD](https://docs.px4.io/master/en/flight_controller/omnibus_f4_sd.html)
* [Holybro Kakute F7](https://docs.px4.io/master/en/flight_controller/kakutef7.html)
* [Raspberry PI with Navio 2](https://docs.px4.io/master/en/flight_controller/raspberry_pi_navio2.html)
* [Bitcraze Crazyflie 2.0](https://docs.px4.io/main/en/complete_vehicles/crazyflie2.html)
* [Omnibus F4 SD](https://docs.px4.io/main/en/flight_controller/omnibus_f4_sd.html)
* [Holybro Kakute F7](https://docs.px4.io/main/en/flight_controller/kakutef7.html)
* [Raspberry PI with Navio 2](https://docs.px4.io/main/en/flight_controller/raspberry_pi_navio2.html)
Additional information about supported hardware can be found in [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/master/en/flight_controller/).
Additional information about supported hardware can be found in [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/).
## Project Roadmap
+9 -15
View File
@@ -112,23 +112,17 @@ add_custom_command(
${PX4_SOURCE_DIR}/Tools/px4airframes/xmlout.py
${PX4_SOURCE_DIR}/Tools/serial/generate_config.py
)
set(romfs_extract_stamp ${CMAKE_CURRENT_BINARY_DIR}/romfs_extract.stamp)
add_custom_command(
OUTPUT ${romfs_extract_stamp}
COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}/*
COMMAND ${CMAKE_COMMAND} -E tar xf ${romfs_tar_file}
COMMAND ${CMAKE_COMMAND} -E touch ${romfs_extract_stamp}
WORKING_DIRECTORY ${romfs_gen_root_dir}
DEPENDS ${romfs_tar_file}
VERBATIM
)
set(romfs_copy_stamp ${CMAKE_CURRENT_BINARY_DIR}/romfs_copy.stamp)
add_custom_command(
OUTPUT
${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_copy.stamp
${romfs_copy_stamp}
COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}/*
COMMAND ${CMAKE_COMMAND} -E tar xf ${romfs_tar_file}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py
--airframes-path ${romfs_gen_root_dir}/init.d
--start-script ${romfs_gen_root_dir}/init.d/rc.autostart
@@ -137,9 +131,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 ${CMAKE_COMMAND} -E touch romfs_copy.stamp
DEPENDS
${romfs_extract_stamp}
COMMAND ${CMAKE_COMMAND} -E touch ${romfs_copy_stamp}
WORKING_DIRECTORY ${romfs_gen_root_dir}
DEPENDS ${romfs_tar_file}
COMMENT "ROMFS: copying, generating airframes"
)
@@ -311,7 +305,7 @@ add_custom_command(OUTPUT romfs_extras.stamp
add_custom_target(romfs_gen_files_target
DEPENDS
${romfs_extract_stamp}
${romfs_copy_stamp}
${romfs_gen_root_dir}/init.d/rc.serial
romfs_extras.stamp
)
@@ -29,7 +29,7 @@ param set-default FW_SPOILERS_LND 0.4
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_THR_CRUISE 0.25
param set-default FW_THR_TRIM 0.25
param set-default FW_T_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
@@ -27,7 +27,7 @@ param set-default FW_RR_P 0.3
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_THR_CRUISE 0.25
param set-default FW_THR_TRIM 0.25
param set-default FW_T_ALT_TC 2
param set-default FW_T_CLMB_MAX 8
@@ -5,5 +5,5 @@
. ${R}etc/init.d-posix/airframes/1030_plane
param set-default FW_THR_CRUISE 0.0
param set-default FW_THR_TRIM 0.0
param set-default RWTO_TKOFF 0
@@ -57,7 +57,7 @@ param set-default FW_P_LIM_MAX 32
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_THR_CRUISE 0.25
param set-default FW_THR_TRIM 0.25
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_CLMB_MAX 8
@@ -51,7 +51,7 @@ param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MAX 32
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_P 0.2
param set-default FW_THR_CRUISE 0.33
param set-default FW_THR_TRIM 0.33
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_ALT_TC 2
@@ -27,7 +27,9 @@ param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR0_TILT 1
param set-default CA_ROTOR1_TILT 2
param set-default CA_ROTOR2_TILT 3
param set-default CA_ROTOR3_TILT 4
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS1_TRQ_R 0.5
@@ -62,7 +64,7 @@ param set-default FW_P_LIM_MAX 32
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_THR_CRUISE 0.38
param set-default FW_THR_TRIM 0.38
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_CLMB_MAX 8
@@ -16,7 +16,7 @@ param set-default FW_P_LIM_MAX 32
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_THR_CRUISE 0.25
param set-default FW_THR_TRIM 0.25
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_ALT_TC 2
@@ -41,7 +41,7 @@ param set-default FW_R_LIM 30
param set-default FW_MAN_P_MAX 30.0
param set-default FW_MAN_R_MAX 30.0
param set-default FW_THR_CRUISE 0.8
param set-default FW_THR_TRIM 0.8
param set-default FW_THR_IDLE 0
param set-default COM_DISARM_PRFLT 0
@@ -43,7 +43,7 @@ param set-default MPC_YAWRAUTO_MAX 40
param set-default FW_PR_I 0.02
param set-default FW_RR_FF 0.6
param set-default FW_RR_I 0.01
param set-default FW_THR_CRUISE 0.75
param set-default FW_THR_TRIM 0.75
param set-default VT_ARSP_BLEND 6
param set-default VT_ARSP_TRANS 12
@@ -14,7 +14,7 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default FW_THR_CRUISE 65
param set-default FW_THR_TRIM 65
param set-default FW_RR_FF 0.6
param set-default MIS_YAW_TMT 10
@@ -53,7 +53,7 @@ param set-default FW_T_CLMB_MAX 3
param set-default FW_T_SINK_MAX 3
param set-default FW_T_SINK_MIN 1
param set-default FW_T_VERT_ACC 6
param set-default FW_THR_CRUISE 0.70
param set-default FW_THR_TRIM 0.70
param set-default FW_THR_SLEW_MAX 1
param set-default FW_MAN_P_MAX 30
param set-default FW_P_LIM_MAX 15
@@ -39,7 +39,7 @@ param set-default FW_RLL_TO_YAW_FF 0.1
param set-default FW_RR_P 0.08
param set-default FW_R_LIM 45
param set-default FW_R_RMAX 50
param set-default FW_THR_CRUISE 0.65
param set-default FW_THR_TRIM 0.65
param set-default FW_THR_MIN 0.3
param set-default FW_THR_SLEW_MAX 0.6
param set-default FW_T_HRATE_FF 0
@@ -37,7 +37,7 @@ param set-default SENS_BOARD_ROT 8
param set-default FW_AIRSPD_MAX 20
param set-default FW_AIRSPD_MIN 7
param set-default FW_AIRSPD_TRIM 13
param set-default FW_THR_CRUISE 0.8
param set-default FW_THR_TRIM 0.8
param set-default FW_MAN_P_MAX 25
param set-default FW_MAN_R_MAX 25
@@ -32,7 +32,7 @@ param set-default SENS_BOARD_ROT 4
param set-default FW_AIRSPD_MAX 20
param set-default FW_AIRSPD_MIN 7
param set-default FW_AIRSPD_TRIM 13
param set-default FW_THR_CRUISE 0.8
param set-default FW_THR_TRIM 0.8
param set-default FW_MAN_P_MAX 25
param set-default FW_MAN_R_MAX 25
@@ -40,7 +40,7 @@ param set-default FW_RR_P 0.013
param set-default FW_P_RMAX_NEG 70
param set-default FW_P_RMAX_POS 70
param set-default FW_R_RMAX 70
param set-default FW_THR_CRUISE 0.55
param set-default FW_THR_TRIM 0.55
param set-default LNDFW_AIRSPD_MAX 6
param set-default LNDFW_XYACC_MAX 4
+21 -21
View File
@@ -206,6 +206,26 @@ else
fi
unset BOARD_RC_DEFAULTS
#
# Set parameters and env variables for selected SYS_AUTOSTART.
#
set AUTOSTART_PATH etc/init.d/rc.autostart
if ! param compare SYS_AUTOSTART 0
then
if param greater SYS_AUTOSTART 1000000
then
# Use external startup file
if [ $SDCARD_AVAILABLE = yes ]
then
set AUTOSTART_PATH etc/init.d/rc.autostart_ext
else
echo "ERROR [init] SD card not mounted - trying to load airframe from ROMFS"
fi
fi
. ${R}$AUTOSTART_PATH
fi
unset AUTOSTART_PATH
#
# Start the tone_alarm driver.
# Needs to be started after the parameters are loaded (for CBRK_BUZZER).
@@ -243,26 +263,6 @@ else
rgbled start -X -q
rgbled_ncp5623c start -X -q
#
# Set parameters and env variables for selected AUTOSTART.
#
set AUTOSTART_PATH etc/init.d/rc.autostart
if ! param compare SYS_AUTOSTART 0
then
if param greater SYS_AUTOSTART 1000000
then
# Use external startup file
if [ $SDCARD_AVAILABLE = yes ]
then
set AUTOSTART_PATH etc/init.d/rc.autostart_ext
else
echo "ERROR [init] SD card not mounted - trying to load airframe from ROMFS"
fi
fi
. ${R}$AUTOSTART_PATH
fi
unset AUTOSTART_PATH
#
# Override parameters from user configuration file.
#
@@ -303,7 +303,7 @@ else
then
# Check for the mini using build with px4io fw file
# but not a px4IO
if ver hwtypecmp V540 V560
if ver hwtypecmp V5004000 V5006000
then
param set SYS_USE_IO 0
else
+1 -3
View File
@@ -115,9 +115,7 @@
#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
#define HW_INFO_INIT {'V','5','x', 'x',0}
#define HW_INFO_INIT_VER 2
#define HW_INFO_INIT_REV 3
#define HW_INFO_INIT_PREFIX "VAM"
#define BOARD_TAP_ESC_MODE 2 // select closed-loop control mode for the esc
// #define BOARD_USE_ESC_CURRENT_REPORT
+3 -1
View File
@@ -72,7 +72,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+3 -3
View File
@@ -83,9 +83,9 @@
#define GPIO_HW_VER_REV_DRIVE /* PB1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1)
#define GPIO_HW_REV_SENSE /* PA0 */ ADC1_GPIO(0)
#define GPIO_HW_VER_SENSE /* PA1 */ ADC1_GPIO(1)
#define HW_INFO_INIT {'C','A','N','G','P','S','x', 'x',0}
#define HW_INFO_INIT_VER 6
#define HW_INFO_INIT_REV 7
#define HW_INFO_INIT_PREFIX "CANGPS"
#define CANGPS00 HW_VER_REV(0x0,0x0) // CANGPS
#define FLASH_BASED_PARAMS
+3 -3
View File
@@ -104,7 +104,7 @@ static const px4_hw_mft_item_t hw_mft_list_v0000[] = {
static px4_hw_mft_list_entry_t mft_lists[] = {
// ver/rev
{0x0000, hw_mft_list_v0000, arraySize(hw_mft_list_v0000)},
{CANGPS00, hw_mft_list_v0000, arraySize(hw_mft_list_v0000)},
};
/************************************************************************************
@@ -127,7 +127,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -138,7 +138,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
@@ -11,13 +11,13 @@ icm20689 -R 2 -s start
bmi088 -A -R 2 -s start
bmi088 -G -R 2 -s start
if ver hwtypecmp VD00
if ver hwtypecmp VD000000
then
# Internal SPI BMI088
bmi088 -A -R 2 -s start
bmi088 -G -R 2 -s start
fi
if ver hwtypecmp VD01
if ver hwtypecmp VD000001
then
# Internal SPI ICM-20602
icm20602 -R 2 -s start
@@ -152,9 +152,7 @@
#define GPIO_HW_REV_SENSE /* PC3 */ GPIO_ADC12_INP13
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_VER_SENSE /* PC2 */ GPIO_ADC123_INP12
#define HW_INFO_INIT {'V','D','x', 'x',0}
#define HW_INFO_INIT_VER 2
#define HW_INFO_INIT_REV 3
#define HW_INFO_INIT_PREFIX "VD"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2
+9 -7
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2019, 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -206,7 +206,6 @@ stm32_boardinitialize(void)
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Power on Interfaces */
@@ -219,6 +218,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
px4_platform_init();
// Use the default HW_VER_REV(0x0,0x0) for Ramtron
stm32_spiinitialize();
/* Configure the HW based on the manifest */
px4_platform_configure();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
@@ -228,7 +234,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
/* configure SPI interfaces (after we determined the HW version) */
/* Configure the actual SPI interfaces (after we determined the HW version) */
stm32_spiinitialize();
@@ -268,9 +274,5 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}
+2 -2
View File
@@ -107,7 +107,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -118,7 +118,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+5 -3
View File
@@ -185,9 +185,11 @@
#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
#define HW_INFO_INIT {'V','5','x', 'x',0}
#define HW_INFO_INIT_VER 2
#define HW_INFO_INIT_REV 3
#define HW_INFO_INIT_PREFIX "VPIX32V5"
#define VPIX32V500 HW_VER_REV(0x0,0x0) // PIX32V5 Rev 0
#define VPIX32V540 HW_VER_REV(0x4,0x0) // HolyBro mini no can 2,3
/* CAN Silence
*
* Silent mode control \ ESC Mux select
+4 -4
View File
@@ -129,8 +129,8 @@ static const px4_hw_mft_item_t hw_mft_list_v0540[] = {
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{0x0400, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, // HolyBro mini no can 2,3
{VPIX32V500, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{VPIX32V540, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, // HolyBro mini no can 2,3
};
/************************************************************************************
@@ -153,7 +153,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -164,7 +164,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+4 -3
View File
@@ -5,6 +5,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_DRIVERS_ACTUATORS_MODALAI_ESC=y
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_COMMON_BAROMETERS=y
@@ -42,6 +43,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -50,6 +52,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -65,7 +68,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -74,10 +76,9 @@ CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+4 -3
View File
@@ -142,9 +142,10 @@
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
#define HW_INFO_INIT {'V','1','x', 'x',0}
#define HW_INFO_INIT_VER 2 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 3 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "V1"
#define V10006 HW_VER_REV(0x0,0x6) // V1006 Rev 6
#define V10100 HW_VER_REV(0x1,0x0) // V1010 Rev 0
/* PWM
*/
+4 -4
View File
@@ -90,8 +90,8 @@ static const px4_hw_mft_item_t hw_mft_list_fc0100[] = {
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0006, hw_mft_list_fc0006, arraySize(hw_mft_list_fc0006)},
{0x0100, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)}
{V10006, hw_mft_list_fc0006, arraySize(hw_mft_list_fc0006)},
{V10100, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)}
};
/************************************************************************************
@@ -114,7 +114,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -125,7 +125,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+4 -3
View File
@@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_DRIVERS_ACTUATORS_MODALAI_ESC=y
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_COMMON_BAROMETERS=y
@@ -40,6 +41,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -48,6 +50,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -63,17 +66,15 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+2 -3
View File
@@ -182,9 +182,8 @@
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
#define HW_INFO_INIT {'V','2','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "V2"
#define V20300 HW_VER_REV(0x3,0x0)
/* PE6 is nARMED --> FCv2 this goes to TP13
* The GPIO will be set as input while not armed HW will have external HW Pull UP.
+3 -3
View File
@@ -83,7 +83,7 @@ static const px4_hw_mft_item_t hw_mft_list_fc0200[] = {
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0300, hw_mft_list_fc0200, arraySize(hw_mft_list_fc0200)},
{V20300, hw_mft_list_fc0200, arraySize(hw_mft_list_fc0200)},
};
/************************************************************************************
@@ -106,7 +106,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -117,7 +117,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+3 -1
View File
@@ -71,7 +71,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+4 -3
View File
@@ -192,9 +192,10 @@
#define GPIO_HW_VER_REV_DRIVE /* GPIO_AD_B0_01 GPIO1_IO01 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | HW_IOMUX)
#define GPIO_HW_REV_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24)
#define GPIO_HW_VER_SENSE /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20)
#define HW_INFO_INIT {'V','5','x', 'x',0}
#define HW_INFO_INIT_VER 2
#define HW_INFO_INIT_REV 3
#define HW_INFO_INIT_PREFIX "V5"
#define V500 HW_VER_REV(0x0,0x0) // FMUV5, Rev 0
#define V540 HW_VER_REV(0x4,0x0) // mini no can 2,3, Rev 0
/* CAN Silence
*
* Silent mode control \ ESC Mux select
+2 -2
View File
@@ -88,8 +88,8 @@ static const px4_hw_mft_item_t hw_mft_list_v0540[] = {
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{0x0400, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
{V500, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{V540, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
};
/************************************************************************************
+3 -1
View File
@@ -66,7 +66,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+3 -1
View File
@@ -65,7 +65,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+1 -1
View File
@@ -9,7 +9,7 @@ param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152
if ver hwtypecmp V550 V552 V560 V562
if ver hwtypecmp V5005000 V5005002 V5006000 V5006002
then
# CUAV V5+ (V550/V552) and V5nano (V560/V562) have 3 IMUs
# Multi-EKF (IMUs only)
+1 -1
View File
@@ -5,7 +5,7 @@
board_adc start
if ver hwtypecmp V552 V562
if ver hwtypecmp V5005002 V5006002
then
# Internal SPI bus ICM-42688-P
icm42688p -s -R 2 -q start
+2 -3
View File
@@ -188,9 +188,8 @@
#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
#define HW_INFO_INIT {'V','5','x', 'x',0}
#define HW_INFO_INIT_VER 2
#define HW_INFO_INIT_REV 3
#define HW_INFO_INIT_PREFIX "V5"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 3
#define V500 HW_VER_REV(0x0,0x0) // FMUV5, Rev 0
#define V515 HW_VER_REV(0x1,0x5) // CUAV V5, Rev 5
+2 -2
View File
@@ -186,7 +186,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -197,7 +197,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+1 -1
View File
@@ -3,7 +3,7 @@
# board specific MAVLink startup script.
#------------------------------------------------------------------------------
if ver hwtypecmp V5X90 V5X91 V5Xa0 V5Xa1 V5X80 V5X81
if ver hwtypecmp V5X009000 V5X009001 V5X00a000 V5X00a001 V5X008000 V5X008001 V5X010001
then
# Start MAVLink on the UART connected to the mission computer
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
+26 -26
View File
@@ -5,7 +5,7 @@
set HAVE_PM2 yes
if ver hwtypecmp V5X50 V5X51 V5X52
if ver hwtypecmp V5X005000 V5X005001 V5X005002
then
set HAVE_PM2 no
fi
@@ -48,33 +48,11 @@ then
fi
fi
if ver hwtypecmp V5X90 V5X91 V5X92 V5Xa0 V5Xa1 V5Xa2
if ver hwtypecmp V5X000000 V5X000001 V5X000002 V5X001000
then
#SKYNODE base fmu board orientation
if ver hwtypecmp V5X90 V5X91 V5Xa0 V5Xa1
then
# Internal SPI BMI088
bmi088 -A -R 2 -s start
bmi088 -G -R 2 -s start
else
# Internal SPI bus ICM20649
icm20649 -s -R 4 start
fi
# Internal SPI bus ICM42688p
icm42688p -R 4 -s start
# Internal SPI bus ICM-20602 (hard-mounted)
icm20602 -R 8 -s start
# Internal magnetometer on I2c
bmm150 -I -R 6 start
else
#FMUv5Xbase board orientation
if ver hwtypecmp V5X00 V5X01
if ver hwtypecmp V5X000000 V5X000001
then
# Internal SPI BMI088
bmi088 -A -R 4 -s start
@@ -93,6 +71,28 @@ else
# Internal magnetometer on I2c
bmm150 -I start
else
#SKYNODE base fmu board orientation
if ver hwtypecmp V5X009000 V5X009001 V5X00a000 V5X00a001 V5X008000 V5X008001 V5X010001
then
# Internal SPI BMI088
bmi088 -A -R 2 -s start
bmi088 -G -R 2 -s start
else
# Internal SPI bus ICM20649
icm20649 -s -R 4 start
fi
# Internal SPI bus ICM42688p
icm42688p -R 4 -s start
# Internal SPI bus ICM-20602 (hard-mounted)
icm20602 -R 8 -s start
# Internal magnetometer on I2c
bmm150 -I -R 6 start
fi
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
@@ -104,7 +104,7 @@ ist8310 -X -b 1 -R 10 start
if param compare SENS_INT_BARO_EN 1
then
bmp388 -I -a 0x77 start
if ver hwtypecmp V5X00 V5X90 V5Xa0
if ver hwtypecmp V5X000000 V5X001000 V5X008000 V5X009000 V5X00a000
then
bmp388 -I start
else
+4 -3
View File
@@ -111,6 +111,8 @@
*
* Note that these are unshifted addresses.
*/
#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/
#define PX4_I2C_OBDEV_SE050 0x48
#define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5)
@@ -182,9 +184,7 @@
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
#define HW_INFO_INIT {'V','5','X','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "V5X"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 6
// Base FMUM
#define V5X00 HW_VER_REV(0x0,0x0) // FMUV5X, Rev 0
@@ -200,6 +200,7 @@
#define V5Xa0 HW_VER_REV(0xa,0x0) // NO USB (Q), Rev 0
#define V5Xa1 HW_VER_REV(0xa,0x1) // NO USB (Q) I2C2 BMP388, Rev 1
#define V5Xa2 HW_VER_REV(0xa,0x2) // NO USB (Q) I2C2 BMP388, Rev 2
#define V5X101 HW_VER_REV(0x10,0x1) // NO USB (Q) I2C2 BMP388, Rev 1
#define UAVCAN_NUM_IFACES_RUNTIME 1
+12 -8
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -54,9 +54,7 @@
#include <errno.h>
#include <nuttx/config.h>
extern "C" {
#include <nuttx/board.h>
}
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
@@ -72,6 +70,7 @@ extern "C" {
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform_common/px4_manifest.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
@@ -221,6 +220,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
px4_platform_init();
// Use the default HW_VER_REV(0x0,0x0) for Ramtron
stm32_spiinitialize();
/* Configure the HW based on the manifest */
px4_platform_configure();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
@@ -230,11 +236,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
/* Configure the Actual SPI interfaces (after we determined the HW version) */
stm32_spiinitialize();
board_spi_reset(10, 0xffff);
/* configure the DMA allocator */
/* Configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
@@ -266,10 +274,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
int hw_version = board_get_hw_version();
if (hw_version == 0x9 || hw_version == 0xa) {
+3 -2
View File
@@ -172,6 +172,7 @@ static px4_hw_mft_list_entry_t mft_lists[] = {
{V5Xa0, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q), Rev 0
{V5Xa1, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 1
{V5Xa2, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 2
{V5X101, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 1
};
/************************************************************************************
@@ -194,7 +195,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -205,7 +206,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+3 -1
View File
@@ -117,7 +117,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+1 -3
View File
@@ -139,9 +139,7 @@
#define GPIO_HW_VER_REV_DRIVE /* PE12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN12)
#define GPIO_HW_REV_SENSE /* PC0 */ GPIO_ADC123_INP10
#define GPIO_HW_VER_SENSE /* PC1 */ GPIO_ADC123_INP11
#define HW_INFO_INIT {'V','6','C','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "V6C"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0, 10 Sensor sets
// Base/FMUM
+2 -2
View File
@@ -121,7 +121,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -132,7 +132,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+3 -1
View File
@@ -95,7 +95,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+2 -3
View File
@@ -173,9 +173,8 @@
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
#define HW_INFO_INIT {'V','6','U','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "V6U"
#define V6U00 HW_VER_REV(0x0,0x0)
/* HEATER
* PWM in future
+3 -3
View File
@@ -82,7 +82,7 @@ static const px4_hw_mft_item_t hw_mft_list_v0600[] = {
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0000, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
{V6U00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
};
/************************************************************************************
@@ -105,7 +105,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -116,7 +116,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+3 -1
View File
@@ -71,7 +71,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
+4 -4
View File
@@ -4,7 +4,7 @@
#------------------------------------------------------------------------------
set HAVE_PM2 yes
if ver hwtypecmp V6X50 V6X51 V6X53 V6X54
if ver hwtypecmp V6X005000 V6X005001 V6X005003 V6X005004
then
set HAVE_PM2 no
fi
@@ -47,7 +47,7 @@ then
fi
fi
if ver hwtypecmp V6X04 V6X14 V6X54
if ver hwtypecmp V6X000004 V6X001004 V6X005004
then
# Internal SPI bus ICM20649
icm20649 -s -R 6 start
@@ -60,7 +60,7 @@ fi
# Internal SPI bus ICM42688p
icm42688p -R 6 -s start
if ver hwtypecmp V6X03 V6X13 V6X04 V6X14 V6X53 V6X54
if ver hwtypecmp V6X000003 V6X001003 V6X000004 V6X001004 V6X005003 V6X005004
then
# Internal SPI bus ICM-42670-P (hard-mounted)
icm42670p -R 10 -s start
@@ -78,7 +78,7 @@ ist8310 -X -b 1 -R 10 start
# Possible internal Baro
bmp388 -I -a 0x77 start
if ver hwtypecmp V6X00 V6X10
if ver hwtypecmp V6X000000 V6X001000
then
bmp388 -I start
else
+1 -3
View File
@@ -211,9 +211,7 @@
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
#define HW_INFO_INIT {'V','6','X','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "V6X"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 6 // Rev 0 and Rev 3,4 Sensor sets
// Base/FMUM
+12 -6
View File
@@ -52,7 +52,6 @@
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
@@ -71,6 +70,7 @@
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform_common/px4_manifest.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
@@ -219,6 +219,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
px4_platform_init();
// Use the default HW_VER_REV(0x0,0x0) for Ramtron
stm32_spiinitialize();
/* Configure the HW based on the manifest */
px4_platform_configure();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
@@ -228,11 +235,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
/* Configure the Actual SPI interfaces (after we determined the HW version) */
stm32_spiinitialize();
board_spi_reset(10, 0xffff);
/* configure the DMA allocator */
/* Configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
@@ -264,13 +273,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)
if (ret != OK) {
led_on(LED_RED);
return ret;
}
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}
+2 -2
View File
@@ -172,7 +172,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -183,7 +183,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
+3 -1
View File
@@ -117,7 +117,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
@@ -173,10 +173,8 @@
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
#define HW_INFO_INIT {'V','5','X','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define HW_INFO_INIT_PREFIX "SDSA"
#define SDSA0501 HW_VER_REV(0x05,0x01)
/* HEATER
* PWM in future
*/
@@ -88,7 +88,7 @@ static const px4_hw_mft_item_t hw_mft_list_v0501[] = {
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0501, hw_mft_list_v0501, arraySize(hw_mft_list_v0501)},
{SDSA0501, hw_mft_list_v0501, arraySize(hw_mft_list_v0501)},
};
@@ -112,7 +112,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@@ -123,7 +123,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
@@ -95,7 +95,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
-1
View File
@@ -189,7 +189,6 @@ set(msg_files
vehicle_constraints.msg
vehicle_control_mode.msg
vehicle_global_position.msg
vehicle_gps_position.msg
vehicle_imu.msg
vehicle_imu_status.msg
vehicle_land_detected.msg
+1 -1
View File
@@ -19,4 +19,4 @@ bool innovation_rejected # true if the observation has been rejected
bool fused # true if the sample was successfully fused
# TOPICS estimator_aid_source_1d
# TOPICS estimator_aid_src_baro_hgt estimator_aid_src_rng_hgt
# TOPICS estimator_aid_src_baro_hgt estimator_aid_src_rng_hgt estimator_aid_src_airspeed
+2 -1
View File
@@ -40,6 +40,7 @@ int8 loiter_direction # loiter direction: 1 = CW, -1 = CCW
float32 acceptance_radius # navigation acceptance_radius if we're doing waypoint navigation
float32 cruising_speed # the generally desired cruising speed (not a hard constraint)
float32 cruising_throttle # the generally desired cruising throttle (not a hard constraint)
bool gliding_enabled # commands the vehicle to glide if the capability is available (fixed wing only)
float32 cruising_throttle # the generally desired cruising throttle (not a hard constraint), only has an effect for rover
bool disable_weather_vane # VTOL: disable (in auto mode) the weather vane feature that turns the nose into the wind
+2 -1
View File
@@ -1,2 +1,3 @@
uint64 timestamp # time since system start (microseconds) at PPS capture event
uint64 rtc_timestamp # Corrected GPS UTC timestamp at PPS capture event
uint64 rtc_timestamp # Corrected GPS UTC timestamp at PPS capture event
uint8 pps_rate_exceeded_counter # Increments when PPS dt < 50ms
+9 -1
View File
@@ -1,6 +1,7 @@
# GPS position in WGS84 coordinates.
# the field 'timestamp' is for the position & velocity (microseconds)
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
@@ -21,8 +22,13 @@ float32 vdop # Vertical dilution of precision
int32 noise_per_ms # GPS noise per millisecond
uint16 automatic_gain_control # Automatic gain control monitor
int32 jamming_indicator # indicates jamming is occurring
uint8 JAMMING_STATE_UNKNOWN = 0
uint8 JAMMING_STATE_OK = 1
uint8 JAMMING_STATE_WARNING = 2
uint8 JAMMING_STATE_CRITICAL = 3
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
int32 jamming_indicator # indicates jamming is occurring
float32 vel_m_s # GPS ground speed, (metres/sec)
float32 vel_n_m_s # GPS North velocity, (metres/sec)
@@ -39,3 +45,5 @@ uint8 satellites_used # Number of satellites used
float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI])
float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI])
float32 heading_accuracy # heading accuracy (rad, [0, 2PI])
# TOPICS sensor_gps vehicle_gps_position
+1
View File
@@ -40,5 +40,6 @@ float32 pitch_integ
float32 throttle_sp
float32 pitch_sp_rad
float32 throttle_trim # estimated throttle value [0,1] required to fly level at equivalent_airspeed_sp in the current atmospheric conditions
uint8 mode
+39 -45
View File
@@ -1,4 +1,7 @@
uint64 timestamp # time since system start (microseconds)
# Vehicle Command uORB message. Used for commanding a mission / action / etc.
# Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
uint64 timestamp # time since system start (microseconds)
uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command
uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command
@@ -11,7 +14,7 @@ uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty
uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing
uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z |
uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z |
uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
uint16 VEHICLE_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|
uint16 VEHICLE_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground / hand and transition to fixed wing |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|
@@ -24,7 +27,7 @@ uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |Delay
uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|
uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt|
uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty|
@@ -41,11 +44,11 @@ uint16 VEHICLE_CMD_DO_LAND_START = 189 # Mission command to perform a landing.
uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPOSITION = 192
uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193
uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint|
uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint|
uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203
uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value|
@@ -54,19 +57,19 @@ uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofenc
uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty|
uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION
uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3 # param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration
uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration
uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units|
uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started
uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty|
uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal
uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal
uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)|
uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function|
@@ -74,21 +77,21 @@ uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|co
uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm
uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes
uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX|
uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message
uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.)
uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom
uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message
uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.)
uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom
uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control
uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence.
uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system
uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture.
uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture.
uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control
uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence.
uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system
uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture.
uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture.
uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data
uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data
uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link
uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition
uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization
uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link
uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition
uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization
uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan
uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment
uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.
@@ -98,33 +101,24 @@ uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibrati
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX)
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude|
uint8 VEHICLE_CMD_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED |
uint8 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED |
uint8 VEHICLE_CMD_RESULT_DENIED = 2 # Command PERMANENTLY DENIED |
uint8 VEHICLE_CMD_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED |
uint8 VEHICLE_CMD_RESULT_FAILED = 4 # Command executed, but failed |
uint8 VEHICLE_CMD_RESULT_IN_PROGRESS = 5 # Command being executed |
uint8 VEHICLE_CMD_RESULT_ENUM_END = 6 #
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization |
uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization |
uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt |
uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 #
uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization |
uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt |
uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 #
uint8 VEHICLE_ROI_NONE = 0 # No region of interest |
uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION |
uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION |
uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location |
uint8 VEHICLE_ROI_TARGET = 4 # Point toward target
uint8 VEHICLE_ROI_NONE = 0 # No region of interest |
uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION |
uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION |
uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location |
uint8 VEHICLE_ROI_TARGET = 4 # Point toward target
uint8 VEHICLE_ROI_ENUM_END = 5
uint8 VEHICLE_CAMERA_ZOOM_TYPE_STEP = 0 # Zoom one step increment
uint8 VEHICLE_CAMERA_ZOOM_TYPE_CONTINUOUS = 1 # Continuous zoom up/down until stopped
uint8 VEHICLE_CAMERA_ZOOM_TYPE_RANGE = 2 # Zoom value as proportion of full camera range
uint8 VEHICLE_CAMERA_ZOOM_TYPE_FOCAL_LENGTH = 3 # Zoom to a focal length
uint8 VEHICLE_CAMERA_ZOOM_TYPE_STEP = 0 # Zoom one step increment
uint8 VEHICLE_CAMERA_ZOOM_TYPE_CONTINUOUS = 1 # Continuous zoom up/down until stopped
uint8 VEHICLE_CAMERA_ZOOM_TYPE_RANGE = 2 # Zoom value as proportion of full camera range
uint8 VEHICLE_CAMERA_ZOOM_TYPE_FOCAL_LENGTH = 3 # Zoom to a focal length
uint8 PARACHUTE_ACTION_DISABLE = 0
uint8 PARACHUTE_ACTION_ENABLE = 1
+21 -12
View File
@@ -1,11 +1,19 @@
uint64 timestamp # time since system start (microseconds)
uint8 VEHICLE_RESULT_ACCEPTED = 0
uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1
uint8 VEHICLE_RESULT_DENIED = 2
uint8 VEHICLE_RESULT_UNSUPPORTED = 3
uint8 VEHICLE_RESULT_FAILED = 4
uint8 VEHICLE_RESULT_IN_PROGRESS = 5
# Vehicle Command Ackonwledgement uORB message.
# Used for acknowledging the vehicle command being received.
# Follows the MAVLink COMMAND_ACK message definition
uint64 timestamp # time since system start (microseconds)
# Result cases. This follows the MAVLink MAV_RESULT enum definition
uint8 VEHICLE_CMD_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED |
uint8 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED |
uint8 VEHICLE_CMD_RESULT_DENIED = 2 # Command PERMANENTLY DENIED |
uint8 VEHICLE_CMD_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED |
uint8 VEHICLE_CMD_RESULT_FAILED = 4 # Command executed, but failed |
uint8 VEHICLE_CMD_RESULT_IN_PROGRESS = 5 # Command being executed |
uint8 VEHICLE_CMD_RESULT_CANCELLED = 6 # Command Canceled
# Arming denied specific cases
uint16 ARM_AUTH_DENIED_REASON_GENERIC = 0
uint16 ARM_AUTH_DENIED_REASON_NONE = 1
uint16 ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2
@@ -15,10 +23,11 @@ uint16 ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5
uint8 ORB_QUEUE_LENGTH = 4
uint32 command
uint8 result
bool from_external
uint8 result_param1
int32 result_param2
uint32 command # Command that is being acknowledged
uint8 result # Command result
uint8 result_param1 # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS
int32 result_param2 # Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
uint8 target_system
uint8 target_component
bool from_external # Indicates if the command came from an external source
-39
View File
@@ -1,39 +0,0 @@
# GPS position in WGS84 coordinates.
# the field 'timestamp' is for the position & velocity (microseconds)
uint64 timestamp # time since system start (microseconds)
int32 lat # Latitude in 1E-7 degrees
int32 lon # Longitude in 1E-7 degrees
int32 alt # Altitude in 1E-3 meters above MSL, (millimetres)
int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres)
float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec)
float32 c_variance_rad # GPS course accuracy estimate, (radians)
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
float32 eph # GPS horizontal position accuracy (metres)
float32 epv # GPS vertical position accuracy (metres)
float32 hdop # Horizontal dilution of precision
float32 vdop # Vertical dilution of precision
int32 noise_per_ms # GPS noise per millisecond
int32 jamming_indicator # indicates jamming is occurring
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
float32 vel_m_s # GPS ground speed, (metres/sec)
float32 vel_n_m_s # GPS North velocity, (metres/sec)
float32 vel_e_m_s # GPS East velocity, (metres/sec)
float32 vel_d_m_s # GPS Down velocity, (metres/sec)
float32 cog_rad # Course over ground (NOT heading, but direction of movement), -PI..PI, (radians)
bool vel_ned_valid # True if NED velocity is valid
int32 timestamp_time_relative # timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds)
uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0
uint8 satellites_used # Number of satellites used
float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI])
float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI])
uint8 selected # GPS selection: 0: GPS1, 1: GPS2. 2: GPS3. 3. Blending multiple receivers
+74 -92
View File
@@ -1,5 +1,11 @@
uint64 timestamp # time since system start (microseconds)
# Encodes the system state of the vehicle published by commander
uint64 timestamp # time since system start (microseconds)
uint64 armed_time # Arming timestamp (microseconds)
uint64 takeoff_time # Takeoff timestamp (microseconds)
uint8 arming_state
uint8 ARMING_STATE_INIT = 0
uint8 ARMING_STATE_STANDBY = 1
uint8 ARMING_STATE_ARMED = 2
@@ -8,93 +14,8 @@ uint8 ARMING_STATE_SHUTDOWN = 4
uint8 ARMING_STATE_IN_AIR_RESTORE = 5
uint8 ARMING_STATE_MAX = 6
# FailureDetector status
uint16 FAILURE_NONE = 0
uint16 FAILURE_ROLL = 1 # (1 << 0)
uint16 FAILURE_PITCH = 2 # (1 << 1)
uint16 FAILURE_ALT = 4 # (1 << 2)
uint16 FAILURE_EXT = 8 # (1 << 3)
uint16 FAILURE_ARM_ESC = 16 # (1 << 4)
uint16 FAILURE_BATTERY = 32 # (1 << 5)
uint16 FAILURE_IMBALANCED_PROP = 64 # (1 << 6)
uint16 FAILURE_MOTOR = 128 # (1 << 7)
# HIL
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# Navigation state, i.e. "what should vehicle do".
uint8 NAVIGATION_STATE_MANUAL = 0 # Manual mode
uint8 NAVIGATION_STATE_ALTCTL = 1 # Altitude control mode
uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_UNUSED3 = 8 # Free slot
uint8 NAVIGATION_STATE_UNUSED = 9 # Free slot
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
uint8 NAVIGATION_STATE_UNUSED1 = 11 # Free slot
uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_UNUSED2 = 16 # Free slot
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_AUTO_VTOL_TAKEOFF = 22 # Takeoff, transition, establish loiter
uint8 NAVIGATION_STATE_MAX = 23
uint8 VEHICLE_TYPE_UNKNOWN = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 VEHICLE_TYPE_AIRSHIP = 4
# state machine / state of vehicle.
# Encodes the complete system state and is set by the commander app.
uint8 nav_state # set navigation state machine to specified value
uint64 nav_state_timestamp # time when current nav_state activated
uint8 arming_state # current arming state
uint8 hil_state # current hil state
bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
uint64 failsafe_timestamp # time when failsafe was activated
uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
uint8 vehicle_type # Type of vehicle (rotary wing/fixed-wing/rover/airship, see above)
# If the vehicle is a VTOL, then this value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter,
# and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing
bool is_vtol # True if the system is VTOL capable
bool is_vtol_tailsitter # True if the system performs a 90° pitch down rotation during transition from MC to FW
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
bool rc_signal_lost # true if RC reception lost
bool data_link_lost # datalink to GCS lost
uint8 data_link_lost_counter # counts unique data link lost events
bool high_latency_data_link_lost # Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
bool mission_failure # Set to true if mission could not continue/finish
bool geofence_violated
uint16 failure_detector_status # Bitmask containing FailureDetector status [0, 0, 0, 0, 0, FAILURE_ALT, FAILURE_PITCH, FAILURE_ROLL]
# see SYS_STATUS mavlink message for the following
# lower 32 bits are for the base flags, higher 32 bits are or the extended flags
uint64 onboard_control_sensors_present
uint64 onboard_control_sensors_enabled
uint64 onboard_control_sensors_health
uint8 latest_arming_reason
uint8 latest_disarming_reason
uint8 ARM_DISARM_REASON_TRANSITION_TO_STANDBY = 0
uint8 ARM_DISARM_REASON_RC_STICK = 1
uint8 ARM_DISARM_REASON_RC_SWITCH = 2
@@ -110,12 +31,73 @@ uint8 ARM_DISARM_REASON_FAILURE_DETECTOR = 11
uint8 ARM_DISARM_REASON_SHUTDOWN = 12
uint8 ARM_DISARM_REASON_UNIT_TEST = 13
uint8 latest_arming_reason
uint8 latest_disarming_reason
uint64 nav_state_timestamp # time when current nav_state activated
uint64 armed_time # Arming timestamp (microseconds)
# Navigation state "what should vehicle do"
uint8 nav_state
uint8 NAVIGATION_STATE_MANUAL = 0 # Manual mode
uint8 NAVIGATION_STATE_ALTCTL = 1 # Altitude control mode
uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_UNUSED3 = 8 # Free slot
uint8 NAVIGATION_STATE_UNUSED = 9 # Free slot
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
uint8 NAVIGATION_STATE_UNUSED1 = 11 # Free slot
uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_UNUSED2 = 16 # Free slot
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_AUTO_VTOL_TAKEOFF = 22 # Takeoff, transition, establish loiter
uint8 NAVIGATION_STATE_MAX = 23
uint64 takeoff_time # Takeoff timestamp (microseconds)
uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# If it's a VTOL, then the value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter, and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing
uint8 vehicle_type
uint8 VEHICLE_TYPE_UNKNOWN = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 VEHICLE_TYPE_AIRSHIP = 4
bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
uint64 failsafe_timestamp # time when failsafe was activated
# Link loss
bool rc_signal_lost # true if RC reception lost
bool data_link_lost # datalink to GCS lost
uint8 data_link_lost_counter # counts unique data link lost events
bool high_latency_data_link_lost # Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
# VTOL flags
bool is_vtol # True if the system is VTOL capable
bool is_vtol_tailsitter # True if the system performs a 90° pitch down rotation during transition from MC to FW
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
bool mission_failure # Set to true if mission could not continue/finish
bool geofence_violated
# MAVLink identification
uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
# see SYS_STATUS mavlink message for the following
# lower 32 bits are for the base flags, higher 32 bits are or the extended flags
uint64 onboard_control_sensors_present
uint64 onboard_control_sensors_enabled
uint64 onboard_control_sensors_health
bool safety_button_available # Set to true if a safety button is connected
bool safety_off # Set to true if safety is off
@@ -82,6 +82,10 @@
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 1
#endif
#ifndef BOARD_MTD_NUM_EEPROM
#define BOARD_MTD_NUM_EEPROM 1
#endif
/* ADC defining tools
* We want to normalize the V5 Sensing to V = (adc_dn) * ADC_V5_V_FULL_SCALE/(2 ^ ADC_BITS) * ADC_V5_SCALE)
*/
@@ -258,9 +262,12 @@
#if defined(BOARD_HAS_HW_VERSIONING)
# define BOARD_HAS_VERSIONING 1
# define HW_VER_REV(v,r) ((uint32_t)((v) & 0xff) << 8) | ((uint32_t)(r) & 0xff)
# define HW_VER_REV(v,r) ((uint32_t)((v) & 0xffff) << 16) | ((uint32_t)(r) & 0xffff)
#endif
#define HW_INFO_REV_DIGITS 3
#define HW_INFO_VER_DIGITS 3
/* Default LED logical to color mapping */
#if defined(BOARD_OVERLOAD_LED)
@@ -100,6 +100,6 @@ __EXPORT int px4_mtd_config(const px4_mtd_manifest_t *mft_mtd);
* 0 (get !=null) item by type's value is returned at get;
*
************************************************************************************/
__EXPORT int px4_mtd_query(const char *type, const char *val, const char **get = nullptr);
__EXPORT int px4_mtd_query(const char *type, const char *val, const char **get);
__END_DECLS
@@ -65,7 +65,7 @@ typedef struct {
typedef struct {
const uint32_t nmft;
const px4_mft_entry_s *mfts;
const px4_mft_entry_s *mfts[];
} px4_mft_s;
#include "px4_platform_common/mtd_manifest.h"
@@ -88,6 +88,19 @@ __BEGIN_DECLS
__EXPORT const px4_mft_s *board_get_manifest(void);
/************************************************************************************
* Name: board_get_base_eeprom_mtd_manifest
*
* Description:
* A board will provide this function to return the mtd with eeprom manifest
*
* Returned Value:
* pointer to mtd manifest
*
************************************************************************************/
__EXPORT const px4_mtd_manifest_t *board_get_base_eeprom_mtd_manifest(void);
/************************************************************************************
* Name: px4_mft_configure
*
@@ -35,6 +35,8 @@
__BEGIN_DECLS
#define MAX_MTD_INSTANCES 5u
// The data needed to interface with mtd device's
typedef struct {
@@ -60,7 +62,7 @@ typedef struct {
* This can be Null if there are no mtd instances.
*
*/
__EXPORT mtd_instance_s *px4_mtd_get_instances(unsigned int *count);
__EXPORT mtd_instance_s **px4_mtd_get_instances(unsigned int *count);
/*
Get device complete geometry or a device
@@ -75,7 +77,9 @@ __EXPORT int px4_mtd_get_geometry(const mtd_instance_s *instance, unsigned long
*/
__EXPORT ssize_t px4_mtd_get_partition_size(const mtd_instance_s *instance, const char *partname);
FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address);
int px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address, FAR struct mtd_dev_s **mtd_dev);
void px4_at24c_deinitialize(void);
__END_DECLS
+3 -3
View File
@@ -47,7 +47,7 @@ void px4_set_spi_buses_from_hw_version()
#if defined(BOARD_HAS_SIMPLE_HW_VERSIONING)
int hw_version_revision = board_get_hw_version();
#else
int hw_version_revision = (board_get_hw_version() << 8) | board_get_hw_revision();
int hw_version_revision = (board_get_hw_version() << 16) | board_get_hw_revision();
#endif
@@ -66,12 +66,12 @@ void px4_set_spi_buses_from_hw_version()
}
}
const px4_spi_bus_t *px4_spi_buses{};
const px4_spi_bus_t *px4_spi_buses{nullptr};
#endif
int px4_find_spi_bus(uint32_t devid)
{
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
for (int i = 0; px4_spi_buses != nullptr && i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
const px4_spi_bus_t &bus_data = px4_spi_buses[i];
if (bus_data.bus == -1) {
+3
View File
@@ -414,6 +414,9 @@ if(NOT NUTTX_DIR MATCHES "external")
elseif(CONFIG_ARCH_CHIP_STM32F777NI)
set(DEBUG_DEVICE "STM32F777NI")
set(DEBUG_SVD_FILE "STM32F7x7.svd")
elseif(CONFIG_ARCH_CHIP_STM32H743VI)
set(DEBUG_DEVICE "STM32H743VI")
set(DEBUG_SVD_FILE "STM32H7x3.svd")
elseif(CONFIG_ARCH_CHIP_STM32H743II)
set(DEBUG_DEVICE "STM32H743II")
set(DEBUG_SVD_FILE "STM32H7x3.svd")
+114
View File
@@ -0,0 +1,114 @@
/****************************************************************************
*
* Copyright (C) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
// minimal cmath
#pragma once
#include <cstdlib>
#include <inttypes.h>
#include <math.h>
#ifndef M_PI
#define M_PI 3.14159265358979323846
#endif
namespace std
{
#if !defined(FLT_EPSILON)
#define FLT_EPSILON __FLT_EPSILON__
#endif
#ifdef isfinite
#undef isfinite
#endif // isfinite
inline bool isfinite(float value) { return __builtin_isfinite(value); }
inline bool isfinite(double value) { return __builtin_isfinite(value); }
inline bool isfinite(long double value) { return __builtin_isfinite(value); }
#ifdef isnan
#undef isnan
#endif // isnan
inline bool isnan(float value) { return __builtin_isnan(value); }
inline bool isnan(double value) { return __builtin_isnan(value); }
inline bool isnan(long double value) { return __builtin_isnan(value); }
#ifdef isinf
#undef isinf
#endif // isinf
inline bool isinf(float value) { return __builtin_isinf_sign(value); }
inline bool isinf(double value) { return __builtin_isinf_sign(value); }
inline bool isinf(long double value) { return __builtin_isinf_sign(value); }
/*
* NuttX has no usable C++ math library, so we need to provide the needed definitions here manually.
*/
#define NUTTX_WRAP_MATH_FUN_UNARY(name) \
inline float name(float x) { return ::name##f(x); } \
inline double name(double x) { return ::name(x); } \
inline long double name(long double x) { return ::name##l(x); }
#define NUTTX_WRAP_MATH_FUN_BINARY(name) \
inline float name(float x, float y) { return ::name##f(x, y); } \
inline double name(double x, double y) { return ::name(x, y); } \
inline long double name(long double x, long double y) { return ::name##l(x, y); }
NUTTX_WRAP_MATH_FUN_UNARY(fabs)
NUTTX_WRAP_MATH_FUN_UNARY(log)
NUTTX_WRAP_MATH_FUN_UNARY(log10)
NUTTX_WRAP_MATH_FUN_UNARY(exp)
NUTTX_WRAP_MATH_FUN_UNARY(sqrt)
NUTTX_WRAP_MATH_FUN_UNARY(sin)
NUTTX_WRAP_MATH_FUN_UNARY(cos)
NUTTX_WRAP_MATH_FUN_UNARY(tan)
NUTTX_WRAP_MATH_FUN_UNARY(asin)
NUTTX_WRAP_MATH_FUN_UNARY(acos)
NUTTX_WRAP_MATH_FUN_UNARY(atan)
NUTTX_WRAP_MATH_FUN_UNARY(sinh)
NUTTX_WRAP_MATH_FUN_UNARY(cosh)
NUTTX_WRAP_MATH_FUN_UNARY(tanh)
NUTTX_WRAP_MATH_FUN_UNARY(ceil)
NUTTX_WRAP_MATH_FUN_UNARY(floor)
NUTTX_WRAP_MATH_FUN_BINARY(pow)
NUTTX_WRAP_MATH_FUN_BINARY(atan2)
}
@@ -33,3 +33,5 @@
px4_add_library(platform_gpio_mcp23009
mcp23009.cpp
)
target_link_libraries(platform_gpio_mcp23009 PRIVATE drivers__device) # device::I2C
@@ -32,9 +32,10 @@
****************************************************************************/
#pragma once
#include "micro_hal.h"
__BEGIN_DECLS
#define HW_INFO_SUFFIX "%0" STRINGIFY(HW_INFO_VER_DIGITS) "x%0" STRINGIFY(HW_INFO_REV_DIGITS) "x"
/************************************************************************************
* Name: board_determine_hw_info
*
@@ -0,0 +1,110 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#define HW_VERSION_EEPROM 0x7 //!< Get hw_info from EEPROM
#define HW_EEPROM_VERSION_MIN 0x10 //!< Minimum supported version
#pragma pack(push, 1)
typedef struct {
uint16_t id;
} mtd_mft_t;
typedef struct {
mtd_mft_t version;
uint16_t hw_extended_ver;
uint16_t crc;
} mtd_mft_v0_t;
typedef struct {
mtd_mft_t version;
uint16_t hw_extended_ver;
//{device tree overlay}
uint16_t crc;
} mtd_mft_v1_t;
#pragma pack(pop)
#define MTD_MFT_v0 0U //<! EEPROM MTD MFT structure version 0
#define MTD_MFT_v1 1U //<! EEPROM MTD MFT structure version 1
#define MTD_MFT_OFFSET 0 //<! Offset in EEPROM where mtd_mft data starts
__BEGIN_DECLS
/************************************************************************************
* Name: board_set_eeprom_hw_info
*
* Description:
* Function for writing hardware info to EEPROM
*
* Input Parameters:
* *path - path to mtd_mft
* *mtd_mft_unk - pointer to mtd_mft to write hw_info
*
* Returned Value:
* 0 - Successful storing to EEPROM
* -1 - Error while storing to EEPROM
*
************************************************************************************/
#if !defined(BOARD_HAS_SIMPLE_HW_VERSIONING) && defined(BOARD_HAS_VERSIONING)
__EXPORT int board_set_eeprom_hw_info(const char *path, mtd_mft_t *mtd_mft_unk);
#else
static inline int board_set_eeprom_hw_info(const char *path, mtd_mft_t *mtd_mft_unk) { return -ENOSYS; }
#endif
/************************************************************************************
* Name: board_get_eeprom_hw_info
*
* Description:
* Function for reading hardware info from EEPROM
*
* Output Parameters:
* *mtd_mft - pointer to mtd_mft to read hw_info
*
* Returned Value:
* 0 - Successful reading from EEPROM
* -1 - Error while reading from EEPROM
*
************************************************************************************/
#if !defined(BOARD_HAS_SIMPLE_HW_VERSIONING) && defined(BOARD_HAS_VERSIONING)
__EXPORT int board_get_eeprom_hw_info(const char *path, mtd_mft_t *mtd_mft);
#else
static inline int board_get_eeprom_hw_info(const char *path, mtd_mft_t *mtd_mft) { return -ENOSYS; }
#endif
__END_DECLS
+17 -15
View File
@@ -70,6 +70,7 @@
#include <nuttx/mtd/mtd.h>
#include <perf/perf_counter.h>
#include <board_config.h>
/************************************************************************************
* Pre-processor Definitions
@@ -195,11 +196,8 @@ int at24c_nuke(void);
* Private Data
************************************************************************************/
/* At present, only a single AT24 part is supported. In this case, a statically
* allocated state structure may be used.
*/
static struct at24c_dev_s g_at24c;
static uint8_t number_of_instances = 0u;
static struct at24c_dev_s g_at24c[BOARD_MTD_NUM_EEPROM];
/************************************************************************************
* Private Functions
@@ -262,7 +260,7 @@ void at24c_test(void)
unsigned errors = 0;
for (count = 0; count < 10000; count++) {
ssize_t result = at24c_bread(&g_at24c.mtd, 0, 1, buf);
ssize_t result = at24c_bread(&g_at24c[0].mtd, 0, 1, buf);
if (result == ERROR) {
if (errors++ > 2) {
@@ -538,13 +536,17 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
* other functions (such as a block or character driver front end).
*
************************************************************************************/
FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address)
int px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address, FAR struct mtd_dev_s **mtd_dev)
{
if (number_of_instances >= BOARD_MTD_NUM_EEPROM) {
return -ENOMEM;
}
FAR struct at24c_dev_s *priv;
finfo("dev: %p\n", dev);
finfo("dev: %p, mtd_dev %p\n", dev, mtd_dev);
/* Allocate a state structure (we allocate the structure instead of using
* a fixed, static allocation so that we can handle multiple FLASH devices.
@@ -553,7 +555,7 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
* to be extended to handle multiple FLASH parts on the same I2C bus.
*/
priv = &g_at24c;
priv = &g_at24c[number_of_instances];
if (priv) {
/* Initialize the allocated structure */
@@ -608,13 +610,13 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
priv->perf_resets_retries = NULL;
priv->perf_errors = NULL;
return NULL;
return ret;
}
/* Return the implementation-specific state structure as the MTD device */
*mtd_dev = (FAR struct mtd_dev_s *)priv;
++number_of_instances;
finfo("Return %p\n", priv);
return (FAR struct mtd_dev_s *)priv;
return 0;
}
/*
@@ -622,5 +624,5 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
*/
int at24c_nuke(void)
{
return at24c_eraseall(&g_at24c);
return at24c_eraseall(&g_at24c[0]);
}
@@ -58,7 +58,9 @@ static const px4_mft_entry_s mtd_mft = {
static const px4_mft_s default_mft = {
.nmft = 1,
.mfts = &mtd_mft
.mfts = {
&mtd_mft
}
};
@@ -73,9 +75,9 @@ __EXPORT int px4_mft_configure(const px4_mft_s *mft)
if (mft != nullptr) {
for (uint32_t m = 0; m < mft->nmft; m++) {
switch (mft->mfts[m].type) {
switch (mft->mfts[m]->type) {
case MTD:
px4_mtd_config(static_cast<const px4_mtd_manifest_t *>(mft->mfts[m].pmft));
px4_mtd_config(static_cast<const px4_mtd_manifest_t *>(mft->mfts[m]->pmft));
break;
case MFT:
@@ -95,10 +97,10 @@ __EXPORT int px4_mft_query(const px4_mft_s *mft, px4_manifest_types_e type,
if (mft != nullptr) {
for (uint32_t m = 0; m < mft->nmft; m++) {
if (mft->mfts[m].type == type)
if (mft->mfts[m]->type == type)
switch (type) {
case MTD:
return px4_mtd_query(sub, val);
return px4_mtd_query(sub, val, nullptr);
break;
case MFT:
+59 -47
View File
@@ -64,7 +64,8 @@ extern "C" {
off_t firstblock, off_t nblocks);
}
static int num_instances = 0;
static mtd_instance_s *instances = nullptr;
static int total_blocks = 0;
static mtd_instance_s *instances[MAX_MTD_INSTANCES] = {};
static int ramtron_attach(mtd_instance_s &instance)
@@ -147,15 +148,19 @@ static int at24xxx_attach(mtd_instance_s &instance)
/* start the MTD driver, attempt 5 times */
for (int i = 0; i < 5; i++) {
instance.mtd_dev = px4_at24c_initialize(i2c, PX4_I2C_DEVID_ADDR(instance.devid));
int ret_val = px4_at24c_initialize(i2c, PX4_I2C_DEVID_ADDR(instance.devid), &(instance.mtd_dev));
if (instance.mtd_dev) {
if (ret_val == 0) {
/* abort on first valid result */
if (i > 0) {
PX4_WARN("EEPROM needed %d attempts to attach", i + 1);
}
break;
} else if (ret_val == -ENOMEM) {
PX4_ERR("Number of at24c EEPROM instances reached the board limit of %d", BOARD_MTD_NUM_EEPROM);
break;
}
}
@@ -230,7 +235,7 @@ ssize_t px4_mtd_get_partition_size(const mtd_instance_s *instance, const char *p
return instance->partition_block_counts[partn] * blocksize;
}
mtd_instance_s *px4_mtd_get_instances(unsigned int *count)
mtd_instance_s **px4_mtd_get_instances(unsigned int *count)
{
*count = num_instances;
return instances;
@@ -292,62 +297,69 @@ int px4_mtd_config(const px4_mtd_manifest_t *mft_mtd)
}
rv = -ENOMEM;
int total_blocks = 0;
uint8_t total_new_instances = mtd_list->nconfigs + num_instances;
instances = new mtd_instance_s[mtd_list->nconfigs];
if (instances == nullptr) {
memoryout:
PX4_ERR("failed to allocate memory!");
if (total_new_instances >= MAX_MTD_INSTANCES) {
PX4_ERR("reached limit of max %u mtd instances", MAX_MTD_INSTANCES);
return rv;
}
for (uint32_t i = 0; i < mtd_list->nconfigs; i++) {
for (uint8_t i = num_instances, num_entry = 0u; i < total_new_instances; ++i, ++num_entry) {
instances[i] = new mtd_instance_s;
if (instances == nullptr) {
memoryout:
PX4_ERR("failed to allocate memory!");
return rv;
}
num_instances++;
uint32_t nparts = mtd_list->entries[i]->npart;
instances[i].devid = mtd_list->entries[i]->device->devid;
instances[i].mtd_dev = nullptr;
instances[i].n_partitions_current = 0;
uint32_t nparts = mtd_list->entries[num_entry]->npart;
instances[i]->devid = mtd_list->entries[num_entry]->device->devid;
instances[i]->mtd_dev = nullptr;
instances[i]->n_partitions_current = 0;
rv = -ENOMEM;
instances[i].part_dev = new FAR struct mtd_dev_s *[nparts];
instances[i]->part_dev = new FAR struct mtd_dev_s *[nparts];
if (instances[i].part_dev == nullptr) {
if (instances[i]->part_dev == nullptr) {
goto memoryout;
}
instances[i].partition_block_counts = new int[nparts];
instances[i]->partition_block_counts = new int[nparts];
if (instances[i].partition_block_counts == nullptr) {
if (instances[i]->partition_block_counts == nullptr) {
goto memoryout;
}
instances[i].partition_types = new int[nparts];
instances[i]->partition_types = new int[nparts];
if (instances[i].partition_types == nullptr) {
if (instances[i]->partition_types == nullptr) {
goto memoryout;
}
instances[i].partition_names = new const char *[nparts];
instances[i]->partition_names = new const char *[nparts];
if (instances[i].partition_names == nullptr) {
if (instances[i]->partition_names == nullptr) {
goto memoryout;
}
for (uint32_t p = 0; p < nparts; p++) {
instances[i].partition_block_counts[p] = mtd_list->entries[i]->partd[p].nblocks;
instances[i].partition_names[p] = mtd_list->entries[i]->partd[p].path;
instances[i].partition_types[p] = mtd_list->entries[i]->partd[p].type;
instances[i]->partition_block_counts[p] = mtd_list->entries[num_entry]->partd[p].nblocks;
instances[i]->partition_names[p] = mtd_list->entries[num_entry]->partd[p].path;
instances[i]->partition_types[p] = mtd_list->entries[num_entry]->partd[p].type;
}
if (mtd_list->entries[i]->device->bus_type == px4_mft_device_t::I2C) {
rv = at24xxx_attach(instances[i]);
if (mtd_list->entries[num_entry]->device->bus_type == px4_mft_device_t::I2C) {
rv = at24xxx_attach(*instances[i]);
} else if (mtd_list->entries[i]->device->bus_type == px4_mft_device_t::SPI) {
rv = ramtron_attach(instances[i]);
} else if (mtd_list->entries[num_entry]->device->bus_type == px4_mft_device_t::SPI) {
rv = ramtron_attach(*instances[i]);
} else if (mtd_list->entries[i]->device->bus_type == px4_mft_device_t::ONCHIP) {
instances[i].n_partitions_current++;
} else if (mtd_list->entries[num_entry]->device->bus_type == px4_mft_device_t::ONCHIP) {
instances[i]->n_partitions_current++;
return 0;
}
@@ -362,7 +374,7 @@ memoryout:
unsigned int nblocks;
unsigned int partsize;
rv = px4_mtd_get_geometry(&instances[i], &blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize);
rv = px4_mtd_get_geometry(instances[i], &blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize);
if (rv != 0) {
goto errout;
@@ -375,13 +387,13 @@ memoryout:
unsigned long offset;
unsigned part;
for (offset = 0, part = 0; rv == 0 && part < nparts; offset += instances[i].partition_block_counts[part], part++) {
for (offset = 0, part = 0; rv == 0 && part < nparts; offset += instances[i]->partition_block_counts[part], part++) {
/* Create the partition */
instances[i].part_dev[part] = mtd_partition(instances[i].mtd_dev, offset, instances[i].partition_block_counts[part]);
instances[i]->part_dev[part] = mtd_partition(instances[i]->mtd_dev, offset, instances[i]->partition_block_counts[part]);
if (instances[i].part_dev[part] == nullptr) {
if (instances[i]->part_dev[part] == nullptr) {
PX4_ERR("mtd_partition failed. offset=%lu nblocks=%u",
offset, nblocks);
rv = -ENOSPC;
@@ -392,7 +404,7 @@ memoryout:
snprintf(blockname, sizeof(blockname), "/dev/mtdblock%d", total_blocks);
rv = ftl_initialize(total_blocks, instances[i].part_dev[part]);
rv = ftl_initialize(total_blocks, instances[i]->part_dev[part]);
if (rv < 0) {
PX4_ERR("ftl_initialize %s failed: %d", blockname, rv);
@@ -403,14 +415,14 @@ memoryout:
/* Now create a character device on the block device */
rv = bchdev_register(blockname, instances[i].partition_names[part], false);
rv = bchdev_register(blockname, instances[i]->partition_names[part], false);
if (rv < 0) {
PX4_ERR("bchdev_register %s failed: %d", instances[i].partition_names[part], rv);
PX4_ERR("bchdev_register %s failed: %d", instances[i]->partition_names[part], rv);
goto errout;
}
instances[i].n_partitions_current++;
instances[i]->n_partitions_current++;
}
errout:
@@ -418,9 +430,9 @@ errout:
if (rv < 0) {
PX4_ERR("mtd failure: %d bus %" PRId32 " address %" PRId32 " class %d",
rv,
PX4_I2C_DEVID_BUS(instances[i].devid),
PX4_I2C_DEVID_ADDR(instances[i].devid),
mtd_list->entries[i]->partd[instances[i].n_partitions_current].type);
PX4_I2C_DEVID_BUS(instances[i]->devid),
PX4_I2C_DEVID_ADDR(instances[i]->devid),
mtd_list->entries[num_entry]->partd[instances[i]->n_partitions_current].type);
break;
}
}
@@ -452,14 +464,14 @@ __EXPORT int px4_mtd_query(const char *sub, const char *val, const char **get)
rv = -ENOENT;
for (int i = 0; i < num_instances; i++) {
for (unsigned n = 0; n < instances[i].n_partitions_current; n++) {
if (instances[i].partition_types[n] == key) {
for (unsigned n = 0; n < instances[i]->n_partitions_current; n++) {
if (instances[i]->partition_types[n] == key) {
if (get != nullptr && val == nullptr) {
*get = instances[i].partition_names[n];
*get = instances[i]->partition_names[n];
return 0;
}
if (val != nullptr && strcmp(instances[i].partition_names[n], val) == 0) {
if (val != nullptr && strcmp(instances[i]->partition_names[n], val) == 0) {
return 0;
}
}
@@ -37,14 +37,16 @@
* Implementation of generic user-space version API
*/
#include <systemlib/px4_macros.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform/board_determine_hw_info.h>
#include "board_config.h"
static int hw_version = 0;
static int hw_revision = 0;
static char hw_info[] = HW_INFO_INIT;
static char hw_info[] = HW_INFO_INIT_PREFIX HW_INFO_SUFFIX;
__EXPORT const char *board_get_hw_type_name(void)
{
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2019 PX4 Development Team. All rights reserved.
* Copyright (C) 2019, 2022 PX4 Development Team. All rights reserved.
* Author: @author David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
@@ -52,12 +52,16 @@
# define GPIO_HW_REV_DRIVE GPIO_HW_VER_REV_DRIVE
# define GPIO_HW_VER_DRIVE GPIO_HW_VER_REV_DRIVE
# endif
#define HW_INFO_SIZE (int) arraySize(HW_INFO_INIT_PREFIX) + HW_INFO_VER_DIGITS + HW_INFO_REV_DIGITS
/****************************************************************************
* Private Data
****************************************************************************/
static int hw_version = 0;
static int hw_revision = 0;
static char hw_info[] = HW_INFO_INIT;
static char hw_info[HW_INFO_SIZE] = {0};
/****************************************************************************
* Protected Functions
@@ -193,7 +197,7 @@ static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc
/* Are Resistors in place ?*/
uint32_t dn_sum = 0;
uint16_t dn = 0;
uint32_t dn = 0;
if ((high ^ low) && low == 0) {
/* Yes - Fire up the ADC (it has once control) */
@@ -204,14 +208,14 @@ static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc
for (unsigned av = 0; av < samples; av++) {
dn = px4_arch_adc_sample(HW_REV_VER_ADC_BASE, adc_channel);
if (dn == 0xffff) {
if (dn == UINT32_MAX) {
break;
}
dn_sum += dn;
}
if (dn != 0xffff) {
if (dn != UINT32_MAX) {
*id = dn_sum / samples;
rv = OK;
}
@@ -338,8 +342,12 @@ int board_determine_hw_info()
int rv = determine_hw_info(&hw_revision, &hw_version);
if (rv == OK) {
hw_info[HW_INFO_INIT_REV] = board_get_hw_revision() + '0';
hw_info[HW_INFO_INIT_VER] = board_get_hw_version() + '0';
if (rv == OK) {
snprintf(hw_info, sizeof(hw_info), HW_INFO_INIT_PREFIX HW_INFO_SUFFIX, hw_version, hw_revision);
}
}
return rv;
@@ -34,4 +34,4 @@
px4_add_library(arch_board_hw_info
board_hw_rev_ver.c
)
target_link_libraries(arch_board_hw_info PRIVATE arch_adc)
target_link_libraries(arch_board_hw_info PRIVATE arch_adc systemlib)
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Copyright (C) 2017, 2022 PX4 Development Team. All rights reserved.
* Author: @author David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
@@ -41,10 +41,14 @@
#include <px4_arch/adc.h>
#include <px4_platform_common/micro_hal.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/px4_manifest.h>
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_hw_eeprom_rev_ver.h>
#include <stdio.h>
#include <fcntl.h>
#include <board_config.h>
#include <systemlib/crc.h>
#include <systemlib/px4_macros.h>
#if defined(BOARD_HAS_HW_VERSIONING)
@@ -53,12 +57,16 @@
# define GPIO_HW_REV_DRIVE GPIO_HW_VER_REV_DRIVE
# define GPIO_HW_VER_DRIVE GPIO_HW_VER_REV_DRIVE
# endif
#define HW_INFO_SIZE (int) arraySize(HW_INFO_INIT_PREFIX) + HW_INFO_VER_DIGITS + HW_INFO_REV_DIGITS
/****************************************************************************
* Private Data
****************************************************************************/
static int hw_version = 0;
static int hw_revision = 0;
static char hw_info[] = HW_INFO_INIT;
static char hw_info[HW_INFO_SIZE] = {0};
/****************************************************************************
* Protected Functions
@@ -437,18 +445,170 @@ __EXPORT int board_get_hw_revision()
int board_determine_hw_info()
{
// MFT supported?
const char *path;
int rvmft = px4_mtd_query("MTD_MFT", NULL, &path);
// Read ADC jumpering hw_info
int rv = determine_hw_info(&hw_revision, &hw_version);
if (rv == OK) {
hw_info[HW_INFO_INIT_REV] = board_get_hw_revision() < 10 ?
board_get_hw_revision() + '0' :
board_get_hw_revision() + 'a' - 10;
hw_info[HW_INFO_INIT_VER] = board_get_hw_version() < 10 ?
board_get_hw_version() + '0' :
board_get_hw_version() + 'a' - 10;
if (rvmft == OK && path != NULL && hw_version == HW_VERSION_EEPROM) {
mtd_mft_v0_t mtd_mft = {MTD_MFT_v0};
rv = board_get_eeprom_hw_info(path, (mtd_mft_t *)&mtd_mft);
if (rv == OK) {
hw_version = mtd_mft.hw_extended_ver;
}
}
}
if (rv == OK) {
snprintf(hw_info, sizeof(hw_info), HW_INFO_INIT_PREFIX HW_INFO_SUFFIX, hw_version, hw_revision);
}
return rv;
}
/************************************************************************************
* Name: board_set_eeprom_hw_info
*
* Description:
* Function for writing hardware info to EEPROM
*
* Input Parameters:
* *mtd_mft_unk - pointer to mtd_mft to write hw_info
*
* Returned Value:
* 0 - Successful storing to EEPROM
* -1 - Error while storing to EEPROM
*
************************************************************************************/
int board_set_eeprom_hw_info(const char *path, mtd_mft_t *mtd_mft_unk)
{
if (mtd_mft_unk == NULL || path == NULL) {
return -EINVAL;
}
// Later this will be a demux on type
if (mtd_mft_unk->id != MTD_MFT_v0) {
printf("Verson is: %d, Only mft version %d is supported\n", mtd_mft_unk->id, MTD_MFT_v0);
return -EINVAL;
}
mtd_mft_v0_t *mtd_mft = (mtd_mft_v0_t *)mtd_mft_unk;
if (mtd_mft->hw_extended_ver < HW_EEPROM_VERSION_MIN) {
printf("hardware version for EEPROM must be greater than %x\n", HW_EEPROM_VERSION_MIN);
return -EINVAL;
}
int fd = open(path, O_WRONLY);
if (fd < 0) {
return -errno;
}
int ret_val = OK;
mtd_mft->crc = crc16_signature(CRC16_INITIAL, sizeof(*mtd_mft) - sizeof(mtd_mft->crc), (uint8_t *) mtd_mft);
if (
(MTD_MFT_OFFSET != lseek(fd, MTD_MFT_OFFSET, SEEK_SET)) ||
(sizeof(*mtd_mft) != write(fd, mtd_mft, sizeof(*mtd_mft)))
) {
ret_val = -errno;
}
close(fd);
return ret_val;
}
/************************************************************************************
* Name: board_get_eeprom_hw_info
*
* Description:
* Function for reading hardware info from EEPROM
*
* Output Parameters:
* *mtd_mft - pointer to mtd_mft to read hw_info
*
* Returned Value:
* 0 - Successful reading from EEPROM
* -1 - Error while reading from EEPROM
*
************************************************************************************/
__EXPORT int board_get_eeprom_hw_info(const char *path, mtd_mft_t *mtd_mft)
{
if (mtd_mft == NULL || path == NULL) {
return -EINVAL;
}
int fd = open(path, O_RDONLY);
if (fd < 0) {
return -errno;
}
int ret_val = OK;
mtd_mft_t format_version = {-1};
if (
(MTD_MFT_OFFSET != lseek(fd, MTD_MFT_OFFSET, SEEK_SET)) ||
(sizeof(format_version) != read(fd, &format_version, sizeof(format_version)))
) {
ret_val = -errno;
} else if (format_version.id != mtd_mft->id) {
ret_val = -EPROTO;
} else {
uint16_t mft_size = 0;
switch (format_version.id) {
case MTD_MFT_v0: mft_size = sizeof(mtd_mft_v0_t); break;
case MTD_MFT_v1: mft_size = sizeof(mtd_mft_v1_t); break;
default:
printf("[boot] Error, unknown version %d of mtd_mft in EEPROM\n", format_version.id);
ret_val = -1;
break;
}
if (ret_val == OK) {
if (
(MTD_MFT_OFFSET != lseek(fd, MTD_MFT_OFFSET, SEEK_SET)) ||
(mft_size != read(fd, mtd_mft, mft_size))
) {
ret_val = -errno;
} else {
union {
uint16_t w;
uint8_t b[2];
} crc;
uint8_t *bytes = (uint8_t *) mtd_mft;
crc.w = crc16_signature(CRC16_INITIAL, mft_size - sizeof(crc), bytes);
uint8_t *eeprom_crc = &bytes[mft_size - sizeof(crc)];
if (!(crc.b[0] == eeprom_crc[0] && crc.b[1] == eeprom_crc[1])) {
ret_val = -1;
}
}
}
}
close(fd);
return ret_val;
}
#endif
+3
View File
@@ -0,0 +1,3 @@
menu "actuators"
rsource "*/Kconfig"
endmenu #actuators
@@ -0,0 +1,50 @@
############################################################################
#
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__actuators__modalai_esc
MAIN modalai_esc
SRCS
crc16.c
crc16.h
modalai_esc_serial.cpp
modalai_esc_serial.hpp
modalai_esc.cpp
modalai_esc.hpp
qc_esc_packet_types.h
qc_esc_packet.c
qc_esc_packet.h
DEPENDS
px4_work_queue
)
@@ -0,0 +1,5 @@
menuconfig DRIVERS_ACTUATORS_MODALAI_ESC
bool "modalai_esc"
default n
---help---
Enable support for modalai_esc
+95
View File
@@ -0,0 +1,95 @@
/****************************************************************************
* Copyright (c) 2017 The Linux Foundation. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name The Linux Foundation nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY
* THIS LICENSE.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
* In addition Supplemental Terms apply. See the SUPPLEMENTAL file.
*
****************************************************************************/
#include <stdint.h>
#include "crc16.h"
// Look-up table for fast CRC16 computations
const uint16_t crc16_table[256] = {
0x0000, 0xc0c1, 0xc181, 0x0140, 0xc301, 0x03c0, 0x0280, 0xc241,
0xc601, 0x06c0, 0x0780, 0xc741, 0x0500, 0xc5c1, 0xc481, 0x0440,
0xcc01, 0x0cc0, 0x0d80, 0xcd41, 0x0f00, 0xcfc1, 0xce81, 0x0e40,
0x0a00, 0xcac1, 0xcb81, 0x0b40, 0xc901, 0x09c0, 0x0880, 0xc841,
0xd801, 0x18c0, 0x1980, 0xd941, 0x1b00, 0xdbc1, 0xda81, 0x1a40,
0x1e00, 0xdec1, 0xdf81, 0x1f40, 0xdd01, 0x1dc0, 0x1c80, 0xdc41,
0x1400, 0xd4c1, 0xd581, 0x1540, 0xd701, 0x17c0, 0x1680, 0xd641,
0xd201, 0x12c0, 0x1380, 0xd341, 0x1100, 0xd1c1, 0xd081, 0x1040,
0xf001, 0x30c0, 0x3180, 0xf141, 0x3300, 0xf3c1, 0xf281, 0x3240,
0x3600, 0xf6c1, 0xf781, 0x3740, 0xf501, 0x35c0, 0x3480, 0xf441,
0x3c00, 0xfcc1, 0xfd81, 0x3d40, 0xff01, 0x3fc0, 0x3e80, 0xfe41,
0xfa01, 0x3ac0, 0x3b80, 0xfb41, 0x3900, 0xf9c1, 0xf881, 0x3840,
0x2800, 0xe8c1, 0xe981, 0x2940, 0xeb01, 0x2bc0, 0x2a80, 0xea41,
0xee01, 0x2ec0, 0x2f80, 0xef41, 0x2d00, 0xedc1, 0xec81, 0x2c40,
0xe401, 0x24c0, 0x2580, 0xe541, 0x2700, 0xe7c1, 0xe681, 0x2640,
0x2200, 0xe2c1, 0xe381, 0x2340, 0xe101, 0x21c0, 0x2080, 0xe041,
0xa001, 0x60c0, 0x6180, 0xa141, 0x6300, 0xa3c1, 0xa281, 0x6240,
0x6600, 0xa6c1, 0xa781, 0x6740, 0xa501, 0x65c0, 0x6480, 0xa441,
0x6c00, 0xacc1, 0xad81, 0x6d40, 0xaf01, 0x6fc0, 0x6e80, 0xae41,
0xaa01, 0x6ac0, 0x6b80, 0xab41, 0x6900, 0xa9c1, 0xa881, 0x6840,
0x7800, 0xb8c1, 0xb981, 0x7940, 0xbb01, 0x7bc0, 0x7a80, 0xba41,
0xbe01, 0x7ec0, 0x7f80, 0xbf41, 0x7d00, 0xbdc1, 0xbc81, 0x7c40,
0xb401, 0x74c0, 0x7580, 0xb541, 0x7700, 0xb7c1, 0xb681, 0x7640,
0x7200, 0xb2c1, 0xb381, 0x7340, 0xb101, 0x71c0, 0x7080, 0xb041,
0x5000, 0x90c1, 0x9181, 0x5140, 0x9301, 0x53c0, 0x5280, 0x9241,
0x9601, 0x56c0, 0x5780, 0x9741, 0x5500, 0x95c1, 0x9481, 0x5440,
0x9c01, 0x5cc0, 0x5d80, 0x9d41, 0x5f00, 0x9fc1, 0x9e81, 0x5e40,
0x5a00, 0x9ac1, 0x9b81, 0x5b40, 0x9901, 0x59c0, 0x5880, 0x9841,
0x8801, 0x48c0, 0x4980, 0x8941, 0x4b00, 0x8bc1, 0x8a81, 0x4a40,
0x4e00, 0x8ec1, 0x8f81, 0x4f40, 0x8d01, 0x4dc0, 0x4c80, 0x8c41,
0x4400, 0x84c1, 0x8581, 0x4540, 0x8701, 0x47c0, 0x4680, 0x8641,
0x8201, 0x42c0, 0x4380, 0x8341, 0x4100, 0x81c1, 0x8081, 0x4040,
};
uint16_t crc16_init()
{
return 0xFFFF;
}
uint16_t crc16_byte(uint16_t prev_crc, const uint8_t new_byte)
{
uint8_t lut = (prev_crc ^ new_byte) & 0xFF;
return (prev_crc >> 8) ^ crc16_table[lut];
}
uint16_t crc16(uint16_t prev_crc, uint8_t const *input_buffer, uint16_t input_length)
{
uint16_t crc = prev_crc;
while (input_length--) {
crc = crc16_byte(crc, *input_buffer++);
}
return crc;
}
+65
View File
@@ -0,0 +1,65 @@
/****************************************************************************
* Copyright (c) 2017 The Linux Foundation. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name The Linux Foundation nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY
* THIS LICENSE.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
* In addition Supplemental Terms apply. See the SUPPLEMENTAL file.
*
****************************************************************************/
/*
* This file contains function prototypes for crc16 computations using polynomial 0x8005
*/
#ifndef CRC16_H_
#define CRC16_H_
#ifdef __cplusplus
extern "C"
{
#endif
#include <stdint.h>
// Returns the seed of crc output, which should be used when computing crc16 of a byte sequence
uint16_t crc16_init(void);
// Process one byte by providing crc16 from previous step and new byte to consume.
// Output is the new crc16 value
uint16_t crc16_byte(uint16_t prev_crc, const uint8_t new_byte);
// Process an array of bytes by providing crc16 from previous step (or seed), array of bytes and its length
// Output is the new crc16 value
uint16_t crc16(uint16_t prev_crc, uint8_t const *input_buffer, uint16_t input_length);
#ifdef __cplusplus
}
#endif
#endif //CRC16_H_
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,237 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <drivers/device/device.h>
#include <drivers/drv_mixer.h>
#include <lib/cdev/CDev.hpp>
#include <lib/led/led.h>
#include <lib/mixer_module/mixer_module.hpp>
#include <lib/perf/perf_counter.h>
#include <px4_log.h>
#include <px4_platform_common/module.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/esc_status.h>
#include "modalai_esc_serial.hpp"
#include "qc_esc_packet.h"
#include "qc_esc_packet_types.h"
class ModalaiEsc : public cdev::CDev, public ModuleBase<ModalaiEsc>, public OutputModuleInterface
{
public:
ModalaiEsc();
virtual ~ModalaiEsc();
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
/** @see ModuleBase::run() */
void Run() override;
/** @see ModuleBase::print_status() */
int print_status() override;
/** @see OutputModuleInterface */
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;
/** @see OutputModuleInterface */
void mixerChanged() override;
virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual int init();
typedef enum {
UART_ESC_RESET,
UART_ESC_VERSION,
UART_ESC_TONE,
UART_ESC_LED
} uart_esc_cmd_t;
struct Command {
uint16_t id = 0;
uint8_t len = 0;
uint16_t repeats = 0;
uint16_t repeat_delay_us = 2000;
uint8_t retries = 0;
bool response = false;
uint16_t resp_delay_us = 1000;
bool print_feedback = false;
static const uint8_t BUF_SIZE = 128;
uint8_t buf[BUF_SIZE];
bool valid() const { return len > 0; }
void clear() { len = 0; }
};
int sendCommandThreadSafe(Command *cmd);
private:
static constexpr uint32_t MODALAI_ESC_UART_CONFIG = 1;
static constexpr uint32_t MODALAI_ESC_DEFAULT_BAUD = 250000;
static constexpr uint16_t MODALAI_ESC_OUTPUT_CHANNELS = 4;
static constexpr uint16_t MODALAI_ESC_OUTPUT_DISABLED = 0;
static constexpr uint32_t MODALAI_ESC_WRITE_WAIT_US = 200;
static constexpr uint32_t MODALAI_ESC_DISCONNECT_TIMEOUT_US = 500000;
static constexpr uint16_t DISARMED_VALUE = 0;
static constexpr uint16_t MODALAI_ESC_PWM_MIN = 0;
static constexpr uint16_t MODALAI_ESC_PWM_MAX = 800;
static constexpr uint16_t MODALAI_ESC_DEFAULT_RPM_MIN = 5000;
static constexpr uint16_t MODALAI_ESC_DEFAULT_RPM_MAX = 17000;
static constexpr float MODALAI_ESC_MODE_DISABLED_SETPOINT = -0.1f;
static constexpr float MODALAI_ESC_MODE_THRESHOLD = 0.0f;
static constexpr float MODALAI_ESC_MODE_DEAD_ZONE_MIN = 0.0f;
static constexpr float MODALAI_ESC_MODE_DEAD_ZONE_MAX = 1.0f;
static constexpr float MODALAI_ESC_MODE_DEAD_ZONE_1 = 0.30f;
static constexpr float MODALAI_ESC_MODE_DEAD_ZONE_2 = 0.02f;
static constexpr uint32_t MODALAI_ESC_MODE = 0;
static constexpr uint32_t MODALAI_ESC_MODE_TURTLE_AUX1 = 1;
static constexpr uint32_t MODALAI_ESC_MODE_TURTLE_AUX2 = 2;
static constexpr uint32_t MODALAI_ESC_MODE_UART_BRIDGE = 3;
//static constexpr uint16_t max_pwm(uint16_t pwm) { return math::min(pwm, MODALAI_ESC_PWM_MAX); }
//static constexpr uint16_t max_rpm(uint16_t rpm) { return math::min(rpm, MODALAI_ESC_RPM_MAX); }
ModalaiEscSerial *_uart_port;
ModalaiEscSerial *_uart_port_bridge;
typedef struct {
int32_t config{MODALAI_ESC_UART_CONFIG};
int32_t mode{MODALAI_ESC_MODE};
float dead_zone_1{MODALAI_ESC_MODE_DEAD_ZONE_1};
float dead_zone_2{MODALAI_ESC_MODE_DEAD_ZONE_2};
int32_t baud_rate{MODALAI_ESC_DEFAULT_BAUD};
int32_t rpm_min{MODALAI_ESC_DEFAULT_RPM_MIN};
int32_t rpm_max{MODALAI_ESC_DEFAULT_RPM_MAX};
int32_t motor_map[MODALAI_ESC_OUTPUT_CHANNELS] {1, 2, 3, 4};
} uart_esc_params_t;
struct EscChan {
int16_t rate_req;
uint8_t state;
uint16_t rate_meas;
uint8_t power_applied;
uint8_t led;
uint8_t cmd_counter;
float voltage; //Volts
float current; //Amps
float temperature; //deg C
hrt_abstime feedback_time;
};
typedef struct {
uint8_t number;
int8_t direction;
} ch_assign_t;
typedef struct {
led_control_s control{};
vehicle_control_mode_s mode{};
uint8_t led_mask;// TODO led_mask[MODALAI_ESC_OUTPUT_CHANNELS];
bool breath_en;
uint8_t breath_counter;
bool test;
} led_rsc_t;
ch_assign_t _output_map[MODALAI_ESC_OUTPUT_CHANNELS] {{1, 1}, {2, 1}, {3, 1}, {4, 1}};
MixingOutput _mixing_output{"MODALAI_ESC", MODALAI_ESC_OUTPUT_CHANNELS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
int _class_instance{-1};
perf_counter_t _cycle_perf;
perf_counter_t _output_update_perf;
bool _outputs_on{false};
unsigned _current_update_rate{0};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _led_update_sub{ORB_ID(led_control)};
//uORB::Publication<actuator_outputs_s> _outputs_debug_pub{ORB_ID(actuator_outputs_debug)};
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
uart_esc_params_t _parameters;
int update_params();
int load_params(uart_esc_params_t *params, ch_assign_t *map);
bool _turtle_mode_en{false};
int32_t _rpm_fullscale{0};
manual_control_setpoint_s _manual_control_setpoint{};
uint16_t _cmd_id{0};
Command _current_cmd;
px4::atomic<Command *> _pending_cmd{nullptr};
EscChan _esc_chans[MODALAI_ESC_OUTPUT_CHANNELS] {};
Command _esc_cmd;
esc_status_s _esc_status;
EscPacket _fb_packet;
EscPacket _uart_bridge_packet;
led_rsc_t _led_rsc;
int _fb_idx;
static const uint8_t READ_BUF_SIZE = 128;
uint8_t _read_buf[READ_BUF_SIZE];
void updateLeds(vehicle_control_mode_s mode, led_control_s control);
int populateCommand(uart_esc_cmd_t cmd_type, uint8_t cmd_mask, Command *out_cmd);
int readResponse(Command *out_cmd);
int parseResponse(uint8_t *buf, uint8_t len, bool print_feedback);
int flushUartRx();
int checkForEscTimeout();
};
@@ -0,0 +1,163 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "string.h"
#include "modalai_esc_serial.hpp"
ModalaiEscSerial::ModalaiEscSerial()
{
}
ModalaiEscSerial::~ModalaiEscSerial()
{
if (_uart_fd >= 0) {
uart_close();
}
}
int ModalaiEscSerial::uart_open(const char *dev, speed_t speed)
{
if (_uart_fd >= 0) {
PX4_ERR("Port in use: %s (%i)", dev, errno);
return -1;
}
/* Open UART */
_uart_fd = open(dev, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (_uart_fd < 0) {
PX4_ERR("Error opening port: %s (%i)", dev, errno);
return -1;
}
/* Back up the original UART configuration to restore it after exit */
int termios_state;
if ((termios_state = tcgetattr(_uart_fd, &_orig_cfg)) < 0) {
PX4_ERR("Error configuring port: tcgetattr %s: %d", dev, termios_state);
uart_close();
return -1;
}
/* Fill the struct for the new configuration */
tcgetattr(_uart_fd, &_cfg);
/* Disable output post-processing */
_cfg.c_oflag &= ~OPOST;
_cfg.c_cflag |= (CLOCAL | CREAD); /* ignore modem controls */
_cfg.c_cflag &= ~CSIZE;
_cfg.c_cflag |= CS8; /* 8-bit characters */
_cfg.c_cflag &= ~PARENB; /* no parity bit */
_cfg.c_cflag &= ~CSTOPB; /* only need 1 stop bit */
_cfg.c_cflag &= ~CRTSCTS; /* no hardware flowcontrol */
/* setup for non-canonical mode */
_cfg.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON);
_cfg.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
if (cfsetispeed(&_cfg, speed) < 0 || cfsetospeed(&_cfg, speed) < 0) {
PX4_ERR("Error configuring port: %s: %d (cfsetispeed, cfsetospeed)", dev, termios_state);
uart_close();
return -1;
}
if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &_cfg)) < 0) {
PX4_ERR("Error configuring port: %s (tcsetattr)", dev);
uart_close();
return -1;
}
_speed = speed;
return 0;
}
int ModalaiEscSerial::uart_set_baud(speed_t speed)
{
if (_uart_fd < 0) {
return -1;
}
if (cfsetispeed(&_cfg, speed) < 0) {
return -1;
}
if (tcsetattr(_uart_fd, TCSANOW, &_cfg) < 0) {
return -1;
}
_speed = speed;
return 0;
}
int ModalaiEscSerial::uart_close()
{
if (_uart_fd < 0) {
PX4_ERR("invalid state for closing");
return -1;
}
if (tcsetattr(_uart_fd, TCSANOW, &_orig_cfg)) {
PX4_ERR("failed restoring uart to original state");
}
if (close(_uart_fd)) {
PX4_ERR("error closing uart");
}
_uart_fd = -1;
return 0;
}
int ModalaiEscSerial::uart_write(FAR void *buf, size_t len)
{
if (_uart_fd < 0 || buf == NULL) {
PX4_ERR("invalid state for writing or buffer");
return -1;
}
return write(_uart_fd, buf, len);
}
int ModalaiEscSerial::uart_read(FAR void *buf, size_t len)
{
if (_uart_fd < 0 || buf == NULL) {
PX4_ERR("invalid state for reading or buffer");
return -1;
}
return read(_uart_fd, buf, len);
}
@@ -0,0 +1,61 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_log.h>
#include <errno.h>
#include <fcntl.h>
#include <termios.h>
class ModalaiEscSerial
{
public:
ModalaiEscSerial();
virtual ~ModalaiEscSerial();
int uart_open(const char *dev, speed_t speed);
int uart_set_baud(speed_t speed);
int uart_close();
int uart_write(FAR void *buf, size_t len);
int uart_read(FAR void *buf, size_t len);
bool is_open() { return _uart_fd >= 0; };
int uart_get_baud() {return _speed; }
private:
int _uart_fd = -1;
struct termios _orig_cfg;
struct termios _cfg;
int _speed = -1;
};
@@ -0,0 +1,167 @@
/****************************************************************************
*
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* UART ESC configuration
*
* Selects what type of UART ESC, if any, is being used.
*
* @reboot_required true
*
* @group UART ESC
* @value 0 - Disabled
* @value 1 - VOXL ESC
* @min 0
* @max 1
*/
PARAM_DEFINE_INT32(UART_ESC_CONFIG, 0);
/**
* UART ESC baud rate
*
* Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products.
*
* @group UART ESC
* @unit bit/s
*/
PARAM_DEFINE_INT32(UART_ESC_BAUD, 250000);
/**
* Motor mappings for ModalAI ESC M004
*
* HW Channel Idexes (PX4 Indexes) (note: silkscreen shows 0 indexed)
* 4(1) 3(4)
* [front]
* 1(3) 2(2)
*/
/**
* UART ESC Motor 1 Mapping. 1-4 (negative for reversal).
*
* @group UART ESC
* @min -4
* @max 4
*/
PARAM_DEFINE_INT32(UART_ESC_MOTOR1, 3);
/**
*UART ESC Motor 2 Mapping. 1-4 (negative for reversal).
*
* @group UART ESC
* @min -4
* @max 4
*/
PARAM_DEFINE_INT32(UART_ESC_MOTOR2, 2);
/**
* UART ESC Motor 3 Mapping. 1-4 (negative for reversal).
*
* @group UART ESC
* @min -4
* @max 4
*/
PARAM_DEFINE_INT32(UART_ESC_MOTOR3, 4);
/**
* UART ESC Motor 4 Mapping. 1-4 (negative for reversal).
*
* @group UART ESC
* @min -4
* @max 4
*/
PARAM_DEFINE_INT32(UART_ESC_MOTOR4, 1);
/**
* UART ESC RPM Min
*
* Minimum RPM for ESC
*
* @group UART ESC
* @unit RPM
*/
PARAM_DEFINE_INT32(UART_ESC_RPM_MIN, 5500);
/**
* UART ESC RPM Max
*
* Maximum RPM for ESC
*
* @group UART ESC
* @unit RPM
*/
PARAM_DEFINE_INT32(UART_ESC_RPM_MAX, 15000);
/**
* UART ESC Mode
*
* Selects what type of mode is enabled, if any
*
* @reboot_required true
*
* @group UART ESC
* @value 0 - None
* @value 1 - Turtle Mode enabled via AUX1
* @value 2 - Turtle Mode enabled via AUX2
* @min 0
* @max 2
*/
PARAM_DEFINE_INT32(UART_ESC_MODE, 0);
/**
* UART ESC Mode Deadzone 1.
*
* Must be greater than Deadzone 2.
* Absolute value of stick position needed to activate a motor.
*
* @group UART ESC Mode Deadzone 1
* @min 0.01
* @max 0.99
* @decimal 10
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(UART_ESC_DEAD1, 0.30f);
/**
* UART ESC Mode Deadzone 2.
*
* Must be less than Deadzone 1.
* Absolute value of stick position considered no longer on the X or Y axis,
* thus targetting a specific motor (single).
*
* @group UART ESC Mode Deadzone 2
* @min 0.01
* @max 0.99
* @decimal 10
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(UART_ESC_DEAD2, 0.02f);

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