Compare commits

...

13 Commits

Author SHA1 Message Date
Hamish Willee 317c32fe2e Update mavlink to latest - for airspeed 2025-10-29 10:41:58 +11:00
PX4 Build Bot a1e5a959b5 New Crowdin translations - uk (#25812)
Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
2025-10-29 09:23:08 +11:00
PX4 Build Bot 99965337f1 New Crowdin translations - zh-CN (#25813)
Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
2025-10-29 09:22:59 +11:00
PX4 Build Bot c536120e3d New Crowdin translations - ko (#25811)
Co-authored-by: Crowdin Bot <support+bot@crowdin.com>
2025-10-29 09:16:54 +11:00
mahima-yoga 73ee098a25 fw_autotune: continue to next axis in case of convergence timeout 2025-10-28 13:16:40 +01:00
mahima-yoga 482683d156 fw-autotune: update docs 2025-10-24 17:38:54 +02:00
mahima-yoga 97c16352a5 fw-autotune: increase abort timeout to 30 seconds
Avoids abort on heavily undertuned systems during amplitude detection state
2025-10-24 17:38:54 +02:00
mahima-yoga fe35f1a34b fw-autotune: run state machine at 50Hz 2025-10-24 17:38:54 +02:00
mahima-yoga 7323075527 fw-autotune: use 0.75*rate_limit as the target rate. 2025-10-24 17:38:54 +02:00
Silvan Fuhrer 17e96554ec Navigator: fix RTL_TYP=2 with NAV_CMD_CONDITION_GATE (#25648)
* rtl_mission_fast: make sure to set a position item on activation

* rtl_mission_fast_reverse: make sure to set a position item on activation

---------

Co-authored-by: Konrad Rudin <konrad@auterion.com>
2025-10-24 10:10:33 +02:00
Hamish Willee 8f38a2ddbc uORB doc update: SensorBaro, DifferentialPressure (#25712) 2025-10-24 06:07:28 +11:00
Ramon Roche 6f4605dd04 ci: better container cache
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
2025-10-23 11:36:33 -07:00
Balduin 1c821cf83d FlightTaskAuto: disable MPC_LAND_RADIUS by default with value -1 (#25275)
* FlightTaskAuto: disable MPC_LAND_RADIUS by default

* format & comment

* Remove position valididy check again

* clean up according to review
2025-10-23 17:36:46 +02:00
25 changed files with 672 additions and 77 deletions
+2 -2
View File
@@ -130,8 +130,8 @@ jobs:
load: false
push: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }}
provenance: false
cache-from: type=gha,version=1
cache-to: type=gha,version=1,mode=max
cache-from: type=gha,version=1,scope=${{ matrix.arch }}
cache-to: type=gha,version=1,mode=max,scope=${{ matrix.arch }}
deploy:
name: Deploy To Registry
+2 -3
View File
@@ -98,8 +98,7 @@ The test steps are:
</div><div v-else-if="$frontmatter.frame === 'Plane'">
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
The progress is shown in the progress bar, next to the _Autotune_ button.
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
</div>
<div style="display: inline;" v-if="$frontmatter.frame === 'Multicopter'">
@@ -194,7 +193,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
</div>
<div v-else-if="$frontmatter.frame === 'Plane'">
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates.
If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration.
+1
View File
@@ -187,6 +187,7 @@
- [Radiolink PIX6](flight_controller/radiolink_pix6.md)
- [Sky-Drones AIRLink](flight_controller/airlink.md)
- [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md)
- [SVehicle E2](flight_controller/svehicle_e2.md)
- [ThePeach FCC-K1](flight_controller/thepeach_k1.md)
- [ThePeach FCC-R1](flight_controller/thepeach_r1.md)
- [Experimental Autopilots](flight_controller/autopilot_experimental.md)
+2 -3
View File
@@ -102,8 +102,7 @@ The test steps are:
</div><div v-else-if="$frontmatter.frame === 'Plane'">
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
The progress is shown in the progress bar, next to the _Autotune_ button.
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
</div>
<div style="display: inline;" v-if="$frontmatter.frame === 'Multicopter'">
@@ -198,7 +197,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
</div>
<div v-else-if="$frontmatter.frame === 'Plane'">
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates.
If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration.
@@ -35,5 +35,6 @@ This category includes boards that are not fully compliant with the pixhawk stan
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md)
- [Sky-Drones AIRLink](../flight_controller/airlink.md)
- [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md)
- [Svehicle E2](../flight_controller/svehicle_e2.md)
- [ThePeach FCC-K1](../flight_controller/thepeach_k1.md)
- [ThePeach FCC-R1](../flight_controller/thepeach_r1.md)
+177
View File
@@ -0,0 +1,177 @@
# S-Vehicle E2
:::warning
PX4 does not manufacture this (or any) autopilot.
:::
The _E2_ is an advanced autopilot manufactured by S-Vehicle<sup>&reg;</sup>.
The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications.
It brings you ultimate performance, stability, and reliability in every aspect.
![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png)
:::info
이 비행 컨트롤러는 [제조업체에서 지원](../flight_controller/autopilot_manufacturer_supported.md)합니다.
:::
### Processors & Sensors
- FMU Processor: STM32H753IIK6
- 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM
- IO Processor: STM32F103
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- 내장 센서 :
- Accel/Gyro: BMI088
- Accel/Gyro: ICM-42688-P
- Accel/Gyro: ICM-20649
- Mag: RM3100
- Barometer: 2x ICP-20100
### 인터페이스
- 14x PWM Servo Outputs
- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus
- 1x Analog/PWM RSSI Input
- 2x TELEM Ports (with full flow control)
- 1x UART4 Port
- 2x GPS Ports
- 1x Full GPS plus Safety Switch Port (GPS1)
- 1x Basic GPS Port (with I2C, GPS2)
- 1x USB Port (TYPE-C)
- 1x Ethernet Port
- Transformerless application
- 100Mbps
- 3x I2C Bus Ports
- 1x SPI Bus
- 1x Chip Select Line
- 1x Data Ready Line
- 1x SPI Reset Line
- 2x CAN Ports
- 3x Power Input Ports
- ADC Power Input
- I2C Power Input
- DroneCAN/UAVCAN Power Input
- 2x AD Ports
- Analog Input (3.3V)
- Analog Input (6.6V - not supported by PX4)
- 1x Dedicated Debug Port
- FMU Debug
## Purchase Channels
Order from [S-Vehicle](https://svehicle.cn/).
## 무선 조종
A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).
기체와 조종자가 통신하기 위하여 송신기와 수신기를 바인딩하여야 합니다.
송신기와 수신기의 매뉴얼을 참고하십시오.
Spektrum/DSM receivers connect to the DSM/SBUS RC input.
PPM or SBUS receivers connect to the RC IN input port.
CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together.
## 시리얼 포트 매핑
| UART | 장치 | 포트 |
| ------ | ---------- | -------- |
| USART1 | /dev/ttyS0 | GPS |
| USART2 | /dev/ttyS1 | TELEM3 |
| USART3 | /dev/ttyS2 | 디버그 콘솔 |
| UART4 | /dev/ttyS3 | UART4 |
| UART5 | /dev/ttyS4 | TELEM2 |
| USART6 | /dev/ttyS5 | PX4IO/RC |
| UART7 | /dev/ttyS6 | TELEM1 |
| UART8 | /dev/ttyS7 | GPS2 |
## PWM Output
The E2-Plus flight controller supports up to 14 PWM outputs.
The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller.
The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs.
These are directly attached to the STM32H753 FMU controller .
The 14 PWM outputs are:
M1 - M8 are connected to the IOMCU
A1 - A6 are connected to the FMU
M1 - M8 support DShot and are in 3 groups:
- M1, M2 in group 1
- M3, M4 in group 2
- M5, M6, M7, M8 in group 3
The 6 FMU PWM outputs are in 2 groups:
A1 - A4 are in one group.
A5, A6 are in a 2nd group.
Channels within the same group need to use the same output rate.
If any channel in a group uses DShot then all channels in the group need to use DShot.
### Electrical data
- Voltage Ratings:
- Max input voltage: 5.7V
- USB Power Input: 4.75\~5.25V
- Servo Rail Input: 0\~9.9V
- Current Ratings:
- TELEM1 and GPS2 combined output current limiter: 1.5A
- All other port combined output current limiter: 1.5A
## Battery Monitoring
The board has connectors for 3 power monitors.
- POWER1 -- ADC
- POWER2 -- DroneCAN
- POWER3 -- I2C
The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled.
The default PDB included with the E2+ is analog and must be connected to `POWER1`.
## 펌웨어 빌드
To [build PX4](../dev_setup/building_px4.md) for this target, execute:
```sh
make svehicle_e2_default
```
## 디버그 포트
The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port.
| 핀 | 신호 | 전압 |
| ------------------------- | ------------------------------- | --------------------- |
| 1(red) | 5V+ | +5V |
| 2 (흑) | DEBUG TX(출력) | +3.3V |
| 3 (흑) | DEBUG TX(입력) | +3.3V |
| 4 (흑) | FMU_SWDIO | +3.3V |
| 5 (흑) | FMU_SWCLK | +3.3V |
| 6 (흑) | GND | GND |
For information about using this port see:
- [SWD Debug Port](../debug/swd_debug.md)
- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3).
- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670).
## 핀배열
![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png)
![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg)
![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png)
![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png)
## 지원 플랫폼 및 기체
Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos.
The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md).
+1
View File
@@ -187,6 +187,7 @@
- [Radiolink PIX6](flight_controller/radiolink_pix6.md)
- [Sky-Drones AIRLink](flight_controller/airlink.md)
- [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md)
- [SVehicle E2](flight_controller/svehicle_e2.md)
- [ThePeach FCC-K1](flight_controller/thepeach_k1.md)
- [ThePeach FCC-R1](flight_controller/thepeach_r1.md)
- [Калібрування рівня горизонту](flight_controller/autopilot_experimental.md)
+2 -3
View File
@@ -102,8 +102,7 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the
</div><div v-else-if="$frontmatter.frame === 'Plane'">
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
The progress is shown in the progress bar, next to the _Autotune_ button.
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
</div>
<div style="display: inline;" v-if="$frontmatter.frame === 'Multicopter'">
@@ -198,7 +197,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
</div>
<div v-else-if="$frontmatter.frame === 'Plane'">
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates.
If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration.
@@ -35,5 +35,6 @@ This category includes boards that are not fully compliant with the pixhawk stan
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md)
- [Sky-Drones AIRLink](../flight_controller/airlink.md)
- [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md)
- [Svehicle E2](../flight_controller/svehicle_e2.md)
- [ThePeach FCC-K1](../flight_controller/thepeach_k1.md)
- [ThePeach FCC-R1](../flight_controller/thepeach_r1.md)
+176
View File
@@ -0,0 +1,176 @@
# S-Vehicle E2
:::warning
PX4 не розробляє цей (або будь-який інший) автопілот.
:::
The _E2_ is an advanced autopilot manufactured by S-Vehicle<sup>&reg;</sup>.
The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications.
It brings you ultimate performance, stability, and reliability in every aspect.
![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png)
:::info
These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
:::
### Processors & Sensors
- FMU Processor: STM32H753IIK6
- 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM
- IO Processor: STM32F103
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- Сенсори на платі
- Акселератор/гіроскоп: BMI088
- Accel/Gyro: ICM-42688-P
- Accel/Gyro: ICM-20649
- Mag: RM3100
- Барометр: 2x ICP-20100
### Інтерфейси
- 14x PWM Servo Outputs
- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus
- 1x Analog/PWM RSSI Input
- 2x TELEM Ports (with full flow control)
- 1x UART4 Port
- 2x GPS Ports
- 1x Full GPS plus Safety Switch Port (GPS1)
- 1x Basic GPS Port (with I2C, GPS2)
- 1x USB Port (TYPE-C)
- 1x Ethernet Port
- Transformerless application
- 100Mbps
- 3x I2C Bus Ports
- 1x SPI Bus
- 1x Chip Select Line
- 1x Data Ready Line
- 1x SPI Reset Line
- 2x CAN Ports
- 3x Power Input Ports
- ADC Power Input
- I2C Power Input
- DroneCAN/UAVCAN Power Input
- 2x AD Ports
- Analog Input (3.3V)
- Analog Input (6.6V - not supported by PX4)
- 1x Dedicated Debug Port
- FMU Debug
## Purchase Channels
Order from [S-Vehicle](https://svehicle.cn/).
## Радіоуправління
A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).
Вам буде потрібно вибрати сумісний передавач/приймач та потім зв'язати їх, щоб вони взаємодіяли (прочитайте інструкції, що додаються до вашого конкретного передавача/приймача).
Spektrum/DSM receivers connect to the DSM/SBUS RC input.
PPM or SBUS receivers connect to the RC IN input port.
CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together.
## Налаштування послідовного порту
| UART | Пристрій | Порт |
| ------ | ---------- | ------------- |
| USART1 | /dev/ttyS0 | GPS |
| USART2 | /dev/ttyS1 | TELEM3 |
| USART3 | /dev/ttyS2 | Debug Console |
| UART4 | /dev/ttyS3 | UART4 |
| UART5 | /dev/ttyS4 | TELEM2 |
| USART6 | /dev/ttyS5 | PX4IO/RC |
| UART7 | /dev/ttyS6 | TELEM1 |
| UART8 | /dev/ttyS7 | GPS2 |
## PWM Output
The E2-Plus flight controller supports up to 14 PWM outputs.
The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller.
The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs.
These are directly attached to the STM32H753 FMU controller .
The 14 PWM outputs are:
M1 - M8 are connected to the IOMCU
A1 - A6 are connected to the FMU
M1 - M8 support DShot and are in 3 groups:
- M1, M2 in group 1
- M3, M4 in group 2
- M5, M6, M7, M8 in group 3
The 6 FMU PWM outputs are in 2 groups:
A1 - A4 are in one group.
A5, A6 are in a 2nd group.
Channels within the same group need to use the same output rate.
If any channel in a group uses DShot then all channels in the group need to use DShot.
### Електричні дані
- Номінальна напруга:
- Максимальна вхідна напруга: 5,7 В
- Вхід USB Power: 4.75~5.25V
- Вхід на серворейку: 0\~9.9В
- Номінальний струм:
- Комбінований обмежувач вихідного струму TELEM1 і GPS2: 1,5 А
- Комбінований обмежувач вихідного струму всіх інших портів: 1.5A
## Battery Monitoring
The board has connectors for 3 power monitors.
- POWER1 -- ADC
- POWER2 -- DroneCAN
- POWER3 -- I2C
The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled.
The default PDB included with the E2+ is analog and must be connected to `POWER1`.
## Збірка прошивки
To [build PX4](../dev_setup/building_px4.md) for this target, execute:
```sh
make svehicle_e2_default
```
## Відладочний порт
The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port.
| Pin | Сигнал | Вольтаж |
| -------------------------- | --------------------------------- | --------------------- |
| 1 (red) | 5V+ | +5V |
| 2 (blk) | DEBUG TX (OUT) | +3.3V |
| 3 (blk) | DEBUG RX (IN) | +3.3V |
| 4 (blk) | FMU_SWDIO | +3.3V |
| 5 (blk) | FMU_SWCLK | +3.3V |
| 6 (blk) | GND | GND |
Інформацію про використання цього порту див:
- [SWD Debug Port](../debug/swd_debug.md)
- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3).
- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670).
## Схема розташування виводів
![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png)
![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg)
![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png)
![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png)
## Підтримувані платформи / Конструкції
Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos.
The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md).
+1
View File
@@ -187,6 +187,7 @@
- [Radiolink PIX6](flight_controller/radiolink_pix6.md)
- [Sky-Drones AIRLink](flight_controller/airlink.md)
- [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md)
- [SVehicle E2](flight_controller/svehicle_e2.md)
- [ThePeach FCC-K1](flight_controller/thepeach_k1.md)
- [ThePeach FCC-R1](flight_controller/thepeach_r1.md)
- [Experimental Autopilots](flight_controller/autopilot_experimental.md)
+2 -3
View File
@@ -102,8 +102,7 @@ The test steps are:
</div><div v-else-if="$frontmatter.frame === 'Plane'">
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
The progress is shown in the progress bar, next to the _Autotune_ button.
4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
</div>
<div style="display: inline;" v-if="$frontmatter.frame === 'Multicopter'">
@@ -198,7 +197,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
</div>
<div v-else-if="$frontmatter.frame === 'Plane'">
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw.
By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates.
If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration.
@@ -35,5 +35,6 @@ The boards in this category are:
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md)
- [Sky-Drones AIRLink](../flight_controller/airlink.md)
- [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md)
- [Svehicle E2](../flight_controller/svehicle_e2.md)
- [ThePeach FCC-K1](../flight_controller/thepeach_k1.md)
- [ThePeach FCC-R1](../flight_controller/thepeach_r1.md)
+176
View File
@@ -0,0 +1,176 @@
# S-Vehicle E2
:::warning
PX4 does not manufacture this (or any) autopilot.
:::
The _E2_ is an advanced autopilot manufactured by S-Vehicle<sup>&reg;</sup>.
The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications.
It brings you ultimate performance, stability, and reliability in every aspect.
![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png)
:::info
These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
:::
### Processors & Sensors
- FMU Processor: STM32H753IIK6
- 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM
- IO Processor: STM32F103
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- On-board sensors
- Accel/Gyro: BMI088
- Accel/Gyro: ICM-42688-P
- Accel/Gyro: ICM-20649
- Mag: RM3100
- Barometer: 2x ICP-20100
### 接口
- 14x PWM Servo Outputs
- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus
- 1x Analog/PWM RSSI Input
- 2x TELEM Ports (with full flow control)
- 1x UART4 Port
- 2x GPS Ports
- 1x Full GPS plus Safety Switch Port (GPS1)
- 1x Basic GPS Port (with I2C, GPS2)
- 1x USB Port (TYPE-C)
- 1x Ethernet Port
- Transformerless application
- 100Mbps
- 3x I2C Bus Ports
- 1x SPI Bus
- 1x Chip Select Line
- 1x Data Ready Line
- 1x SPI Reset Line
- 2x CAN Ports
- 3x Power Input Ports
- ADC Power Input
- I2C Power Input
- DroneCAN/UAVCAN Power Input
- 2x AD Ports
- Analog Input (3.3V)
- Analog Input (6.6V - not supported by PX4)
- 1x Dedicated Debug Port
- FMU Debug
## Purchase Channels
Order from [S-Vehicle](https://svehicle.cn/).
## 遥控器
A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).
将 <em>HW\\u PM</em> 模块的6针连接器连接到飞控的<code>电源</code>接口。
Spektrum/DSM receivers connect to the DSM/SBUS RC input.
PPM or SBUS receivers connect to the RC IN input port.
CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together.
## 串口映射
| UART | 设备 | Port |
| ------ | ---------- | ------------- |
| USART1 | /dev/ttyS0 | GPS |
| USART2 | /dev/ttyS1 | TELEM3 |
| USART3 | /dev/ttyS2 | Debug Console |
| UART4 | /dev/ttyS3 | UART4 |
| UART5 | /dev/ttyS4 | TELEM2 |
| USART6 | /dev/ttyS5 | PX4IO/RC |
| UART7 | /dev/ttyS6 | TELEM1 |
| UART8 | /dev/ttyS7 | GPS2 |
## PWM Output
The E2-Plus flight controller supports up to 14 PWM outputs.
The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller.
The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs.
These are directly attached to the STM32H753 FMU controller .
The 14 PWM outputs are:
M1 - M8 are connected to the IOMCU
A1 - A6 are connected to the FMU
M1 - M8 support DShot and are in 3 groups:
- M1, M2 in group 1
- M3, M4 in group 2
- M5, M6, M7, M8 in group 3
The 6 FMU PWM outputs are in 2 groups:
A1 - A4 are in one group.
A5, A6 are in a 2nd group.
Channels within the same group need to use the same output rate.
If any channel in a group uses DShot then all channels in the group need to use DShot.
### Electrical data
- Voltage Ratings:
- Max input voltage: 5.7V
- USB Power Input: 4.75\~5.25V
- Servo Rail Input: 0\~9.9V
- Current Ratings:
- TELEM1 and GPS2 combined output current limiter: 1.5A
- All other port combined output current limiter: 1.5A
## Battery Monitoring
The board has connectors for 3 power monitors.
- POWER1 -- ADC
- POWER2 -- DroneCAN
- POWER3 -- I2C
The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled.
The default PDB included with the E2+ is analog and must be connected to `POWER1`.
## 编译固件
To [build PX4](../dev_setup/building_px4.md) for this target, execute:
```sh
make svehicle_e2_default
```
## 调试接口
The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port.
| 针脚 | 信号 | 电压 |
| ---- | --------------------------------- | --------------------- |
| 1(红) | 5V+ | +5V |
| 2 | DEBUG TX (OUT) | +3.3V |
| 3 | DEBUG RX (IN) | +3.3V |
| 4(黑) | FMU_SWDIO | +3.3V |
| 6 | FMU_SWCLK | +3.3V |
| 6 | GND | GND |
For information about using this port see:
- [SWD Debug Port](../debug/swd_debug.md)
- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3).
- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670).
## 针脚定义
![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png)
![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg)
![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png)
![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png)
## 支持的平台/机身
Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos.
The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md).
+10 -8
View File
@@ -1,10 +1,12 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample
# Differential-pressure (airspeed) sensor
#
# This is populated by airspeed sensor drivers and used by the sensor module to calculate airspeed.
# The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `SensorBaro` instance).
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 timestamp # [us] Time of publication (since system start)
uint64 timestamp_sample # [us] Time of raw data capture
float32 differential_pressure_pa # differential pressure reading in Pascals (may be negative)
float32 temperature # Temperature provided by sensor in degrees Celsius, NAN if unknown
uint32 error_count # Number of errors detected by driver
uint32 device_id # [-] Unique device ID for the sensor that does not change between power cycles
float32 differential_pressure_pa # [Pa] Differential pressure reading (may be negative)
float32 temperature # [degC] [@invalid NaN if unknown] Temperature
uint32 error_count # [-] Number of errors detected by driver
+10 -8
View File
@@ -1,12 +1,14 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample
# Barometer sensor
#
# This is populated by barometer drivers and used by the EKF2 estimator.
# The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `DifferentialPressure` instance).
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 timestamp # [us] Time of publication (since system start)
uint64 timestamp_sample # [us] Time of raw data capture
float32 pressure # static pressure measurement in Pascals
float32 temperature # temperature in degrees Celsius
uint32 error_count
uint32 device_id # [-] Unique device ID for the sensor that does not change between power cycles
float32 pressure # [Pa] Static pressure measurement
float32 temperature # [degC] Temperature.
uint32 error_count # [-] Number of errors detected by driver.
uint8 ORB_QUEUE_LENGTH = 4
@@ -266,21 +266,28 @@ void FlightTaskAuto::_prepareLandSetpoints()
Vector2f sticks_ne = sticks_xy;
Sticks::rotateIntoHeadingFrameXY(sticks_ne, _yaw, _land_heading);
const float distance_to_circle = math::trajectory::getMaxDistanceToCircle(_position.xy(), _initial_land_position.xy(),
_param_mpc_land_radius.get(), sticks_ne);
float max_speed;
float max_speed = INFINITY;
if (PX4_ISFINITE(distance_to_circle)) {
max_speed = math::trajectory::computeMaxSpeedFromDistance(_stick_acceleration_xy.getMaxJerk(),
_stick_acceleration_xy.getMaxAcceleration(), distance_to_circle, 0.f);
if (_param_mpc_land_radius.get() > FLT_EPSILON) {
if (max_speed < 0.5f) {
// = NaN if we are outside of the allowed circle and nudging does not point back towards it
const float distance_to_circle = math::trajectory::getMaxDistanceToCircle(_position.xy(), _initial_land_position.xy(),
_param_mpc_land_radius.get(), sticks_ne);
if (PX4_ISFINITE(distance_to_circle)) {
// We are inside of the allowed circle. Limit speed so we can always brake in time to not leave the circle.
max_speed = math::trajectory::computeMaxSpeedFromDistance(_stick_acceleration_xy.getMaxJerk(),
_stick_acceleration_xy.getMaxAcceleration(), distance_to_circle, 0.f);
if (max_speed < 0.5f) {
sticks_xy.setZero();
}
} else {
max_speed = 0.f;
sticks_xy.setZero();
}
} else {
max_speed = 0.f;
sticks_xy.setZero();
}
_stick_acceleration_xy.setVelocityConstraint(max_speed);
@@ -345,7 +345,7 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now)
}
const float abs_roll_rate = fabsf(_angular_velocity(0));
const float target = min(kTargetRollRate, math::radians(_param_fw_r_rmax.get()));
const float target = 0.75f * math::radians(_param_fw_r_rmax.get());
updateAmplitudeDetectionState(now, abs_roll_rate, target);
@@ -396,7 +396,7 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now)
const float abs_pitch_rate = fabsf(_angular_velocity(1));
const float max_pitch_rate = min(_param_fw_p_rmax_pos.get(), _param_fw_p_rmax_neg.get());
const float target = min(kTargetPitchRate, math::radians(max_pitch_rate));
const float target = 0.75f * math::radians(max_pitch_rate);
updateAmplitudeDetectionState(now, abs_pitch_rate, target);
@@ -444,7 +444,7 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now)
}
const float abs_yaw_rate = fabsf(_angular_velocity(2));
const float target = min(kTargetYawRate, math::radians(_param_fw_y_rmax.get()));
const float target = 0.75f * math::radians(_param_fw_y_rmax.get());
updateAmplitudeDetectionState(now, abs_yaw_rate, target);
@@ -548,16 +548,47 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now)
}
// In case of convergence timeout
// the identification sequence is aborted immediately
// the identification sequence is aborted and the FSM moves on to the next axis
if (_state != state::wait_for_disarm && _state != state::idle && _state != state::fail && _state != state::complete) {
if (now - _state_start_time > 20_s
|| (_param_fw_at_man_aux.get() && !_aux_switch_en)
|| _start_flight_mode != _nav_state) {
orb_advert_t mavlink_log_pub = nullptr;
const bool timeout = (now - _state_start_time) > 30_s;
const bool mode_changed = (_start_flight_mode != _nav_state);
const bool aux_switched_off = (_param_fw_at_man_aux.get() && !_aux_switch_en);
orb_advert_t mavlink_log_pub = nullptr;
if (mode_changed || aux_switched_off) {
// Abort
mavlink_log_critical(&mavlink_log_pub, "Autotune aborted before finishing");
_state = state::fail;
_state_start_time = now;
} else if (timeout) {
// Skip to next axis
mavlink_log_critical(&mavlink_log_pub, "Autotune axis timeout, skipping to next axis");
switch (_state) {
case state::roll_amp_detection:
case state::roll:
_state = state::roll_pause; // proceed to pitch
break;
case state::pitch_amp_detection:
case state::pitch:
_state = state::pitch_pause; // proceed to yaw
break;
case state::yaw_amp_detection:
case state::yaw:
_state = state::yaw_pause; // proceed to verification
break;
default:
_state = state::fail; // safety fallback
break;
}
}
_state_start_time = now;
}
}
@@ -172,16 +172,6 @@ private:
static constexpr float kSignalAmpMax{5.0f};
static constexpr float kSignalAmpStep{0.1f};
// Target maximum angular rates for the system identification signal.
// ~45 deg/s for roll, ~30 deg/s for pitch and yaw. These values are:
// - High enough to provide good signal-to-noise ratio for identification.
// - Low enough to keep pitch and yaw responses within the linear range
// for most vehicles.
static constexpr float kTargetRollRate{0.8f};
static constexpr float kTargetPitchRate{0.5f};
static constexpr float kTargetYawRate{0.5f};
matrix::Vector3f _angular_velocity{};
bool _armed{false};
@@ -253,6 +243,6 @@ private:
(ParamInt<px4::params::FW_AT_SYSID_TYPE>) _param_fw_sysid_signal_type
)
static constexpr float _publishing_dt_s = 100e-3f;
static constexpr hrt_abstime _publishing_dt_hrt = 100_ms;
static constexpr float _publishing_dt_s = 20e-3f;
static constexpr hrt_abstime _publishing_dt_hrt = 20_ms;
};
@@ -53,13 +53,17 @@ PARAM_DEFINE_INT32(MPC_LAND_RC_HELP, 0);
/**
* User assisted landing radius
*
* When nudging is enabled (see MPC_LAND_RC_HELP), this controls
* the maximum allowed horizontal displacement from the original landing point.
* When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum
* allowed horizontal displacement from the original landing point.
* - If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it.
* - If outside of the radius, only allow nudging inputs that move the vehicle back towards it.
*
* Set it to -1 for infinite radius.
*
* @unit m
* @min 0
* @min -1
* @decimal 0
* @increment 1
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_LAND_RADIUS, 1000.f);
PARAM_DEFINE_FLOAT(MPC_LAND_RADIUS, -1.0f);
+21 -4
View File
@@ -57,7 +57,7 @@ void RtlMissionFast::on_inactive()
MissionBase::on_inactive();
_vehicle_status_sub.update();
_mission_index_prior_rtl = _vehicle_status_sub.get().nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION ?
_mission.current_seq : -1;
_mission.current_seq : INT32_C(-1);
}
void RtlMissionFast::on_activation()
@@ -65,13 +65,30 @@ void RtlMissionFast::on_activation()
_home_pos_sub.update();
// set mission item to closest item if not already in mission
if (_mission_index_prior_rtl < 0) {
if (_mission_index_prior_rtl < INT32_C(0)) {
_is_current_planned_mission_item_valid = setMissionToClosestItem(_global_pos_sub.get().lat, _global_pos_sub.get().lon,
_global_pos_sub.get().alt, _home_pos_sub.get().alt, _vehicle_status_sub.get()) == PX4_OK;
} else {
setMissionIndex(_mission_index_prior_rtl);
_is_current_planned_mission_item_valid = isMissionValid();
int32_t next_mission_item_index;
size_t num_found_items{0U};
getNextPositionItems(_mission_index_prior_rtl, &next_mission_item_index, num_found_items, UINT8_C(1));
if (num_found_items > 0U) {
setMissionIndex(next_mission_item_index);
_is_current_planned_mission_item_valid = isMissionValid();
} else {
// No more position items left. Set it to the land item if it exists
if (_mission.land_index > 0) {
setMissionIndex(_mission.land_index);
_is_current_planned_mission_item_valid = isMissionValid();
} else {
// Nothing we can do, set the validity to false to trigger end of mission reaction
_is_current_planned_mission_item_valid = false;
}
}
}
if (_land_detected_sub.get().landed) {
+1 -1
View File
@@ -64,7 +64,7 @@ private:
bool setNextMissionItem() override;
void setActiveMissionItems() override;
int _mission_index_prior_rtl{-1};
int32_t _mission_index_prior_rtl{INT32_C(-1)};
uORB::SubscriptionData<home_position_s> _home_pos_sub{ORB_ID(home_position)}; /**< home position subscription */
};
@@ -57,7 +57,7 @@ void RtlMissionFastReverse::on_inactive()
MissionBase::on_inactive();
_vehicle_status_sub.update();
_mission_index_prior_rtl = _vehicle_status_sub.get().nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION ?
_mission.current_seq : -1;
_mission.current_seq : INT32_C(-1);
}
void RtlMissionFastReverse::on_inactivation()
@@ -71,13 +71,24 @@ void RtlMissionFastReverse::on_activation()
_home_pos_sub.update();
// set mission item to closest item if not already in mission. If we are in mission, set to the previous item.
if (_mission_index_prior_rtl < 0) {
if (_mission_index_prior_rtl < INT32_C(0)) {
_is_current_planned_mission_item_valid = setMissionToClosestItem(_global_pos_sub.get().lat, _global_pos_sub.get().lon,
_global_pos_sub.get().alt, _home_pos_sub.get().alt, _vehicle_status_sub.get()) == PX4_OK;
} else {
setMissionIndex(math::max(_mission_index_prior_rtl - 1, 0));
_is_current_planned_mission_item_valid = isMissionValid();
int32_t previous_mission_item_index;
size_t num_found_items{0U};
getPreviousPositionItems(math::max(_mission_index_prior_rtl - INT32_C(1), INT32_C(0)), &previous_mission_item_index,
num_found_items, UINT8_C(1));
if (num_found_items > 0U) {
setMissionIndex(previous_mission_item_index);
_is_current_planned_mission_item_valid = isMissionValid();
} else {
// No prior position items, so try to go to the first one.
_is_current_planned_mission_item_valid = (goToNextPositionItem(false) == PX4_OK);
}
}
if (_land_detected_sub.get().landed) {
@@ -69,7 +69,7 @@ private:
void setActiveMissionItems() override;
void handleLanding(WorkItemType &new_work_item_type);
int _mission_index_prior_rtl{-1};
int32_t _mission_index_prior_rtl{INT32_C(-1)};
bool _in_landing_phase{false};