Compare commits

..

19 Commits

Author SHA1 Message Date
Daniel Agar
a1fa3cc699
WIP: common board init 2022-05-04 18:31:40 -04:00
Daniel Agar
2cc25f0763
boards: px4_fmu-v5/v5x init all I2C pins 2022-05-04 14:02:23 -04:00
Matthias Grob
46fdc28cf8 MulticopterPositionControl: fix typo "descen{d/t}" 2022-05-04 02:22:18 -07:00
Daniel Agar
7f1bb556e9 Update src/modules/mc_pos_control/MulticopterPositionControl.cpp
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2022-05-04 02:22:18 -07:00
Matthias Grob
3fb4889ab9 MultcopterPositionControl: fix executing a zero setpoint for 200ms
This is a combination of the originally introduced delay:
06c10f61c1401d448979c65c2250afde42b99522
then the emergency failsafe being changed to not just land,
position control being rescheduled to not overwrite every setpoint in:
e502214429576ce68ac3fee9d2db19112f4604b9
and it being fixed by overwriting the setpoint but not removing
the long obsolete hystersis here:
114e85d260d4acb157e191fd8cfc1f58c9c73e4e
2022-05-04 02:22:18 -07:00
Matthias Grob
cb484c5ac7 PositionControl: publish NAN jerk
because the controller does not read or write jerk
2022-05-04 02:22:18 -07:00
Matthias Grob
5055fec796 MulticoperPositionControl: explicitly overwrite setpoint timestamp when setpoint is reset 2022-05-04 02:22:18 -07:00
Matthias Grob
424fd8b304 MulticoperPositionControl: remove time_stamp_now alias for timestamp_sample of the local position
to make it explicit what is used is not a fresh hrt_absolute_time() call
by this module.
2022-05-04 02:22:18 -07:00
Matthias Grob
8180f931de MulticopterPositionControl: rename local_pos -> vehicle_local_position 2022-05-04 02:22:18 -07:00
Matthias Grob
4ffe796b4d MulticopterPositionControl: clarify previous position control naming 2022-05-04 02:22:18 -07:00
Daniel Agar
ad6592f669 mc_pos_control: require current trajectory setpoint to run controller 2022-05-04 02:22:18 -07:00
Silvan Fuhrer
138772386f FW Position control: explicitly set spoiler/flaps in every control mode
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-03 15:11:21 +02:00
Silvan Fuhrer
089673ff35 only allow positive spoiler and flap controls
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-03 15:11:21 +02:00
Silvan Fuhrer
64ff31aa08 VTOL: add flap and spoiler support
- including slew rate limiting
- adds option to set spoiler setting during the Land phase (hover)

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-03 15:11:21 +02:00
Silvan Fuhrer
4b8f93de5c FW: rework spoiler/flap control logic
- remove separate flaperon controls input to mixer instead enable spoiler support
- add slew rate limiting on both flap and spoiler controls
- add spoiler configuration for Landing and Descend
- add trimming from spoiler deflection
- FW Attitude control: remove FW_FLAPS_SCL param -->
    The flap settings for takeoff and landing are now specified relative to full range.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-03 15:11:21 +02:00
Silvan Fuhrer
21a2892f47 use actuator_controls[8] for collective tilt for tiltrotor VTOL, instead of [4]
[4] is reserved for Flaps, so also having the tilt on it was preventing us from
using flaps on tiltrotors, and other ripple effects.
By using [8] the tilt is separated from all other channels - it requires to increase the size of
actuator_controls by 1 to 9.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-03 15:11:21 +02:00
Peter van der Perk
7e6aa28106 Added LTO targets for CI 2022-05-02 10:07:54 -04:00
Peter van der Perk
108c98a691 Added experimental LTO kconfig option 2022-05-02 10:07:54 -04:00
Beat Küng
8da02e2233 dshot: avoid using pwm failsafe params when dynamic mixing is enabled 2022-05-02 07:16:23 +02:00
93 changed files with 921 additions and 834 deletions

View File

@ -92,6 +92,7 @@ pipeline {
"px4_fmu-v2_fixedwing",
"px4_fmu-v2_multicopter",
"px4_fmu-v2_rover",
"px4_fmu-v2_lto",
"px4_fmu-v3_default",
"px4_fmu-v4_default",
"px4_fmu-v4pro_default",
@ -101,6 +102,7 @@ pipeline {
"px4_fmu-v5_stackcheck",
"px4_fmu-v5_uavcanv0periph",
"px4_fmu-v5_uavcanv1",
"px4_fmu-v5_lto",
"px4_fmu-v5x_default",
"px4_fmu-v6u_default",
"px4_fmu-v6x_default",

View File

@ -99,7 +99,7 @@
#
#=============================================================================
cmake_minimum_required(VERSION 3.2 FATAL_ERROR)
cmake_minimum_required(VERSION 3.9 FATAL_ERROR)
set(PX4_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}" CACHE FILEPATH "PX4 source directory" FORCE)
set(PX4_BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}" CACHE FILEPATH "PX4 binary directory" FORCE)
@ -234,6 +234,14 @@ message(STATUS "cmake build type: ${CMAKE_BUILD_TYPE}")
#
project(px4 CXX C ASM)
# Check if LTO option and check if toolchain supports it
if(LTO)
include(CheckIPOSupported)
check_ipo_supported()
message(AUTHOR_WARNING "LTO enabled: LTO is highly experimental and should not be used in production")
set(CMAKE_INTERPROCEDURAL_OPTIMIZATION TRUE)
endif()
set(package-contact "px4users@googlegroups.com")
set(CMAKE_CXX_STANDARD 14)

View File

@ -51,6 +51,13 @@ menu "Toolchain"
string "Architecture"
default ""
config BOARD_LTO
bool "(EXPERIMENTAL) Link Time Optimization (LTO)"
default n
help
Enables LTO flag in linker
Note: Highly EXPERIMENTAL, furthermore make sure you're using a modern compiler GCC 9 or later
config BOARD_FULL_OPTIMIZATION
bool "Full optmization (O3)"
default n

View File

@ -25,6 +25,8 @@ 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_SPOILERS_LND 0.8
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_THR_CRUISE 0.25

View File

@ -21,14 +21,16 @@ O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
# mixer for the left aileron
M: 1
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
# mixer for the right aileron
M: 1
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
# mixer for the elevator
M: 1

View File

@ -8,22 +8,22 @@ R: 4x
# tilt servo motor 1
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# tilt servo motor 2
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# tilt servo motor 3
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# tilt servo motor 4
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# mixer for the left aileron
M: 1

View File

@ -10,7 +10,7 @@ to output 4 and the wheel to output 5.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@ -20,11 +20,11 @@ endpoints to suit.
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
Elevator mixer
------------

View File

@ -11,7 +11,7 @@ to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@ -21,11 +21,11 @@ endpoints to suit.
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
V-tail mixers
-------------

View File

@ -9,20 +9,20 @@ output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
(roll), 1 (pitch), 2 (yaw), 3 (thrust) 4 (flaps), 5 (spoiler).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up mechanically reversed.
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
V-tail mixers
-------------

View File

@ -10,7 +10,7 @@ Tilt mechanism servo mixer
M: 1
S: 1 4 10000 10000 0 -10000 10000
S: 1 8 10000 10000 0 -10000 10000

View File

@ -6,7 +6,7 @@
Tilt mechanism servo mixer
---------------------------
M: 1
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
Elevon mixers
-------------

View File

@ -5,14 +5,14 @@ Aileron/v-tail/throttle VTOL mixer for PX4FMU
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, v-tail (rudder, elevator) and throttle using PX4FMU.
The configuration assumes the aileron servos are connected to PX4FMU
The configuration assumes the aileron servos are connected to PX4FMU
AUX servo output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@ -22,11 +22,11 @@ endpoints to suit.
M: 2
S: 1 0 -10000 -10000 0 -10000 10000
S: 1 6 10000 10000 0 -10000 10000
S: 1 5 10000 10000 0 -10000 10000
M: 2
S: 1 0 -10000 -10000 0 -10000 10000
S: 1 6 -10000 -10000 0 -10000 10000
S: 1 5 -10000 -10000 0 -10000 10000
V-tail mixers

View File

@ -6,19 +6,19 @@
---------------------------
# front left up:2000 down:1000
M: 1
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
# front right up:1000 down:2000
M: 1
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# rear left up:2000 down:1000
M: 1
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
# rear right up:1000 down:2000
M: 1
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# Aileron mixer

View File

@ -10,12 +10,12 @@ Tilt mechanism servo mixer
---------------------------
#RIGHT up:2000 down:1000
M: 2
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
Elevon mixers

View File

@ -10,7 +10,7 @@ to output 4 and the wheel to output 5.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@ -21,12 +21,12 @@ endpoints to suit.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
Elevator mixer
------------

View File

@ -9,9 +9,9 @@ output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 5 (spoiler).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@ -22,12 +22,12 @@ endpoints to suit.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
V-tail mixers
-------------

View File

@ -10,13 +10,13 @@ Tilt mechanism servo mixer
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 -20000 9000 -10000 10000
S: 1 8 0 -20000 9000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
Elevon mixers

View File

@ -3,14 +3,14 @@ Aileron/v-tail/throttle VTOL mixer for PX4FMU
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, v-tail (rudder, elevator) and throttle using PX4FMU.
The configuration assumes the aileron servos are connected to PX4FMU
The configuration assumes the aileron servos are connected to PX4FMU
AUX servo output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 5 (spoiler).
Aileron mixer (roll + flaperon)
Aileron mixer (roll + spoiler)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@ -21,12 +21,12 @@ endpoints to suit.
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 6 10000 10000 0 -10000 10000
S: 1 5 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 6 -10000 -10000 0 -10000 10000
S: 1 5 -10000 -10000 0 -10000 10000
V-tail mixers

View File

@ -10,13 +10,13 @@ Tilt mechanism servo mixer
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
Elevon mixers

View File

@ -113,7 +113,7 @@
#define RC_SERIAL_PORT "/dev/ttyS0"
// #define GPIO_RSSI_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10)
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true);
#define GPIO_FRSKY_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12)

View File

@ -46,6 +46,7 @@ add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
arch_init
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio

View File

@ -149,6 +149,7 @@
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* power on/off */
#define MS_PWR_BUTTON_DOWN 750
@ -189,7 +190,6 @@
GPIO_HW_VER_DRIVE, \
GPIO_HEATER_OUTPUT, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_OTGFS_VBUS \
}
#define BOARD_ENABLE_CONSOLE_BUFFER

View File

@ -149,27 +149,6 @@ __EXPORT void board_on_reset(int status)
{
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
/* Hold power state */
board_pwr_init(0);
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
}
/****************************************************************************
* Name: board_app_initialize
*

View File

@ -160,6 +160,7 @@
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/**
* GPIO PPM_IN on PB4 T3C1
@ -168,6 +169,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/* RSSI_IN */

View File

@ -160,6 +160,7 @@
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/**
* GPIO PPM_IN on PB4 T3C1
@ -168,6 +169,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/* RSSI_IN */

View File

@ -42,6 +42,7 @@ add_library(drivers_board
target_link_libraries(drivers_board
PRIVATE
arch_init
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio

View File

@ -149,10 +149,6 @@
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN2_TX, \
GPIO_CAN2_RX, \
GPIO_PWM_VOLT_SEL, \
GPIO_nVDD_BRICK1_VALID, \
GPIO_nVDD_BRICK1_VALID, \

View File

@ -107,29 +107,6 @@ __EXPORT void board_on_reset(int status)
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
/* Reset PWM first thing */
board_on_reset(-1);
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
* Name: board_app_initialize
*

View File

@ -37,13 +37,21 @@
* Board-specific USB functions.
*/
#include "board_config.h"
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <stm32_otg.h>
#include <debug.h>
#include <syslog.h>
#include <arm_arch.h>
#include <chip.h>
#include <stm32_gpio.h>
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Name: stm32_usbsuspend
@ -55,6 +63,7 @@
* while the USB is suspended.
*
************************************************************************************/
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);

View File

@ -141,6 +141,12 @@
* SPEKTRUM_RX (it's TX or RX in Bind) on PA10 UART1
* The FMU can drive GPIO PPM_IN as an output
*/
// TODO?
//#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6)
//#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
//#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
//#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* This board provides a DMA pool and APIs */

View File

@ -42,6 +42,7 @@ add_library(drivers_board
target_link_libraries(drivers_board
PRIVATE
arch_init
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio

View File

@ -132,37 +132,11 @@
#define BOARD_NUM_IO_TIMERS 4
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -37,10 +37,6 @@
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
@ -57,37 +53,6 @@
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32F7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*

View File

@ -281,7 +281,9 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
@ -325,6 +327,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -46,6 +46,7 @@ add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_init
arch_spi
arch_board_hw_info
drivers__led # drv_led_start

View File

@ -205,6 +205,7 @@
#define SPEKTRUM_RX_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(SPEKTRUM_RX_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(SPEKTRUM_RX_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */
@ -245,8 +246,6 @@
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_HW_VER_REV_DRIVE, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_A71CH_nRST, \
@ -298,8 +297,6 @@ int stm32_sdio_initialize(void);
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>

View File

@ -146,64 +146,6 @@ __EXPORT void board_on_reset(int status)
}
}
/****************************************************************************
* Name: board_app_finalinitialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command
* BOARDIOC_FINALINIT.
*
* Input Parameters:
* arg - The argument has no meaning.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
#ifdef CONFIG_BOARDCTL_FINALINIT
int board_app_finalinitialize(uintptr_t arg)
{
return 0;
}
#endif
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
}
/****************************************************************************
* Name: board_app_initialize
@ -234,12 +176,10 @@ stm32_boardinitialize(void)
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Power on Interfaces */
VDD_3V3_SD_CARD_EN(true);
VDD_3V3_SPEKTRUM_POWER_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
if (OK == board_determine_hw_info()) {
@ -250,8 +190,9 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
/* configure the DMA allocator */
stm32_spiinitialize();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}

View File

@ -37,10 +37,6 @@
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
@ -57,37 +53,6 @@
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4FMU board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32F7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*

View File

@ -264,6 +264,7 @@
#define SPEKTRUM_RX_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(SPEKTRUM_RX_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(SPEKTRUM_RX_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -135,6 +135,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -158,6 +158,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -157,6 +157,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -134,6 +134,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -134,6 +134,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -134,6 +134,7 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -312,6 +312,7 @@
#define GPIO_PPM_IN /* GPIO_B1_06 GPT1_CAPTURE2 */ (GPIO_GPT1_CAPTURE2_2 | GENERAL_INPUT_IOMUX)
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* PWM input driver. Use FMU AUX5 pins attached to GPIO_EMC_33 GPIO3_IO19 FLEXPWM3_PWMA2 */

View File

@ -0,0 +1 @@
CONFIG_BOARD_LTO=y

View File

@ -128,7 +128,7 @@
#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
/* For R12, this signal is active high. */
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true)
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
@ -158,6 +158,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/**

View File

@ -0,0 +1 @@
CONFIG_BOARD_LTO=y

View File

@ -381,12 +381,6 @@
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13 */
/* I2C
*
* Each I2C is associated with a U[S]ART
* hence the naming I2C2_SDA_UART4 in FMU USAGE spreadsheet
*
*
* I2C3 is not pined out on FMUv5 on 144 pin packages
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
@ -397,27 +391,15 @@
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8] */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0)
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN7)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15)
/* SDMMC1
*
* VDD 3.3

View File

@ -52,6 +52,7 @@ add_dependencies(drivers_board nuttx_context)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
arch_init
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio

View File

@ -274,6 +274,7 @@ static inline bool board_get_external_lockout_state(void)
#define GPIO_nVDD_5V_HIPOWER_EN /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12)
#define GPIO_nVDD_5V_HIPOWER_OC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13)
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
#define GPIO_VDD_3V3_SPEKTRUM_PASSIVE /* PE4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN4)
#define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5)
#define GPIO_VDD_5V_WIFI_EN /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5)
#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7)
@ -313,7 +314,9 @@ static inline bool board_get_external_lockout_state(void)
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
@ -346,6 +349,7 @@ static inline bool board_get_external_lockout_state(void)
/* Power switch controls ******************************************************/
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
#define SPEKTRUM_POWER_PASSIVE() px4_arch_configgpio(GPIO_VDD_3V3_SPEKTRUM_PASSIVE)
#define SPEKTRUM_POWER_CONFIG() px4_arch_configgpio(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
/*
@ -359,6 +363,7 @@ static inline bool board_get_external_lockout_state(void)
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */
@ -429,15 +434,6 @@ static inline bool board_get_external_lockout_state(void)
PX4_ADC_GPIO, \
GPIO_HW_REV_DRIVE, \
GPIO_HW_VER_DRIVE, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN2_TX, \
GPIO_CAN2_RX, \
GPIO_CAN3_TX, \
GPIO_CAN3_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_CAN2_SILENT_S1, \
GPIO_CAN3_SILENT_S2, \
GPIO_HEATER_OUTPUT, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
@ -454,7 +450,7 @@ static inline bool board_get_external_lockout_state(void)
GPIO_RSSI_IN_INIT, \
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_nARMED_INIT \
GPIO_nARMED_INIT, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
@ -498,8 +494,6 @@ int stm32_sdio_initialize(void);
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>

View File

@ -148,37 +148,6 @@ __EXPORT void board_on_reset(int status)
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure USB interfaces */
stm32_usbinitialize();
}
/****************************************************************************
* Name: board_app_initialize
*
@ -212,6 +181,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
board_control_spi_sensors_power(true, 0xffff);
#ifdef SPEKTRUM_POWER_PASSIVE
// Turn power controls to passive
SPEKTRUM_POWER_PASSIVE();
#endif
VDD_5V_RC_EN(true);
VDD_5V_WIFI_EN(true);

View File

@ -37,10 +37,6 @@
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
@ -57,37 +53,6 @@
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4FMU board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32F7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*

View File

@ -394,27 +394,15 @@
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0)
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN7)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15)
/* SDMMC2
*
* VDD 3.3

View File

@ -48,6 +48,7 @@ add_dependencies(drivers_board platform_gpio_mcp23009)
target_link_libraries(drivers_board
PRIVATE
arch_init
arch_io_pins
arch_spi
arch_board_hw_info

View File

@ -250,7 +250,7 @@
/* ETHERNET GPIO */
#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15)
#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN15)
/* NFC GPIO */
@ -292,7 +292,9 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 5
@ -332,6 +334,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */
@ -396,10 +399,6 @@
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_HW_VER_REV_DRIVE, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN2_TX, \
GPIO_CAN2_RX, \
GPIO_HEATER_OUTPUT, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
@ -420,7 +419,7 @@
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_PG6, \
GPIO_nARMED_INIT \
GPIO_nARMED_INIT, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
@ -431,47 +430,13 @@
#define PX4_I2C_BUS_MTD 4,5
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -151,37 +151,6 @@ __EXPORT void board_on_reset(int status)
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
extern "C" __EXPORT void
stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure USB interfaces */
stm32_usbinitialize();
VDD_3V3_ETH_POWER_EN(true);
}
/****************************************************************************
* Name: board_app_initialize

View File

@ -32,15 +32,11 @@
****************************************************************************/
/**
* @file px4fmu_usb.c
* @file usb.c
*
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
@ -57,37 +53,6 @@
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4FMU board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32F7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*

View File

@ -258,7 +258,10 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
#define RC_SERIAL_SWAP_RXTX
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 1
@ -299,6 +302,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -316,7 +316,9 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 1
@ -357,6 +359,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -253,7 +253,9 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 5
@ -291,6 +293,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -126,7 +126,7 @@
#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
/* For,this signal is active high. */
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true)
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
@ -157,6 +157,7 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
/**

View File

@ -11,6 +11,7 @@ uint8 INDEX_AIRBRAKES = 6
uint8 INDEX_LANDING_GEAR = 7
uint8 INDEX_GIMBAL_SHUTTER = 3
uint8 INDEX_CAMERA_ZOOM = 4
uint8 INDEX_COLLECTIVE_TILT = 8
uint8 GROUP_INDEX_ATTITUDE = 0
uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1
@ -19,7 +20,7 @@ uint8 GROUP_INDEX_MANUAL_PASSTHROUGH = 3
uint8 GROUP_INDEX_PAYLOAD = 6
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
float32[8] control
float32[9] control
# TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3
# TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc

View File

@ -24,4 +24,9 @@ uint8 FLAPS_OFF = 0 # no flaps
uint8 FLAPS_LAND = 1 # landing config flaps
uint8 FLAPS_TAKEOFF = 2 # take-off config flaps
uint8 apply_spoilers # spoiler config specifier
uint8 SPOILERS_OFF = 0 # no spoilers
uint8 SPOILERS_LAND = 1 # landing config spoiler
uint8 SPOILERS_DESCEND = 2 # descend config spoiler
# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint

View File

@ -411,6 +411,79 @@ typedef uint8_t px4_guid_t[PX4_GUID_BYTE_LENGTH];
************************************************************************************/
__BEGIN_DECLS
/************************************************************************************
* Name: board_rc_singlewire
*
* Description:
* A board may define RC_SERIAL_SINGLEWIRE, so that RC_SERIAL_PORT is configured
* as singlewire UART.
*
* Input Parameters:
* device: serial device, e.g. "/dev/ttyS0"
*
* Returned Value:
* true singlewire should be enabled.
* false if not.
*
************************************************************************************/
#if defined(RC_SERIAL_SINGLEWIRE)
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
#else
static inline bool board_rc_singlewire(const char *device) { return false; }
#endif
/************************************************************************************
* Name: board_rc_swap_rxtx
*
* Description:
* A board may define RC_SERIAL_SWAP_RXTX, so that RC_SERIAL_PORT is configured
* as UART with RX/TX swapped.
*
* Input Parameters:
* device: serial device, e.g. "/dev/ttyS0"
*
* Returned Value:
* true RX/RX should be swapped.
* false if not.
*
************************************************************************************/
#if defined(RC_SERIAL_SWAP_RXTX)
static inline bool board_rc_swap_rxtx(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
#else
static inline bool board_rc_swap_rxtx(const char *device) { return false; }
#endif
/************************************************************************************
* Name: board_rc_invert_input
*
* Description:
* All boards may optionally define RC_INVERT_INPUT(bool invert) that is
* used to invert the RC_SERIAL_PORT RC port (e.g. to toggle an external XOR via
* GPIO).
*
* Input Parameters:
* invert_on - A positive logic value, that when true (on) will set the HW in
* inverted NRZ mode where a MARK will be 0 and SPACE will be a 1.
*
* Returned Value:
* true the UART inversion got set.
*
************************************************************************************/
#ifdef RC_INVERT_INPUT
static inline bool board_rc_invert_input(const char *device, bool invert)
{
if (strcmp(device, RC_SERIAL_PORT) == 0) { RC_INVERT_INPUT(invert); return true; }
return false;
}
#else
static inline bool board_rc_invert_input(const char *device, bool invert) { return false; }
#endif
/* Provide an interface for reading the connected state of VBUS */
/************************************************************************************

View File

@ -46,3 +46,9 @@ add_subdirectory(../stm32_common/version version)
add_subdirectory(px4io_serial)
add_subdirectory(watchdog)
px4_add_library(arch_init
init.cpp
)
target_link_libraries(arch_init PRIVATE px4_layer)

View File

@ -0,0 +1,147 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#include "board_config.h"
#include <px4_platform_common/px4_config.h>
#include <px4_platform/gpio.h>
#include <lib/systemlib/px4_macros.h>
extern "C" __EXPORT void stm32_boardinitialize(void)
{
#if defined(BOARD_HAS_ON_RESET)
// Reset PWM first thing
board_on_reset(-1);
#endif // BOARD_HAS_ON_RESET
#if defined(PX4_GPIO_INIT_LIST)
// configure pins
static constexpr uint32_t gpio_init_list[] = PX4_GPIO_INIT_LIST;
for (const auto &gpio : gpio_init_list) {
px4_arch_configgpio(gpio);
}
#endif // PX4_GPIO_INIT_LIST
board_control_spi_sensors_power_configgpio();
// I2C
#if defined(CONFIG_STM32F7_I2C1)
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SCL));
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SDA));
#endif // CONFIG_STM32F7_I2C1
#if defined(CONFIG_STM32F7_I2C2)
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SCL));
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SDA));
#endif // CONFIG_STM32F7_I2C2
#if defined(CONFIG_STM32F7_I2C3)
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C3_SCL));
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C3_SDA));
#endif // CONFIG_STM32F7_I2C3
#if defined(CONFIG_STM32F7_I2C4)
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C4_SCL));
px4_arch_configgpio(PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C4_SDA));
#endif // CONFIG_STM32F7_I2C4
// SPI
#if defined(CONFIG_STM32F7_SPI1)
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI1_SCK));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI1_MISO));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI1_MOSI));
#endif // CONFIG_STM32F7_SPI1
#if defined(CONFIG_STM32F7_SPI2)
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI2_SCK));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI2_MISO));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI2_MOSI));
#endif // CONFIG_STM32F7_SPI2
#if defined(CONFIG_STM32F7_SPI3)
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI3_SCK));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI3_MISO));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI3_MOSI));
#endif // CONFIG_STM32F7_SPI3
#if defined(CONFIG_STM32F7_SPI4)
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI4_SCK));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI4_MISO));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI4_MOSI));
#endif // CONFIG_STM32F7_SPI4
#if defined(CONFIG_STM32F7_SPI5)
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI5_SCK));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI5_MISO));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI5_MOSI));
#endif // CONFIG_STM32F7_SPI5
#if defined(CONFIG_STM32F7_SPI6)
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI6_SCK));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI6_MISO));
px4_arch_configgpio(PX4_GPIO_PIN_OFF(GPIO_SPI6_MOSI));
#endif // CONFIG_STM32F7_SPI6
// CAN
#if defined(GPIO_CAN1_TX) && defined(GPIO_CAN1_RX)
px4_arch_configgpio(GPIO_CAN1_TX);
px4_arch_configgpio(GPIO_CAN1_RX);
# if defined(GPIO_CAN1_SILENT_S0)
px4_arch_configgpio(GPIO_CAN1_SILENT_S0);
# endif // GPIO_CAN1_SILENT_S0
#endif // GPIO_CAN1_TX && GPIO_CAN1_RX
#if defined(GPIO_CAN2_TX) && defined(GPIO_CAN2_RX)
px4_arch_configgpio(GPIO_CAN2_TX);
px4_arch_configgpio(GPIO_CAN2_RX);
# if defined(GPIO_CAN2_SILENT_S0)
px4_arch_configgpio(GPIO_CAN2_SILENT_S0);
# endif // GPIO_CAN2_SILENT_S0
#endif // GPIO_CAN2_TX && GPIO_CAN2_RX
#if defined(GPIO_CAN3_TX) && defined(GPIO_CAN3_RX)
px4_arch_configgpio(GPIO_CAN3_TX);
px4_arch_configgpio(GPIO_CAN3_RX);
# if defined(GPIO_CAN3_SILENT_S0)
px4_arch_configgpio(GPIO_CAN3_SILENT_S0);
# endif // GPIO_CAN3_SILENT_S0
#endif // GPIO_CAN3_TX && GPIO_CAN3_RX
#if defined(CONFIG_STM32F7_OTGFS)
// configure USB interfaces
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif // CONFIG_STM32F7_OTGFS
#if defined(CONFIG_ARCH_LEDS)
// configure LEDs
board_autoled_initialize();
#endif // CONFIG_ARCH_LEDS
}

View File

@ -47,6 +47,11 @@ DShot::DShot() :
_mixing_output.setAllDisarmedValues(DSHOT_DISARM_VALUE);
_mixing_output.setAllMinValues(DSHOT_MIN_THROTTLE);
_mixing_output.setAllMaxValues(DSHOT_MAX_THROTTLE);
if (_mixing_output.useDynamicMixing()) {
// Avoid using the PWM failsafe params
_mixing_output.setAllFailsafeValues(UINT16_MAX);
}
}
DShot::~DShot()

View File

@ -71,6 +71,10 @@ RCInput::RCInput(const char *device) :
RCInput::~RCInput()
{
#if defined(SPEKTRUM_POWER_PASSIVE)
// Disable power controls for Spektrum receiver
SPEKTRUM_POWER_PASSIVE();
#endif
dsm_deinit();
delete _crsf_telemetry;
@ -80,6 +84,41 @@ RCInput::~RCInput()
perf_free(_publish_interval_perf);
}
int
RCInput::init()
{
#ifdef RF_RADIO_POWER_CONTROL
// power radio on
RF_RADIO_POWER_CONTROL(true);
#endif // RF_RADIO_POWER_CONTROL
// dsm_init sets some file static variables and returns a file descriptor
// it also powers on the radio if needed
_rcs_fd = dsm_init(_device);
if (_rcs_fd < 0) {
return -errno;
}
if (board_rc_swap_rxtx(_device)) {
#if defined(TIOCSSWAP)
ioctl(_rcs_fd, TIOCSSWAP, SER_SWAP_ENABLED);
#endif // TIOCSSWAP
}
// assume SBUS input and immediately switch it to
// so that if Single wire mode on TX there will be only
// a short contention
sbus_config(_rcs_fd, board_rc_singlewire(_device));
#ifdef GPIO_PPM_IN
// disable CPPM input by mapping it away from the timer capture input
px4_arch_unconfiggpio(GPIO_PPM_IN);
#endif // GPIO_PPM_IN
return 0;
}
int
RCInput::task_spawn(int argc, char *argv[])
{
@ -238,28 +277,20 @@ void RCInput::set_rc_scan_state(RC_SCAN newState)
void RCInput::rc_io_invert(bool invert)
{
#if defined(RC_SERIAL_PORT) && defined(RC_INVERT_INPUT)
if (strcmp(_device, RC_SERIAL_PORT) == 0) {
RC_INVERT_INPUT(invert);
}
#endif // RC_SERIAL_PORT && RC_INVERT_INPUT
// First check if the board provides a board-specific inversion method (e.g. via GPIO),
// and if not use an IOCTL
if (!board_rc_invert_input(_device, invert)) {
#if defined(TIOCSINVERT)
if (_rcs_fd >= 0) {
if (invert) {
//int ret_invert = ioctl(_rcs_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX);
ioctl(_rcs_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX);
} else {
ioctl(_rcs_fd, TIOCSINVERT, 0);
}
}
#endif // TIOCSINVERT
}
}
void RCInput::Run()
@ -269,7 +300,16 @@ void RCInput::Run()
return;
}
{
if (!_initialized) {
if (init() == PX4_OK) {
_initialized = true;
} else {
PX4_ERR("init failed");
exit_and_cleanup();
}
} else {
perf_begin(_cycle_perf);
@ -305,17 +345,6 @@ void RCInput::Run()
if (!_rc_scan_locked && !_armed) {
if ((int)vcmd.param1 == 0) {
rc_io_invert(false);
if (_rcs_fd >= 0) {
close(_rcs_fd);
_rcs_fd = -1;
}
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
// DSM binding command
int dsm_bind_mode = (int)vcmd.param2;
@ -334,8 +363,6 @@ void RCInput::Run()
bind_spektrum(dsm_bind_pulses);
cmd_ret = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
dsm_deinit();
}
} else {
@ -391,7 +418,7 @@ void RCInput::Run()
// This block scans for a supported serial RC input and locks onto the first one found
// Scan for 300 msec, then switch protocol
constexpr hrt_abstime rc_scan_max = 700_ms;
constexpr hrt_abstime rc_scan_max = 300_ms;
unsigned frame_drops = 0;
@ -401,8 +428,7 @@ void RCInput::Run()
// read all available data from the serial RC input UART
// read all available data from the serial RC input UART
uint8_t rcs_buf[RC_MAX_BUFFER_SIZE];
int newBytes = ::read(_rcs_fd, &rcs_buf[0], RC_MAX_BUFFER_SIZE);
int newBytes = ::read(_rcs_fd, &_rcs_buf[0], RC_MAX_BUFFER_SIZE);
if (newBytes > 0) {
_bytes_rx += newBytes;
@ -415,24 +441,14 @@ void RCInput::Run()
case RC_SCAN_SBUS:
if (_rc_scan_begin == 0) {
if (_rcs_fd < 0) {
_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
// assume SBUS input and immediately switch it to
// so that if Single wire mode on TX there will be only
// a short contention
sbus_config(_rcs_fd, true);
#if defined(TIOCSSINGLEWIRE)
ioctl(_rcs_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
#endif // TIOCSSINGLEWIRE
_rc_scan_begin = cycle_timestamp;
// Configure serial port for SBUS
sbus_config(_rcs_fd, board_rc_singlewire(_device));
rc_io_invert(true);
_rc_scan_begin = hrt_absolute_time();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -442,7 +458,7 @@ void RCInput::Run()
bool sbus_failsafe = false;
bool sbus_frame_drop = false;
rc_updated = sbus_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count, &sbus_failsafe,
rc_updated = sbus_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count, &sbus_failsafe,
&sbus_frame_drop, &frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -455,16 +471,8 @@ void RCInput::Run()
}
} else {
rc_io_invert(false);
#if defined(TIOCSSINGLEWIRE)
ioctl(_rcs_fd, TIOCSSINGLEWIRE, 0);
#endif // TIOCSSINGLEWIRE
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
rc_io_invert(false);
set_rc_scan_state(RC_SCAN_DSM);
}
@ -472,20 +480,13 @@ void RCInput::Run()
case RC_SCAN_DSM:
if (_rc_scan_begin == 0) {
// dsm_init sets some file static variables and returns a file descriptor
// it also powers on the radio if needed
if (_rcs_fd < 0) {
//_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
dsm_config(_rcs_fd);
if (_rcs_fd < 0) {
PX4_ERR("dsm init failed");
}
_rc_scan_begin = hrt_absolute_time();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -495,7 +496,7 @@ void RCInput::Run()
bool dsm_11_bit = false;
// parse new data
rc_updated = dsm_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
rc_updated = dsm_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
&dsm_11_bit, &frame_drops, &dsm_rssi, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -508,9 +509,6 @@ void RCInput::Run()
}
} else {
dsm_deinit();
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_ST24);
}
@ -521,7 +519,11 @@ void RCInput::Run()
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
dsm_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -535,7 +537,7 @@ void RCInput::Run()
for (unsigned i = 0; i < (unsigned)newBytes; i++) {
/* set updated flag if one complete packet was parsed */
st24_rssi = input_rc_s::RSSI_MAX;
rc_updated = (OK == st24_decode(rcs_buf[i], &st24_rssi, &lost_count,
rc_updated = (OK == st24_decode(_rcs_buf[i], &st24_rssi, &lost_count,
&_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS));
}
@ -558,8 +560,6 @@ void RCInput::Run()
}
} else {
dsm_deinit();
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SUMD);
}
@ -570,9 +570,12 @@ void RCInput::Run()
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
dsm_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -586,7 +589,7 @@ void RCInput::Run()
for (unsigned i = 0; i < (unsigned)newBytes; i++) {
/* set updated flag if one complete packet was parsed */
sumd_rssi = input_rc_s::RSSI_MAX;
rc_updated = (OK == sumd_decode(rcs_buf[i], &sumd_rssi, &rx_count,
rc_updated = (OK == sumd_decode(_rcs_buf[i], &sumd_rssi, &rx_count,
&_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS, &sumd_failsafe));
}
@ -600,8 +603,6 @@ void RCInput::Run()
}
} else {
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_PPM);
}
@ -646,20 +647,19 @@ void RCInput::Run()
case RC_SCAN_CRSF:
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
if (_rcs_fd < 0) {
_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
// Configure serial port for CRSF
crsf_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
// parse new data
if (newBytes > 0) {
rc_updated = crsf_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
rc_updated = crsf_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -686,8 +686,6 @@ void RCInput::Run()
}
} else {
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_GHST);
}
@ -697,21 +695,20 @@ void RCInput::Run()
case RC_SCAN_GHST:
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for GHST
if (_rcs_fd < 0) {
_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
ghst_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
// parse new data
if (newBytes > 0) {
int8_t ghst_rssi = -1;
rc_updated = ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
&_raw_rc_count, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -739,8 +736,6 @@ void RCInput::Run()
}
} else {
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SBUS);
}

View File

@ -129,6 +129,7 @@ private:
hrt_abstime _rc_scan_begin{0};
bool _initialized{false};
bool _rc_scan_locked{false};
bool _report_lock{true};
@ -154,6 +155,7 @@ private:
char _device[20] {}; ///< device / serial port path
static constexpr size_t RC_MAX_BUFFER_SIZE{SBUS_BUFFER_SIZE};
uint8_t _rcs_buf[RC_MAX_BUFFER_SIZE] {};
uint16_t _raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {};
uint16_t _raw_rc_count{};

View File

@ -189,6 +189,8 @@ static bool dsm_decode_channel(uint16_t raw, unsigned shift, uint8_t &channel, u
static constexpr uint16_t offset = 903; // microseconds
value = roundf(servo_position * 0.583f) + offset;
PX4_DEBUG(stderr, "CH%d=%d(0x%02x), ", channel, value, raw);
return true;
}
@ -468,9 +470,6 @@ int dsm_config(int fd)
void dsm_proto_init()
{
memset(&dsm_frame, 0, sizeof(dsm_frame_t));
memset(&dsm_buf, 0, sizeof(dsm_buf_t));
dsm_channel_shift = 0;
dsm_frame_drops = 0;
dsm_chan_count = 0;
@ -510,6 +509,11 @@ int dsm_init(const char *device)
void dsm_deinit()
{
#ifdef SPEKTRUM_POWER_PASSIVE
// Turn power controls to passive
SPEKTRUM_POWER_PASSIVE();
#endif
if (dsm_fd >= 0) {
close(dsm_fd);
}
@ -576,9 +580,7 @@ void dsm_bind(uint16_t cmd, int pulses)
#if defined(DSM_DEBUG)
printf("DSM: DSM_CMD_BIND_REINIT_UART\n");
#endif
#if defined(SPEKTRUM_RX_AS_UART)
SPEKTRUM_RX_AS_UART();
#endif // SPEKTRUM_RX_AS_UART
break;
}

View File

@ -98,9 +98,9 @@ void ActuatorEffectivenessTiltrotorVTOL::updateSetpoint(const matrix::Vector<flo
actuator_controls_s actuator_controls_1;
if (_actuator_controls_1_sub.copy(&actuator_controls_1)) {
float control_flaps = -1.f; // For tilt-rotors INDEX_FLAPS is set as combined tilt. TODO: fix this
float airbrakes_control = actuator_controls_1.control[actuator_controls_s::INDEX_AIRBRAKES];
_control_surfaces.applyFlapsAndAirbrakes(control_flaps, airbrakes_control, _first_control_surface_idx, actuator_sp);
const float flaps_control = actuator_controls_1.control[actuator_controls_s::INDEX_FLAPS];
const float airbrakes_control = actuator_controls_1.control[actuator_controls_s::INDEX_AIRBRAKES];
_control_surfaces.applyFlapsAndAirbrakes(flaps_control, airbrakes_control, _first_control_surface_idx, actuator_sp);
}
}
@ -109,7 +109,7 @@ void ActuatorEffectivenessTiltrotorVTOL::updateSetpoint(const matrix::Vector<flo
actuator_controls_s actuator_controls_1;
if (_actuator_controls_1_sub.copy(&actuator_controls_1)) {
float control_tilt = actuator_controls_1.control[4] * 2.f - 1.f;
float control_tilt = actuator_controls_1.control[actuator_controls_s::INDEX_COLLECTIVE_TILT] * 2.f - 1.f;
// set control_tilt to exactly -1 or 1 if close to these end points
control_tilt = control_tilt < -0.99f ? -1.f : control_tilt;

View File

@ -44,4 +44,5 @@ px4_add_module(
ecl_yaw_controller.cpp
DEPENDS
px4_work_queue
SlewRate
)

View File

@ -67,6 +67,8 @@ FixedwingAttitudeControl::FixedwingAttitudeControl(bool vtol) :
_yaw_ctrl.set_max_rate(radians(_param_fw_acro_z_max.get()));
_rate_ctrl_status_pub.advertise();
_spoiler_setpoint_with_slewrate.setSlewRate(kSpoilerSlewRate);
_flaps_setpoint_with_slewrate.setSlewRate(kFlapSlewRate);
}
FixedwingAttitudeControl::~FixedwingAttitudeControl()
@ -382,11 +384,14 @@ void FixedwingAttitudeControl::Run()
/* if we are in rotary wing mode, do nothing */
if (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !_vehicle_status.is_vtol) {
_spoiler_setpoint_with_slewrate.setForcedValue(0.f);
_flaps_setpoint_with_slewrate.setForcedValue(0.f);
perf_end(_loop_perf);
return;
}
control_flaps(dt);
controlFlaps(dt);
controlSpoilers(dt);
/* decide if in stabilized or full manual control */
if (_vcontrol_mode.flag_control_rates_enabled) {
@ -498,8 +503,11 @@ void FixedwingAttitudeControl::Run()
}
/* add trim increment if flaps are deployed */
trim_roll += _flaps_applied * _param_fw_dtrim_r_flps.get();
trim_pitch += _flaps_applied * _param_fw_dtrim_p_flps.get();
trim_roll += _flaps_setpoint_with_slewrate.getState() * _param_fw_dtrim_r_flps.get();
trim_pitch += _flaps_setpoint_with_slewrate.getState() * _param_fw_dtrim_p_flps.get();
// add trim increment from spoilers (only pitch)
trim_pitch += _spoiler_setpoint_with_slewrate.getState() * _param_fw_dtrim_p_spoil.get();
/* Run attitude controllers */
if (_vcontrol_mode.flag_control_attitude_enabled) {
@ -645,11 +653,11 @@ void FixedwingAttitudeControl::Run()
_actuators.control[actuator_controls_s::INDEX_YAW] += _param_fw_rll_to_yaw_ff.get()
* constrain(_actuators.control[actuator_controls_s::INDEX_ROLL], -1.0f, 1.0f);
_actuators.control[actuator_controls_s::INDEX_FLAPS] = _flaps_applied;
_actuators.control[5] = _manual_control_setpoint.aux1;
_actuators.control[actuator_controls_s::INDEX_AIRBRAKES] = _flaperons_applied;
_actuators.control[actuator_controls_s::INDEX_FLAPS] = _flaps_setpoint_with_slewrate.getState();
_actuators.control[actuator_controls_s::INDEX_SPOILERS] = _spoiler_setpoint_with_slewrate.getState();
_actuators.control[actuator_controls_s::INDEX_AIRBRAKES] = 0.f;
// FIXME: this should use _vcontrol_mode.landing_gear_pos in the future
_actuators.control[7] = _manual_control_setpoint.aux3;
_actuators.control[actuator_controls_s::INDEX_LANDING_GEAR] = _manual_control_setpoint.aux3;
/* lazily publish the setpoint only once available */
_actuators.timestamp = hrt_absolute_time();
@ -697,18 +705,16 @@ void FixedwingAttitudeControl::publishThrustSetpoint(const hrt_abstime &timestam
_vehicle_thrust_setpoint_pub.publish(v_thrust_sp);
}
void FixedwingAttitudeControl::control_flaps(const float dt)
void FixedwingAttitudeControl::controlFlaps(const float dt)
{
/* default flaps to center */
float flap_control = 0.0f;
/* map flaps by default to manual if valid */
if (PX4_ISFINITE(_manual_control_setpoint.flaps) && _vcontrol_mode.flag_control_manual_enabled
&& fabsf(_param_fw_flaps_scl.get()) > 0.01f) {
flap_control = _manual_control_setpoint.flaps * _param_fw_flaps_scl.get();
if (PX4_ISFINITE(_manual_control_setpoint.flaps) && _vcontrol_mode.flag_control_manual_enabled) {
flap_control = _manual_control_setpoint.flaps;
} else if (_vcontrol_mode.flag_control_auto_enabled
&& fabsf(_param_fw_flaps_scl.get()) > 0.01f) {
} else if (_vcontrol_mode.flag_control_auto_enabled) {
switch (_att_sp.apply_flaps) {
case vehicle_attitude_setpoint_s::FLAPS_OFF:
@ -716,50 +722,54 @@ void FixedwingAttitudeControl::control_flaps(const float dt)
break;
case vehicle_attitude_setpoint_s::FLAPS_LAND:
flap_control = 1.0f * _param_fw_flaps_scl.get() * _param_fw_flaps_lnd_scl.get();
flap_control = _param_fw_flaps_lnd_scl.get();
break;
case vehicle_attitude_setpoint_s::FLAPS_TAKEOFF:
flap_control = 1.0f * _param_fw_flaps_scl.get() * _param_fw_flaps_to_scl.get();
flap_control = _param_fw_flaps_to_scl.get();
break;
}
}
// move the actual control value continuous with time, full flap travel in 1sec
if (fabsf(_flaps_applied - flap_control) > 0.01f) {
_flaps_applied += (_flaps_applied - flap_control) < 0 ? dt : -dt;
_flaps_setpoint_with_slewrate.update(math::constrain(flap_control, 0.f, 1.f), dt);
}
} else {
_flaps_applied = flap_control;
}
void FixedwingAttitudeControl::controlSpoilers(const float dt)
{
float spoiler_control = 0.f;
/* default flaperon to center */
float flaperon_control = 0.0f;
if (_vcontrol_mode.flag_control_manual_enabled) {
switch (_param_fw_spoilers_man.get()) {
case 0:
break;
/* map flaperons by default to manual if valid */
if (PX4_ISFINITE(_manual_control_setpoint.aux2) && _vcontrol_mode.flag_control_manual_enabled
&& fabsf(_param_fw_flaperon_scl.get()) > 0.01f) {
case 1:
spoiler_control = PX4_ISFINITE(_manual_control_setpoint.flaps) ? _manual_control_setpoint.flaps : 0.f;
break;
flaperon_control = 0.5f * (_manual_control_setpoint.aux2 + 1.0f) * _param_fw_flaperon_scl.get();
case 2:
spoiler_control = PX4_ISFINITE(_manual_control_setpoint.aux1) ? _manual_control_setpoint.aux1 : 0.f;
break;
}
} else if (_vcontrol_mode.flag_control_auto_enabled
&& fabsf(_param_fw_flaperon_scl.get()) > 0.01f) {
} else if (_vcontrol_mode.flag_control_auto_enabled) {
switch (_att_sp.apply_spoilers) {
case vehicle_attitude_setpoint_s::SPOILERS_OFF:
spoiler_control = 0.f;
break;
if (_att_sp.apply_flaps == vehicle_attitude_setpoint_s::FLAPS_LAND) {
flaperon_control = _param_fw_flaperon_scl.get();
case vehicle_attitude_setpoint_s::SPOILERS_LAND:
spoiler_control = _param_fw_spoilers_lnd.get();
break;
} else {
flaperon_control = 0.0f;
case vehicle_attitude_setpoint_s::SPOILERS_DESCEND:
spoiler_control = _param_fw_spoilers_desc.get();
break;
}
}
// move the actual control value continuous with time, full flap travel in 1sec
if (fabsf(_flaperons_applied - flaperon_control) > 0.01f) {
_flaperons_applied += (_flaperons_applied - flaperon_control) < 0 ? dt : -dt;
} else {
_flaperons_applied = flaperon_control;
}
_spoiler_setpoint_with_slewrate.update(math::constrain(spoiler_control, 0.f, 1.f), dt);
}
void FixedwingAttitudeControl::updateActuatorControlsStatus(float dt)

View File

@ -40,6 +40,7 @@
#include <lib/mathlib/mathlib.h>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>
#include <lib/slew_rate/SlewRate.hpp>
#include <matrix/math.hpp>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
@ -78,6 +79,9 @@ using uORB::SubscriptionData;
using namespace time_literals;
static constexpr float kFlapSlewRate = 1.f; //minimum time from none to full flap deflection [s]
static constexpr float kSpoilerSlewRate = 1.f; //minimum time from none to full spoiler deflection [s]
class FixedwingAttitudeControl final : public ModuleBase<FixedwingAttitudeControl>, public ModuleParams,
public px4::WorkItem
{
@ -139,9 +143,6 @@ private:
hrt_abstime _last_run{0};
float _flaps_applied{0.0f};
float _flaperons_applied{0.0f};
float _airspeed_scaling{1.0f};
bool _landed{true};
@ -156,6 +157,9 @@ private:
float _control_energy[4] {};
float _control_prev[3] {};
SlewRate<float> _spoiler_setpoint_with_slewrate;
SlewRate<float> _flaps_setpoint_with_slewrate;
DEFINE_PARAMETERS(
(ParamFloat<px4::params::FW_ACRO_X_MAX>) _param_fw_acro_x_max,
(ParamFloat<px4::params::FW_ACRO_Y_MAX>) _param_fw_acro_y_max,
@ -171,6 +175,7 @@ private:
(ParamBool<px4::params::FW_BAT_SCALE_EN>) _param_fw_bat_scale_en,
(ParamFloat<px4::params::FW_DTRIM_P_FLPS>) _param_fw_dtrim_p_flps,
(ParamFloat<px4::params::FW_DTRIM_P_SPOIL>) _param_fw_dtrim_p_spoil,
(ParamFloat<px4::params::FW_DTRIM_P_VMAX>) _param_fw_dtrim_p_vmax,
(ParamFloat<px4::params::FW_DTRIM_P_VMIN>) _param_fw_dtrim_p_vmin,
(ParamFloat<px4::params::FW_DTRIM_R_FLPS>) _param_fw_dtrim_r_flps,
@ -179,10 +184,11 @@ private:
(ParamFloat<px4::params::FW_DTRIM_Y_VMAX>) _param_fw_dtrim_y_vmax,
(ParamFloat<px4::params::FW_DTRIM_Y_VMIN>) _param_fw_dtrim_y_vmin,
(ParamFloat<px4::params::FW_FLAPERON_SCL>) _param_fw_flaperon_scl,
(ParamFloat<px4::params::FW_FLAPS_LND_SCL>) _param_fw_flaps_lnd_scl,
(ParamFloat<px4::params::FW_FLAPS_SCL>) _param_fw_flaps_scl,
(ParamFloat<px4::params::FW_FLAPS_TO_SCL>) _param_fw_flaps_to_scl,
(ParamFloat<px4::params::FW_SPOILERS_LND>) _param_fw_spoilers_lnd,
(ParamFloat<px4::params::FW_SPOILERS_DESC>) _param_fw_spoilers_desc,
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man,
(ParamFloat<px4::params::FW_MAN_P_MAX>) _param_fw_man_p_max,
(ParamFloat<px4::params::FW_MAN_P_SC>) _param_fw_man_p_sc,
@ -230,7 +236,19 @@ private:
ECL_YawController _yaw_ctrl;
ECL_WheelController _wheel_ctrl;
void control_flaps(const float dt);
/**
* @brief Update flap control setting
*
* @param dt Current time delta [s]
*/
void controlFlaps(const float dt);
/**
* @brief Update spoiler control setting
*
* @param dt Current time delta [s]
*/
void controlSpoilers(const float dt);
void updateActuatorControlsStatus(float dt);

View File

@ -457,22 +457,11 @@ PARAM_DEFINE_FLOAT(FW_MAN_R_MAX, 45.0f);
*/
PARAM_DEFINE_FLOAT(FW_MAN_P_MAX, 45.0f);
/**
* Scale factor for flaps
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_FLAPS_SCL, 1.0f);
/**
* Flaps setting during take-off
*
* Sets a fraction of full flaps (FW_FLAPS_SCL) during take-off
* Sets a fraction of full flaps during take-off.
* Also applies to flaperons if enabled in the mixer/allocation.
*
* @unit norm
* @min 0.0
@ -486,7 +475,8 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f);
/**
* Flaps setting during landing
*
* Sets a fraction of full flaps (FW_FLAPS_SCL) during landing
* Sets a fraction of full flaps during landing.
* Also applies to flaperons if enabled in the mixer/allocation.
*
* @unit norm
* @min 0.0
@ -497,18 +487,6 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f);
*/
PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f);
/**
* Scale factor for flaperons
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_FLAPERON_SCL, 0.0f);
/**
* Airspeed mode
*
@ -735,3 +713,52 @@ PARAM_DEFINE_FLOAT(FW_DTRIM_R_FLPS, 0.0f);
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(FW_DTRIM_P_FLPS, 0.0f);
/**
* Pitch trim increment for spoiler configuration
*
* This increment is added to the pitch trim whenever spoilers are fully deployed.
*
* @group FW Attitude Control
* @min -0.25
* @max 0.25
* @decimal 2
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(FW_DTRIM_P_SPOIL, 0.f);
/**
* Spoiler landing setting
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_SPOILERS_LND, 0.f);
/**
* Spoiler descend setting
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_SPOILERS_DESC, 0.f);
/**
* Spoiler input in manual flight
*
* Chose source for manual setting of spoilers in manual flight modes.
*
* @value 0 Disabled
* @value 1 Flaps channel
* @value 2 Aux1
* @group FW Attitude Control
*/
PARAM_DEFINE_INT32(FW_SPOILERS_MAN, 0);

View File

@ -842,9 +842,6 @@ FixedwingPositionControl::control_auto(const hrt_abstime &now, const Vector2d &c
_l1_control.set_dt(dt);
}
_att_sp.fw_control_yaw = false; // by default we don't want yaw to be contoller directly with rudder
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF; // by default we don't use flaps
/* save time when airplane is in air */
if (!_was_in_air && !_landed) {
_was_in_air = true;
@ -917,6 +914,9 @@ FixedwingPositionControl::control_auto(const hrt_abstime &now, const Vector2d &c
_att_sp.thrust_body[0] = 0.0f;
_att_sp.roll_body = 0.0f;
_att_sp.pitch_body = radians(_param_fw_psp_off.get());
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
break;
case position_setpoint_s::SETPOINT_TYPE_POSITION:
@ -991,6 +991,9 @@ FixedwingPositionControl::control_auto_fixed_bank_alt_hold(const hrt_abstime &no
}
_att_sp.pitch_body = get_tecs_pitch();
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
}
void
@ -1019,6 +1022,9 @@ FixedwingPositionControl::control_auto_descend(const hrt_abstime &now)
_att_sp.thrust_body[0] = (_landed) ? _param_fw_thr_min.get() : min(get_tecs_thrust(), _param_fw_thr_max.get());
_att_sp.pitch_body = get_tecs_pitch();
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
}
uint8_t
@ -1206,6 +1212,9 @@ FixedwingPositionControl::control_auto_position(const hrt_abstime &now, const fl
_att_sp.yaw_body = _yaw; // yaw is not controlled, so set setpoint to current yaw
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
tecs_update_pitch_throttle(now, position_sp_alt,
target_airspeed,
radians(_param_fw_p_lim_min.get()),
@ -1269,6 +1278,9 @@ FixedwingPositionControl::control_auto_velocity(const hrt_abstime &now, const fl
_att_sp.yaw_body = _yaw;
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
tecs_update_pitch_throttle(now, position_sp_alt,
target_airspeed,
radians(_param_fw_p_lim_min.get()),
@ -1356,7 +1368,12 @@ FixedwingPositionControl::control_auto_loiter(const hrt_abstime &now, const floa
// have to do this switch (which can cause significant altitude errors) close to the ground.
_tecs.set_height_error_time_constant(_param_fw_thrtc_sc.get() * _param_fw_t_h_error_tc.get());
airspeed_sp = _param_fw_lnd_airspd_sc.get() * _param_fw_airspd_min.get();
_att_sp.apply_flaps = true;
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_LAND;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_LAND;
} else {
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
}
float target_airspeed = get_auto_airspeed_setpoint(now, airspeed_sp, ground_speed, dt);
@ -1445,10 +1462,6 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const Vec
prev_wp(1) = pos_sp_curr.lon;
}
// apply flaps for takeoff according to the corresponding scale factor set
// via FW_FLAPS_TO_SCL
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_TAKEOFF;
// continuously reset launch detection and runway takeoff until armed
if (!_control_mode.flag_armed) {
_launchDetector.reset();
@ -1521,6 +1534,10 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const Vec
_att_sp.roll_reset_integral = _runway_takeoff.resetIntegrators();
_att_sp.pitch_reset_integral = _runway_takeoff.resetIntegrators();
// apply flaps for takeoff according to the corresponding scale factor set via FW_FLAPS_TO_SCL
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_TAKEOFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
} else {
/* Perform launch detection */
if (_launchDetector.launchDetectionEnabled() &&
@ -1623,6 +1640,9 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const Vec
_att_sp.roll_body = 0.0f;
_att_sp.pitch_body = radians(_takeoff_pitch_min.get());
}
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
}
if (_launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS && !_runway_takeoff.runwayTakeoffEnabled()) {
@ -1684,10 +1704,6 @@ FixedwingPositionControl::control_auto_landing(const hrt_abstime &now, const Vec
prev_wp(1) = pos_sp_curr.lon;
}
// apply full flaps for landings. this flag will also trigger the use of flaperons
// if they have been enabled using the corresponding parameter
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_LAND;
// Enable tighter altitude control for landings
_tecs.set_height_error_time_constant(_param_fw_thrtc_sc.get() * _param_fw_t_h_error_tc.get());
@ -2003,6 +2019,10 @@ FixedwingPositionControl::control_auto_landing(const hrt_abstime &now, const Vec
// when we are landed state we want the motor to spin at idle speed
_att_sp.thrust_body[0] = (_landed) ? min(_param_fw_thr_idle.get(), 1.f) : get_tecs_thrust();
// Apply flaps and spoilers for landing. Amount of deflection is handled in the FW attitdue controller
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_LAND;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_LAND;
if (!_vehicle_status.in_transition_to_fw) {
publishLocalPositionSetpoint(pos_sp_curr);
}
@ -2068,6 +2088,11 @@ FixedwingPositionControl::control_manual_altitude(const hrt_abstime &now, const
}
_att_sp.pitch_body = get_tecs_pitch();
// In Manual modes flaps and spoilers are directly controlled in FW Attitude controller and not passed
// through attitdue setpoints
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
}
void
@ -2212,6 +2237,11 @@ FixedwingPositionControl::control_manual_position(const hrt_abstime &now, const
}
_att_sp.pitch_body = get_tecs_pitch();
// In Manual modes flaps and spoilers are directly controlled in FW Attitude controller and not passed
// through attitdue setpoints
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
}
float
@ -2391,6 +2421,8 @@ FixedwingPositionControl::Run()
set_control_mode_current(_local_pos.timestamp, _pos_sp_triplet.current.valid);
_att_sp.fw_control_yaw = false; // by default we don't want yaw to be contoller directly with rudder
switch (_control_mode_current) {
case FW_POSCTRL_MODE_AUTO: {
control_auto(_local_pos.timestamp, curr_pos, ground_speed, _pos_sp_triplet.previous, _pos_sp_triplet.current,
@ -2437,6 +2469,9 @@ FixedwingPositionControl::Run()
_att_sp.thrust_body[0] = min(_att_sp.thrust_body[0], _param_fw_thr_max.get());
_att_sp.apply_flaps = vehicle_attitude_setpoint_s::FLAPS_OFF;
_att_sp.apply_spoilers = vehicle_attitude_setpoint_s::SPOILERS_OFF;
break;
}

View File

@ -51,7 +51,6 @@ MulticopterPositionControl::MulticopterPositionControl(bool vtol) :
_vel_z_deriv(this, "VELD")
{
parameters_update(true);
_failsafe_land_hysteresis.set_hysteresis_time_from(false, LOITER_TIME_BEFORE_DESCEND);
_tilt_limit_slew_rate.setSlewRate(.2f);
reset_setpoint_to_nan(_setpoint);
_takeoff_status_pub.advertise();
@ -241,32 +240,35 @@ void MulticopterPositionControl::parameters_update(bool force)
}
}
PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehicle_local_position_s &local_pos)
PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehicle_local_position_s
&vehicle_local_position)
{
PositionControlStates states;
// only set position states if valid and finite
if (PX4_ISFINITE(local_pos.x) && PX4_ISFINITE(local_pos.y) && local_pos.xy_valid) {
states.position(0) = local_pos.x;
states.position(1) = local_pos.y;
if (PX4_ISFINITE(vehicle_local_position.x) && PX4_ISFINITE(vehicle_local_position.y)
&& vehicle_local_position.xy_valid) {
states.position(0) = vehicle_local_position.x;
states.position(1) = vehicle_local_position.y;
} else {
states.position(0) = NAN;
states.position(1) = NAN;
}
if (PX4_ISFINITE(local_pos.z) && local_pos.z_valid) {
states.position(2) = local_pos.z;
if (PX4_ISFINITE(vehicle_local_position.z) && vehicle_local_position.z_valid) {
states.position(2) = vehicle_local_position.z;
} else {
states.position(2) = NAN;
}
if (PX4_ISFINITE(local_pos.vx) && PX4_ISFINITE(local_pos.vy) && local_pos.v_xy_valid) {
states.velocity(0) = local_pos.vx;
states.velocity(1) = local_pos.vy;
states.acceleration(0) = _vel_x_deriv.update(local_pos.vx);
states.acceleration(1) = _vel_y_deriv.update(local_pos.vy);
if (PX4_ISFINITE(vehicle_local_position.vx) && PX4_ISFINITE(vehicle_local_position.vy)
&& vehicle_local_position.v_xy_valid) {
states.velocity(0) = vehicle_local_position.vx;
states.velocity(1) = vehicle_local_position.vy;
states.acceleration(0) = _vel_x_deriv.update(vehicle_local_position.vx);
states.acceleration(1) = _vel_y_deriv.update(vehicle_local_position.vy);
} else {
states.velocity(0) = NAN;
@ -279,8 +281,8 @@ PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehic
_vel_y_deriv.reset();
}
if (PX4_ISFINITE(local_pos.vz) && local_pos.v_z_valid) {
states.velocity(2) = local_pos.vz;
if (PX4_ISFINITE(vehicle_local_position.vz) && vehicle_local_position.v_z_valid) {
states.velocity(2) = vehicle_local_position.vz;
states.acceleration(2) = _vel_z_deriv.update(states.velocity(2));
} else {
@ -291,7 +293,7 @@ PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehic
_vel_z_deriv.reset();
}
states.yaw = local_pos.heading;
states.yaw = vehicle_local_position.heading;
return states;
}
@ -310,18 +312,30 @@ void MulticopterPositionControl::Run()
parameters_update(false);
perf_begin(_cycle_perf);
vehicle_local_position_s local_pos;
vehicle_local_position_s vehicle_local_position;
if (_local_pos_sub.update(&local_pos)) {
const hrt_abstime time_stamp_now = local_pos.timestamp_sample;
const float dt = math::constrain(((time_stamp_now - _time_stamp_last_loop) * 1e-6f), 0.002f, 0.04f);
_time_stamp_last_loop = time_stamp_now;
if (_local_pos_sub.update(&vehicle_local_position)) {
const float dt =
math::constrain(((vehicle_local_position.timestamp_sample - _time_stamp_last_loop) * 1e-6f), 0.002f, 0.04f);
_time_stamp_last_loop = vehicle_local_position.timestamp_sample;
// set _dt in controllib Block for BlockDerivative
setDt(dt);
_in_failsafe = false;
_vehicle_control_mode_sub.update(&_vehicle_control_mode);
if (_vehicle_control_mode_sub.updated()) {
const bool previous_position_control_enabled = _vehicle_control_mode.flag_multicopter_position_control_enabled;
if (_vehicle_control_mode_sub.update(&_vehicle_control_mode)) {
if (!previous_position_control_enabled && _vehicle_control_mode.flag_multicopter_position_control_enabled) {
_time_position_control_enabled = _vehicle_control_mode.timestamp;
} else if (previous_position_control_enabled && !_vehicle_control_mode.flag_multicopter_position_control_enabled) {
// clear existing setpoint when controller is no longer active
reset_setpoint_to_nan(_setpoint);
}
}
}
_vehicle_land_detected_sub.update(&_vehicle_land_detected);
if (_param_mpc_use_hte.get()) {
@ -334,36 +348,65 @@ void MulticopterPositionControl::Run()
}
}
PositionControlStates states{set_vehicle_states(local_pos)};
const bool is_trajectory_setpoint_updated = _trajectory_setpoint_sub.update(&_setpoint);
// adjust existing (or older) setpoint with any EKF reset deltas
if ((_setpoint.timestamp != 0) && (_setpoint.timestamp < vehicle_local_position.timestamp)) {
if (vehicle_local_position.vxy_reset_counter != _vxy_reset_counter) {
_setpoint.vx += vehicle_local_position.delta_vxy[0];
_setpoint.vy += vehicle_local_position.delta_vxy[1];
}
if (vehicle_local_position.vz_reset_counter != _vz_reset_counter) {
_setpoint.vz += vehicle_local_position.delta_vz;
}
if (vehicle_local_position.xy_reset_counter != _xy_reset_counter) {
_setpoint.x += vehicle_local_position.delta_xy[0];
_setpoint.y += vehicle_local_position.delta_xy[1];
}
if (vehicle_local_position.z_reset_counter != _z_reset_counter) {
_setpoint.z += vehicle_local_position.delta_z;
}
if (vehicle_local_position.heading_reset_counter != _heading_reset_counter) {
_setpoint.yaw = wrap_pi(_setpoint.yaw + vehicle_local_position.delta_heading);
}
}
if (vehicle_local_position.vxy_reset_counter != _vxy_reset_counter) {
_vel_x_deriv.reset();
_vel_y_deriv.reset();
}
if (vehicle_local_position.vz_reset_counter != _vz_reset_counter) {
_vel_z_deriv.reset();
}
// save latest reset counters
_vxy_reset_counter = vehicle_local_position.vxy_reset_counter;
_vz_reset_counter = vehicle_local_position.vz_reset_counter;
_xy_reset_counter = vehicle_local_position.xy_reset_counter;
_z_reset_counter = vehicle_local_position.z_reset_counter;
_heading_reset_counter = vehicle_local_position.heading_reset_counter;
PositionControlStates states{set_vehicle_states(vehicle_local_position)};
if (_vehicle_control_mode.flag_multicopter_position_control_enabled) {
// set failsafe setpoint if there hasn't been a new
// trajectory setpoint since position control started
if ((_setpoint.timestamp < _time_position_control_enabled)
&& (vehicle_local_position.timestamp_sample > _time_position_control_enabled)) {
const bool is_trajectory_setpoint_updated = _trajectory_setpoint_sub.update(&_setpoint);
// adjust existing (or older) setpoint with any EKF reset deltas
if (_setpoint.timestamp < local_pos.timestamp) {
if (local_pos.vxy_reset_counter != _vxy_reset_counter) {
_setpoint.vx += local_pos.delta_vxy[0];
_setpoint.vy += local_pos.delta_vxy[1];
}
if (local_pos.vz_reset_counter != _vz_reset_counter) {
_setpoint.vz += local_pos.delta_vz;
}
if (local_pos.xy_reset_counter != _xy_reset_counter) {
_setpoint.x += local_pos.delta_xy[0];
_setpoint.y += local_pos.delta_xy[1];
}
if (local_pos.z_reset_counter != _z_reset_counter) {
_setpoint.z += local_pos.delta_z;
}
if (local_pos.heading_reset_counter != _heading_reset_counter) {
_setpoint.yaw += local_pos.delta_heading;
}
_setpoint = generateFailsafeSetpoint(vehicle_local_position.timestamp_sample, states);
}
}
if (_vehicle_control_mode.flag_multicopter_position_control_enabled
&& (_setpoint.timestamp >= _time_position_control_enabled)) {
// update vehicle constraints and handle smooth takeoff
_vehicle_constraints_sub.update(&_vehicle_constraints);
@ -377,7 +420,7 @@ void MulticopterPositionControl::Run()
if (_vehicle_control_mode.flag_control_offboard_enabled) {
bool want_takeoff = _vehicle_control_mode.flag_armed && _vehicle_land_detected.landed
&& hrt_elapsed_time(&_setpoint.timestamp) < 1_s;
&& (vehicle_local_position.timestamp_sample < _setpoint.timestamp + 1_s);
if (want_takeoff && PX4_ISFINITE(_setpoint.z)
&& (_setpoint.z < states.position(2))) {
@ -406,7 +449,7 @@ void MulticopterPositionControl::Run()
// handle smooth takeoff
_takeoff.updateTakeoffState(_vehicle_control_mode.flag_armed, _vehicle_land_detected.landed,
_vehicle_constraints.want_takeoff,
_vehicle_constraints.speed_up, false, time_stamp_now);
_vehicle_constraints.speed_up, false, vehicle_local_position.timestamp_sample);
const bool flying = (_takeoff.getTakeoffState() >= TakeoffState::flight);
@ -424,6 +467,7 @@ void MulticopterPositionControl::Run()
if (not_taken_off || flying_but_ground_contact) {
// we are not flying yet and need to avoid any corrections
reset_setpoint_to_nan(_setpoint);
_setpoint.timestamp = vehicle_local_position.timestamp_sample;
Vector3f(0.f, 0.f, 100.f).copyTo(_setpoint.acceleration); // High downwards acceleration to make sure there's no thrust
// prevent any integrator windup
@ -456,40 +500,24 @@ void MulticopterPositionControl::Run()
// update states
if (!PX4_ISFINITE(_setpoint.z)
&& PX4_ISFINITE(_setpoint.vz) && (fabsf(_setpoint.vz) > FLT_EPSILON)
&& PX4_ISFINITE(local_pos.z_deriv) && local_pos.z_valid && local_pos.v_z_valid) {
&& PX4_ISFINITE(vehicle_local_position.z_deriv) && vehicle_local_position.z_valid && vehicle_local_position.v_z_valid) {
// A change in velocity is demanded and the altitude is not controlled.
// Set velocity to the derivative of position
// because it has less bias but blend it in across the landing speed range
// < MPC_LAND_SPEED: ramp up using altitude derivative without a step
// >= MPC_LAND_SPEED: use altitude derivative
float weighting = fminf(fabsf(_setpoint.vz) / _param_mpc_land_speed.get(), 1.f);
states.velocity(2) = local_pos.z_deriv * weighting + local_pos.vz * (1.f - weighting);
states.velocity(2) = vehicle_local_position.z_deriv * weighting + vehicle_local_position.vz * (1.f - weighting);
}
_control.setState(states);
// Run position control
if (_control.update(dt)) {
_failsafe_land_hysteresis.set_state_and_update(false, time_stamp_now);
} else {
if (!_control.update(dt)) {
// Failsafe
// do not warn while we are disarmed, as we might not have valid setpoints yet
const bool warn_failsafe = ((time_stamp_now - _last_warn) > 2_s) && _vehicle_control_mode.flag_armed;
_vehicle_constraints = {0, NAN, NAN, false, {}}; // reset constraints
if (warn_failsafe) {
PX4_WARN("invalid setpoints");
_last_warn = time_stamp_now;
}
vehicle_local_position_setpoint_s failsafe_setpoint{};
failsafe(time_stamp_now, failsafe_setpoint, states, warn_failsafe);
// reset constraints
_vehicle_constraints = {0, NAN, NAN, false, {}};
_control.setInputSetpoint(failsafe_setpoint);
_control.setInputSetpoint(generateFailsafeSetpoint(vehicle_local_position.timestamp_sample, states));
_control.setVelocityLimits(_param_mpc_xy_vel_max.get(), _param_mpc_z_vel_max_up.get(), _param_mpc_z_vel_max_dn.get());
_control.update(dt);
}
@ -511,7 +539,7 @@ void MulticopterPositionControl::Run()
} else {
// an update is necessary here because otherwise the takeoff state doesn't get skiped with non-altitude-controlled modes
_takeoff.updateTakeoffState(_vehicle_control_mode.flag_armed, _vehicle_land_detected.landed, false, 10.f, true,
time_stamp_now);
vehicle_local_position.timestamp_sample);
}
// Publish takeoff status
@ -524,71 +552,71 @@ void MulticopterPositionControl::Run()
_takeoff_status_pub.get().timestamp = hrt_absolute_time();
_takeoff_status_pub.update();
}
// save latest reset counters
_vxy_reset_counter = local_pos.vxy_reset_counter;
_vz_reset_counter = local_pos.vz_reset_counter;
_xy_reset_counter = local_pos.xy_reset_counter;
_z_reset_counter = local_pos.z_reset_counter;
_heading_reset_counter = local_pos.heading_reset_counter;
}
perf_end(_cycle_perf);
}
void MulticopterPositionControl::failsafe(const hrt_abstime &now, vehicle_local_position_setpoint_s &setpoint,
const PositionControlStates &states, bool warn)
vehicle_local_position_setpoint_s MulticopterPositionControl::generateFailsafeSetpoint(const hrt_abstime &now,
const PositionControlStates &states)
{
// Only react after a short delay
_failsafe_land_hysteresis.set_state_and_update(true, now);
// do not warn while we are disarmed, as we might not have valid setpoints yet
bool warn = _vehicle_control_mode.flag_armed && ((now - _last_warn) > 2_s);
if (_failsafe_land_hysteresis.get_state()) {
reset_setpoint_to_nan(setpoint);
if (PX4_ISFINITE(states.velocity(0)) && PX4_ISFINITE(states.velocity(1))) {
// don't move along xy
setpoint.vx = setpoint.vy = 0.f;
if (warn) {
PX4_WARN("Failsafe: stop and wait");
}
} else {
// descend with land speed since we can't stop
setpoint.acceleration[0] = setpoint.acceleration[1] = 0.f;
setpoint.vz = _param_mpc_land_speed.get();
if (warn) {
PX4_WARN("Failsafe: blind land");
}
}
if (PX4_ISFINITE(states.velocity(2))) {
// don't move along z if we can stop in all dimensions
if (!PX4_ISFINITE(setpoint.vz)) {
setpoint.vz = 0.f;
}
} else {
// emergency descend with a bit below hover thrust
setpoint.vz = NAN;
setpoint.acceleration[2] = .3f;
if (warn) {
PX4_WARN("Failsafe: blind descend");
}
}
_in_failsafe = true;
if (warn) {
PX4_WARN("invalid setpoints");
_last_warn = now;
}
vehicle_local_position_setpoint_s failsafe_setpoint{};
reset_setpoint_to_nan(failsafe_setpoint);
failsafe_setpoint.timestamp = now;
if (PX4_ISFINITE(states.velocity(0)) && PX4_ISFINITE(states.velocity(1))) {
// don't move along xy
failsafe_setpoint.vx = failsafe_setpoint.vy = 0.f;
if (warn) {
PX4_WARN("Failsafe: stop and wait");
}
} else {
// descend with land speed since we can't stop
failsafe_setpoint.acceleration[0] = failsafe_setpoint.acceleration[1] = 0.f;
failsafe_setpoint.vz = _param_mpc_land_speed.get();
if (warn) {
PX4_WARN("Failsafe: blind land");
}
}
if (PX4_ISFINITE(states.velocity(2))) {
// don't move along z if we can stop in all dimensions
if (!PX4_ISFINITE(failsafe_setpoint.vz)) {
failsafe_setpoint.vz = 0.f;
}
} else {
// emergency descend with a bit below hover thrust
failsafe_setpoint.vz = NAN;
failsafe_setpoint.acceleration[2] = .3f;
if (warn) {
PX4_WARN("Failsafe: blind descent");
}
}
return failsafe_setpoint;
}
void MulticopterPositionControl::reset_setpoint_to_nan(vehicle_local_position_setpoint_s &setpoint)
{
setpoint.timestamp = 0;
setpoint.x = setpoint.y = setpoint.z = NAN;
setpoint.vx = setpoint.vy = setpoint.vz = NAN;
setpoint.yaw = setpoint.yawspeed = NAN;
setpoint.vx = setpoint.vy = setpoint.vz = NAN;
setpoint.acceleration[0] = setpoint.acceleration[1] = setpoint.acceleration[2] = NAN;
setpoint.jerk[0] = setpoint.jerk[1] = setpoint.jerk[2] = NAN;
setpoint.thrust[0] = setpoint.thrust[1] = setpoint.thrust[2] = NAN;
}

View File

@ -42,7 +42,6 @@
#include <drivers/drv_hrt.h>
#include <lib/controllib/blocks.hpp>
#include <lib/hysteresis/hysteresis.h>
#include <lib/perf/perf_counter.h>
#include <lib/slew_rate/SlewRateYaw.hpp>
#include <lib/systemlib/mavlink_log.h>
@ -88,25 +87,26 @@ public:
private:
void Run() override;
Takeoff _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */
TakeoffHandling _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */
orb_advert_t _mavlink_log_pub{nullptr};
uORB::PublicationData<takeoff_status_s> _takeoff_status_pub {ORB_ID(takeoff_status)};
uORB::Publication<vehicle_attitude_setpoint_s> _vehicle_attitude_setpoint_pub {ORB_ID(vehicle_attitude_setpoint)};
uORB::Publication<vehicle_local_position_setpoint_s> _local_pos_sp_pub {ORB_ID(vehicle_local_position_setpoint)}; /**< vehicle local position setpoint publication */
uORB::PublicationData<takeoff_status_s> _takeoff_status_pub{ORB_ID(takeoff_status)};
uORB::Publication<vehicle_attitude_setpoint_s> _vehicle_attitude_setpoint_pub{ORB_ID(vehicle_attitude_setpoint)};
uORB::Publication<vehicle_local_position_setpoint_s> _local_pos_sp_pub{ORB_ID(vehicle_local_position_setpoint)}; /**< vehicle local position setpoint publication */
uORB::SubscriptionCallbackWorkItem _local_pos_sub {this, ORB_ID(vehicle_local_position)}; /**< vehicle local position */
uORB::SubscriptionCallbackWorkItem _local_pos_sub{this, ORB_ID(vehicle_local_position)}; /**< vehicle local position */
uORB::SubscriptionInterval _parameter_update_sub {ORB_ID(parameter_update), 1_s};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _hover_thrust_estimate_sub {ORB_ID(hover_thrust_estimate)};
uORB::Subscription _trajectory_setpoint_sub {ORB_ID(trajectory_setpoint)};
uORB::Subscription _vehicle_constraints_sub {ORB_ID(vehicle_constraints)};
uORB::Subscription _vehicle_control_mode_sub {ORB_ID(vehicle_control_mode)};
uORB::Subscription _vehicle_land_detected_sub {ORB_ID(vehicle_land_detected)};
uORB::Subscription _hover_thrust_estimate_sub{ORB_ID(hover_thrust_estimate)};
uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)};
uORB::Subscription _vehicle_constraints_sub{ORB_ID(vehicle_constraints)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)};
hrt_abstime _time_stamp_last_loop{0}; /**< time stamp of last loop iteration */
hrt_abstime _time_stamp_last_loop{0}; /**< time stamp of last loop iteration */
hrt_abstime _time_position_control_enabled{0};
vehicle_local_position_setpoint_s _setpoint {};
vehicle_control_mode_s _vehicle_control_mode {};
@ -183,22 +183,16 @@ private:
hrt_abstime _last_warn{0}; /**< timer when the last warn message was sent out */
bool _in_failsafe{false}; /**< true if failsafe was entered within current cycle */
bool _hover_thrust_initialized{false};
/** Timeout in us for trajectory data to get considered invalid */
static constexpr uint64_t TRAJECTORY_STREAM_TIMEOUT_US = 500_ms;
/** If Flighttask fails, keep 0.2 seconds the current setpoint before going into failsafe land */
static constexpr uint64_t LOITER_TIME_BEFORE_DESCEND = 200_ms;
/** During smooth-takeoff, below ALTITUDE_THRESHOLD the yaw-control is turned off and tilt is limited */
static constexpr float ALTITUDE_THRESHOLD = 0.3f;
static constexpr float MAX_SAFE_TILT_DEG = 89.f; // Numerical issues above this value due to tanf
systemlib::Hysteresis _failsafe_land_hysteresis{false}; /**< becomes true if task did not update correctly for LOITER_TIME_BEFORE_DESCEND */
SlewRate<float> _tilt_limit_slew_rate;
uint8_t _vxy_reset_counter{0};
@ -222,14 +216,11 @@ private:
PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos);
/**
* Failsafe.
* If flighttask fails for whatever reason, then do failsafe. This could
* occur if the commander fails to switch to a mode in case of invalid states or
* setpoints. The failsafe will occur after LOITER_TIME_BEFORE_DESCEND. If force is set
* to true, the failsafe will be initiated immediately.
* Generate setpoint to bridge no executable setpoint being available.
* Used to handle transitions where no proper setpoint was generated yet and when the received setpoint is invalid.
* This should only happen briefly when transitioning and never during mode operation or by design.
*/
void failsafe(const hrt_abstime &now, vehicle_local_position_setpoint_s &setpoint, const PositionControlStates &states,
bool warn);
vehicle_local_position_setpoint_s generateFailsafeSetpoint(const hrt_abstime &now, const PositionControlStates &states);
/**
* Reset setpoints to NAN

View File

@ -114,7 +114,7 @@ bool PositionControl::update(const float dt)
_yaw_sp = PX4_ISFINITE(_yaw_sp) ? _yaw_sp : _yaw; // TODO: better way to disable yaw control
}
// There has to be a valid output accleration and thrust setpoint otherwise something went wrong
// There has to be a valid output acceleration and thrust setpoint otherwise something went wrong
valid = valid && PX4_ISFINITE(_acc_sp(0)) && PX4_ISFINITE(_acc_sp(1)) && PX4_ISFINITE(_acc_sp(2));
valid = valid && PX4_ISFINITE(_thr_sp(0)) && PX4_ISFINITE(_thr_sp(1)) && PX4_ISFINITE(_thr_sp(2));
@ -246,6 +246,7 @@ void PositionControl::getLocalPositionSetpoint(vehicle_local_position_setpoint_s
local_position_setpoint.vy = _vel_sp(1);
local_position_setpoint.vz = _vel_sp(2);
_acc_sp.copyTo(local_position_setpoint.acceleration);
nans<3, 1>().copyTo(local_position_setpoint.jerk);
_thr_sp.copyTo(local_position_setpoint.thrust);
}

View File

@ -52,7 +52,7 @@ TEST(PositionControlTest, EmptySetpoint)
EXPECT_FLOAT_EQ(output_setpoint.vy, 0.f);
EXPECT_FLOAT_EQ(output_setpoint.vz, 0.f);
EXPECT_EQ(Vector3f(output_setpoint.acceleration), Vector3f(0.f, 0.f, 0.f));
EXPECT_EQ(Vector3f(output_setpoint.jerk), Vector3f(0.f, 0.f, 0.f));
EXPECT_EQ(Vector3f(output_setpoint.jerk), Vector3f(NAN, NAN, NAN));
EXPECT_EQ(Vector3f(output_setpoint.thrust), Vector3f(0, 0, 0));
vehicle_attitude_setpoint_s attitude{};

View File

@ -39,14 +39,14 @@
#include <mathlib/mathlib.h>
#include <lib/geo/geo.h>
void Takeoff::generateInitialRampValue(float velocity_p_gain)
void TakeoffHandling::generateInitialRampValue(float velocity_p_gain)
{
velocity_p_gain = math::max(velocity_p_gain, 0.01f);
_takeoff_ramp_vz_init = -CONSTANTS_ONE_G / velocity_p_gain;
}
void Takeoff::updateTakeoffState(const bool armed, const bool landed, const bool want_takeoff,
const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us)
void TakeoffHandling::updateTakeoffState(const bool armed, const bool landed, const bool want_takeoff,
const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us)
{
_spoolup_time_hysteresis.set_state_and_update(armed, now_us);
@ -109,7 +109,7 @@ void Takeoff::updateTakeoffState(const bool armed, const bool landed, const bool
}
}
float Takeoff::updateRamp(const float dt, const float takeoff_desired_vz)
float TakeoffHandling::updateRamp(const float dt, const float takeoff_desired_vz)
{
float upwards_velocity_limit = takeoff_desired_vz;

View File

@ -53,11 +53,11 @@ enum class TakeoffState {
flight = takeoff_status_s::TAKEOFF_STATE_FLIGHT
};
class Takeoff
class TakeoffHandling
{
public:
Takeoff() = default;
~Takeoff() = default;
TakeoffHandling() = default;
~TakeoffHandling() = default;
// initialize parameters
void setSpoolupTime(const float seconds) { _spoolup_time_hysteresis.set_hysteresis_time_from(false, seconds * 1_s); }

View File

@ -38,13 +38,13 @@
TEST(TakeoffTest, Initialization)
{
Takeoff takeoff;
TakeoffHandling takeoff;
EXPECT_EQ(takeoff.getTakeoffState(), TakeoffState::disarmed);
}
TEST(TakeoffTest, RegularTakeoffRamp)
{
Takeoff takeoff;
TakeoffHandling takeoff;
takeoff.setSpoolupTime(1.f);
takeoff.setTakeoffRampTime(2.0);
takeoff.generateInitialRampValue(CONSTANTS_ONE_G / 0.5f);

View File

@ -39,5 +39,7 @@ px4_add_module(
vtol_type.cpp
tailsitter.cpp
standard.cpp
DEPENDS
SlewRate
)

View File

@ -288,6 +288,10 @@ void Standard::update_transition_state()
}
}
// set spoiler and flaps to 0
_flaps_setpoint_with_slewrate.update(0.f, _dt);
_spoiler_setpoint_with_slewrate.update(0.f, _dt);
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_TO_MC) {
if (_v_control_mode->flag_control_climb_rate_enabled) {
@ -370,8 +374,9 @@ void Standard::fill_actuator_outputs()
fw_out[actuator_controls_s::INDEX_PITCH] = elevon_lock ? 0 : fw_in[actuator_controls_s::INDEX_PITCH];
fw_out[actuator_controls_s::INDEX_YAW] = 0;
fw_out[actuator_controls_s::INDEX_THROTTLE] = _pusher_throttle;
fw_out[actuator_controls_s::INDEX_FLAPS] = 0;
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = 0;
fw_out[actuator_controls_s::INDEX_FLAPS] = _flaps_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_SPOILERS] = _spoiler_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = 0.f;
break;
@ -391,7 +396,8 @@ void Standard::fill_actuator_outputs()
fw_out[actuator_controls_s::INDEX_PITCH] = fw_in[actuator_controls_s::INDEX_PITCH];
fw_out[actuator_controls_s::INDEX_YAW] = fw_in[actuator_controls_s::INDEX_YAW];
fw_out[actuator_controls_s::INDEX_THROTTLE] = _pusher_throttle;
fw_out[actuator_controls_s::INDEX_FLAPS] = fw_in[actuator_controls_s::INDEX_FLAPS];
fw_out[actuator_controls_s::INDEX_FLAPS] = _flaps_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_SPOILERS] = _spoiler_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = _reverse_output;
break;
@ -409,7 +415,8 @@ void Standard::fill_actuator_outputs()
fw_out[actuator_controls_s::INDEX_PITCH] = fw_in[actuator_controls_s::INDEX_PITCH];
fw_out[actuator_controls_s::INDEX_YAW] = fw_in[actuator_controls_s::INDEX_YAW];
fw_out[actuator_controls_s::INDEX_THROTTLE] = fw_in[actuator_controls_s::INDEX_THROTTLE];
fw_out[actuator_controls_s::INDEX_FLAPS] = fw_in[actuator_controls_s::INDEX_FLAPS];
fw_out[actuator_controls_s::INDEX_FLAPS] = _flaps_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_SPOILERS] = _spoiler_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = 0;
break;
}

View File

@ -370,6 +370,10 @@ void Tiltrotor::update_transition_state()
// add minimum throttle for front transition
_thrust_transition = math::max(_thrust_transition, FRONTTRANS_THR_MIN);
// set spoiler and flaps to 0
_flaps_setpoint_with_slewrate.update(0.f, _dt);
_spoiler_setpoint_with_slewrate.update(0.f, _dt);
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_FRONT_P2) {
// the plane is ready to go into fixed wing mode, tilt the rotors forward completely
_tilt_control = math::constrain(_params_tiltrotor.tilt_transition +
@ -392,6 +396,10 @@ void Tiltrotor::update_transition_state()
// if this is not then then there is race condition where the fw rate controller still publishes a zero sample throttle after transition
_v_att_sp->thrust_body[0] = _thrust_transition;
// set spoiler and flaps to 0
_flaps_setpoint_with_slewrate.update(0.f, _dt);
_spoiler_setpoint_with_slewrate.update(0.f, _dt);
} else if (_vtol_schedule.flight_mode == vtol_mode::TRANSITION_BACK) {
// set idle speed for rotary wing mode
@ -531,12 +539,12 @@ void Tiltrotor::fill_actuator_outputs()
}
// Fixed wing output
fw_out[4] = _tilt_control;
fw_out[actuator_controls_s::INDEX_COLLECTIVE_TILT] = _tilt_control;
if (_params->elevons_mc_lock && _vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
fw_out[actuator_controls_s::INDEX_ROLL] = 0;
fw_out[actuator_controls_s::INDEX_PITCH] = 0;
fw_out[actuator_controls_s::INDEX_YAW] = 0;
fw_out[actuator_controls_s::INDEX_ROLL] = 0;
fw_out[actuator_controls_s::INDEX_PITCH] = 0;
fw_out[actuator_controls_s::INDEX_YAW] = 0;
} else {
fw_out[actuator_controls_s::INDEX_ROLL] = fw_in[actuator_controls_s::INDEX_ROLL];
@ -547,6 +555,10 @@ void Tiltrotor::fill_actuator_outputs()
_torque_setpoint_1->xyz[2] = fw_in[actuator_controls_s::INDEX_YAW];
}
fw_out[actuator_controls_s::INDEX_FLAPS] = _flaps_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_SPOILERS] = _spoiler_setpoint_with_slewrate.getState();
fw_out[actuator_controls_s::INDEX_AIRBRAKES] = 0;
_actuators_out_0->timestamp_sample = _actuators_mc_in->timestamp_sample;
_actuators_out_1->timestamp_sample = _actuators_fw_in->timestamp_sample;

View File

@ -109,6 +109,7 @@ VtolAttitudeControl::VtolAttitudeControl() :
_params_handles.land_pitch_min_rad = param_find("VT_LND_PTCH_MIN");
_params_handles.vt_spoiler_mc_ld = param_find("VT_SPOILER_MC_LD");
/* fetch initial parameter values */
parameters_update();
@ -372,6 +373,8 @@ VtolAttitudeControl::parameters_update()
param_get(_params_handles.mpc_land_alt1, &_params.mpc_land_alt1);
param_get(_params_handles.mpc_land_alt2, &_params.mpc_land_alt2);
param_get(_params_handles.vt_spoiler_mc_ld, &_params.vt_spoiler_mc_ld);
// update the parameters of the instances of base VtolType
if (_vtol_type != nullptr) {
_vtol_type->parameters_update();
@ -401,6 +404,7 @@ VtolAttitudeControl::Run()
#endif // !ENABLE_LOCKSTEP_SCHEDULER
const float dt = math::min((now - _last_run_timestamp) / 1e6f, kMaxVTOLAttitudeControlTimeStep);
_last_run_timestamp = now;
if (!_initialized) {
@ -415,6 +419,8 @@ VtolAttitudeControl::Run()
}
}
_vtol_type->setDt(dt);
perf_begin(_loop_perf);
const bool updated_fw_in = _actuator_inputs_fw.update(&_actuators_fw_in);

View File

@ -92,6 +92,8 @@ using namespace time_literals;
extern "C" __EXPORT int vtol_att_control_main(int argc, char *argv[]);
static constexpr float kMaxVTOLAttitudeControlTimeStep = 0.1f; // max time step [s]
class VtolAttitudeControl : public ModuleBase<VtolAttitudeControl>, public px4::WorkItem
{
public:
@ -249,6 +251,7 @@ private:
param_t mpc_land_alt1;
param_t mpc_land_alt2;
param_t sys_ctrl_alloc;
param_t vt_spoiler_mc_ld;
} _params_handles{};
hrt_abstime _last_run_timestamp{0};

View File

@ -384,3 +384,15 @@ PARAM_DEFINE_FLOAT(VT_PTCH_MIN, -5.0f);
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_LND_PTCH_MIN, -5.0f);
/**
* Spoiler setting while landing (hover)
*
* @unit norm
* @min -1
* @max 1
* @decimal 1
* @increment 0.05
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_SPOILER_MC_LD, 0.f);

View File

@ -136,6 +136,9 @@ bool VtolType::init()
}
}
_flaps_setpoint_with_slewrate.setSlewRate(kFlapSlewRateVtol);
_spoiler_setpoint_with_slewrate.setSlewRate(kSpoilerSlewRateVtol);
return true;
}
@ -157,6 +160,16 @@ void VtolType::update_mc_state()
_mc_pitch_weight = 1.0f;
_mc_yaw_weight = 1.0f;
_mc_throttle_weight = 1.0f;
float spoiler_setpoint_hover = 0.f;
if (_attc->get_pos_sp_triplet()->current.valid
&& _attc->get_pos_sp_triplet()->current.type == position_setpoint_s::SETPOINT_TYPE_LAND) {
spoiler_setpoint_hover = _params->vt_spoiler_mc_ld;
}
_spoiler_setpoint_with_slewrate.update(math::constrain(spoiler_setpoint_hover, 0.f, 1.f), _dt);
_flaps_setpoint_with_slewrate.update(0.f, _dt);
}
void VtolType::update_fw_state()
@ -205,6 +218,9 @@ void VtolType::update_fw_state()
}
check_quadchute_condition();
_spoiler_setpoint_with_slewrate.update(_actuators_fw_in->control[actuator_controls_s::INDEX_SPOILERS], _dt);
_flaps_setpoint_with_slewrate.update(_actuators_fw_in->control[actuator_controls_s::INDEX_FLAPS], _dt);
}
void VtolType::update_transition_state()
@ -215,8 +231,6 @@ void VtolType::update_transition_state()
_last_loop_ts = t_now;
_throttle_blend_start_ts = t_now;
check_quadchute_condition();
}

View File

@ -46,6 +46,10 @@
#include <lib/mathlib/mathlib.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include <lib/slew_rate/SlewRate.hpp>
static constexpr float kFlapSlewRateVtol = 1.f; // minimum time from none to full flap deflection [s]
static constexpr float kSpoilerSlewRateVtol = 1.f; // minimum time from none to full spoiler deflection [s]
struct Params {
int32_t ctrl_alloc;
@ -81,6 +85,7 @@ struct Params {
int32_t vt_forward_thrust_enable_mode;
float mpc_land_alt1;
float mpc_land_alt2;
float vt_spoiler_mc_ld;
};
// Has to match 1:1 msg/vtol_vehicle_status.msg
@ -207,6 +212,14 @@ public:
virtual void parameters_update() = 0;
/**
* @brief Set current time delta
*
* @param dt Current time delta [s]
*/
void setDt(float dt) {_dt = dt; }
protected:
VtolAttitudeControl *_attc;
mode _vtol_mode;
@ -292,6 +305,11 @@ public:
float update_and_get_backtransition_pitch_sp();
SlewRate<float> _spoiler_setpoint_with_slewrate;
SlewRate<float> _flaps_setpoint_with_slewrate;
float _dt{0.0025f}; // time step [s]
private: