mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 01:05:21 +03:00
Merge branch 'master' of https://github.com/iNavFlight/inav into BLE
This commit is contained in:
commit
ebf88e1a86
118 changed files with 277 additions and 222 deletions
|
@ -3774,11 +3774,11 @@ If GPS fails wait for this much seconds before switching to emergency landing mo
|
|||
|
||||
### nav_rth_abort_threshold
|
||||
|
||||
RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm]
|
||||
RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. Set to 0 to disable. [cm]
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 50000 | | 65000 |
|
||||
| 50000 | 0 | 65000 |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4712,6 +4712,16 @@ Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, and `HD`
|
|||
|
||||
---
|
||||
|
||||
### output_mode
|
||||
|
||||
Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| AUTO | | |
|
||||
|
||||
---
|
||||
|
||||
### pid_type
|
||||
|
||||
Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`
|
||||
|
|
|
@ -25,31 +25,30 @@ Smartport devices are using _inverted_ serial protocol and as such can not be di
|
|||
|
||||
| CPU family | Direct connection | Receiver _uninverted_ hack | SoftwareSerial | Additional hardware inverter |
|
||||
| ----- | ----- | ----- | ----- | ----- |
|
||||
| STM32F1 | no possible (*) | possible | possible | possible |
|
||||
| STM32F3 | possible | not required | possible | not required |
|
||||
| STM32F4 | not possible (*) | possible | possible | possible |
|
||||
| STM32F7 | possible | not required | possible | not required |
|
||||
| STM32H7 | possible | not required | possible | not required |
|
||||
|
||||
> * possible if flight controller has dedicated, additional, hardware inverter
|
||||
|
||||
Smartport uses _57600bps_ serial speed.
|
||||
|
||||
### Direct connection for F3/F7
|
||||
### Direct connection for F7/H7
|
||||
|
||||
Only TX serial pin has to be connected to Smartport receiver. Disable `telemetry_inverted`.
|
||||
Only TX serial pin has to be connected to Smartport receiver.
|
||||
|
||||
```
|
||||
set telemetry_inverted = OFF
|
||||
set telemetry_uart_unidir = OFF
|
||||
set telemetry_halfduplex = ON
|
||||
```
|
||||
|
||||
### Receiver univerted hack
|
||||
### Receiver uninverted hack
|
||||
|
||||
Some receivers (X4R, XSR and so on) can be hacked to get _uninverted_ Smartport signal. In this case connect uninverted signal to TX pad of chosen serial port and enable `telemetry_inverted`.
|
||||
|
||||
```
|
||||
set telemetry_inverted = ON
|
||||
set telemetry_uart_unidir = OFF
|
||||
set telemetry_halfduplex = ON
|
||||
```
|
||||
|
||||
### Software Serial
|
||||
|
@ -58,9 +57,10 @@ Software emulated serial port allows to connect to Smartport receivers without a
|
|||
|
||||
```
|
||||
set telemetry_inverted = OFF
|
||||
set telemetry_halfduplex = ON
|
||||
```
|
||||
|
||||
If solution above is not working, there is an alternative RX and TX lines have to be bridged using
|
||||
If the solution above is not working, there is an alternative RX and TX lines have to be bridged using
|
||||
1kOhm resistor (confirmed working with 100Ohm, 1kOhm and 10kOhm)
|
||||
|
||||
```
|
||||
|
@ -73,7 +73,7 @@ set telemetry_inverted = OFF
|
|||
|
||||
### SmartPort (S.Port) with external hardware inverter
|
||||
|
||||
It is possible to use DIY UART inverter to connect SmartPort receivers to F1 and F4 based flight controllers. This method does not require hardware hack of S.Port receiver.
|
||||
It is possible to use DIY UART inverter to connect SmartPort receivers to F1 and F4 based flight controllers. This method does not require a hardware hack of S.Port receiver.
|
||||
|
||||
#### SmartPort inverter using bipolar transistors
|
||||

|
||||
|
@ -83,10 +83,10 @@ It is possible to use DIY UART inverter to connect SmartPort receivers to F1 and
|
|||
|
||||
**Warning** Chosen UART has to be 5V tolerant. If not, use 3.3V power supply instead (not tested)
|
||||
|
||||
When external inverter is used, following configuration has to be applied:
|
||||
When the external inverter is used, following configuration has to be applied:
|
||||
|
||||
```
|
||||
set telemetry_uart_unidir = ON
|
||||
set telemetry_halfduplex = OFF
|
||||
set telemetry_inverted = ON
|
||||
```
|
||||
|
||||
|
@ -177,7 +177,7 @@ Use the latest Graupner firmware for your transmitter and receiver.
|
|||
|
||||
Older HoTT transmitters required the EAM and GPS modules to be enabled in the telemetry menu of the transmitter. (e.g. on MX-20)
|
||||
|
||||
You can use a single connection, connect HoTT RX/TX only to serial TX, leave serial RX open and make sure the setting `telemetry_uart_unidir` is OFF.
|
||||
You can use a single connection, connect HoTT RX/TX only to serial TX, leave serial RX open and make sure the setting `telemetry_halfduplex` is OFF.
|
||||
|
||||
The following information is deprecated, use only for compatibility:
|
||||
Serial ports use two wires but HoTT uses a single wire so some electronics are required so that the signals don't get mixed up. The TX and RX pins of
|
||||
|
@ -196,7 +196,7 @@ The diode should be arranged to allow the data signals to flow the right way
|
|||
|
||||
1N4148 diodes have been tested and work with the GR-24.
|
||||
|
||||
When using the diode enable `telemetry_uart_unidir`, go to CLI and type `set telemetry_uart_unidir = ON`, don't forget a `save` afterwards.
|
||||
When using the diode enable `telemetry_halfduplex`, go to CLI and type `set telemetry_halfduplex = ON`, don't forget a `save` afterwards.
|
||||
|
||||
As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which has 5V tolerant digital pins.
|
||||
|
||||
|
|
|
@ -24,7 +24,7 @@ target_stm32f405xg(QUARKVISION HSE_MHZ 16)
|
|||
|
||||
## Hardware names
|
||||
|
||||
As of inav 2.6, the following target hardware platforms are recognised:
|
||||
As of inav 4.1, the following target hardware platforms are recognised:
|
||||
|
||||
* stm32f303xc
|
||||
* stm32f405xg
|
||||
|
@ -34,6 +34,7 @@ As of inav 2.6, the following target hardware platforms are recognised:
|
|||
* stm32f745xg
|
||||
* stm32f765xg
|
||||
* stm32f765xi
|
||||
* stm32h743xi
|
||||
|
||||
The device characteristics for these names may be found at [stm32-base.org](https://stm32-base.org/cheatsheets/linker-memory-regions/).
|
||||
|
||||
|
|
|
@ -86,5 +86,6 @@ typedef enum {
|
|||
DEBUG_AUTOTRIM,
|
||||
DEBUG_AUTOTUNE,
|
||||
DEBUG_RATE_DYNAMICS,
|
||||
DEBUG_LANDING,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -198,13 +198,44 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw)
|
|||
return false;
|
||||
}
|
||||
|
||||
static void timerHardwareOverride(timerHardware_t * timer) {
|
||||
if (mixerConfig()->outputMode == OUTPUT_MODE_SERVOS) {
|
||||
|
||||
//Motors are rewritten as servos
|
||||
if (timer->usageFlags & TIM_USE_MC_MOTOR) {
|
||||
timer->usageFlags = timer->usageFlags & ~TIM_USE_MC_MOTOR;
|
||||
timer->usageFlags = timer->usageFlags | TIM_USE_MC_SERVO;
|
||||
}
|
||||
if (timer->usageFlags & TIM_USE_FW_MOTOR) {
|
||||
timer->usageFlags = timer->usageFlags & ~TIM_USE_FW_MOTOR;
|
||||
timer->usageFlags = timer->usageFlags | TIM_USE_FW_SERVO;
|
||||
}
|
||||
|
||||
} else if (mixerConfig()->outputMode == OUTPUT_MODE_MOTORS) {
|
||||
|
||||
// Servos are rewritten as motors
|
||||
if (timer->usageFlags & TIM_USE_MC_SERVO) {
|
||||
timer->usageFlags = timer->usageFlags & ~TIM_USE_MC_SERVO;
|
||||
timer->usageFlags = timer->usageFlags | TIM_USE_MC_MOTOR;
|
||||
}
|
||||
if (timer->usageFlags & TIM_USE_FW_SERVO) {
|
||||
timer->usageFlags = timer->usageFlags & ~TIM_USE_FW_SERVO;
|
||||
timer->usageFlags = timer->usageFlags | TIM_USE_FW_MOTOR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos)
|
||||
{
|
||||
timOutputs->maxTimMotorCount = 0;
|
||||
timOutputs->maxTimServoCount = 0;
|
||||
|
||||
for (int idx = 0; idx < timerHardwareCount; idx++) {
|
||||
const timerHardware_t *timHw = &timerHardware[idx];
|
||||
|
||||
timerHardware_t *timHw = &timerHardware[idx];
|
||||
|
||||
timerHardwareOverride(timHw);
|
||||
|
||||
int type = MAP_TO_NONE;
|
||||
|
||||
// Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC)
|
||||
|
|
|
@ -136,7 +136,7 @@ extern timHardwareContext_t * timerCtx[HARDWARE_TIMER_DEFINITION_COUNT];
|
|||
extern const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT];
|
||||
|
||||
// Per target timer output definitions
|
||||
extern const timerHardware_t timerHardware[];
|
||||
extern timerHardware_t timerHardware[];
|
||||
extern const int timerHardwareCount;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -932,12 +932,10 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
writeMotors();
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
// Check if landed, FW and MR
|
||||
if (STATE(ALTITUDE_CONTROL)) {
|
||||
updateLandingStatus();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_BLACKBOX
|
||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||
|
|
|
@ -1472,8 +1472,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
|
||||
case MSP2_INAV_OUTPUT_MAPPING:
|
||||
for (uint8_t i = 0; i < timerHardwareCount; ++i)
|
||||
if (!(timerHardware[i].usageFlags & (TIM_USE_PPM | TIM_USE_PWM)))
|
||||
if (!(timerHardware[i].usageFlags & (TIM_USE_PPM | TIM_USE_PWM))) {
|
||||
sbufWriteU8(dst, timerHardware[i].usageFlags);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP2_INAV_MC_BRAKING:
|
||||
|
|
|
@ -96,7 +96,7 @@ tables:
|
|||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
|
||||
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
|
||||
"IRLOCK", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "IMU2", "ALTITUDE",
|
||||
"SMITH_PREDICTOR", "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS"]
|
||||
"SMITH_PREDICTOR", "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING"]
|
||||
- name: async_mode
|
||||
values: ["NONE", "GYRO", "ALL"]
|
||||
- name: aux_operator
|
||||
|
@ -122,7 +122,9 @@ tables:
|
|||
enum: smartportFuelUnit_e
|
||||
- name: platform_type
|
||||
values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
|
||||
enum: flyingPlatformType_e
|
||||
- name: output_mode
|
||||
values: ["AUTO", "MOTORS", "SERVOS"]
|
||||
enum: outputMode_e
|
||||
- name: tz_automatic_dst
|
||||
values: ["OFF", "EU", "USA"]
|
||||
enum: tz_automatic_dst_e
|
||||
|
@ -1262,6 +1264,11 @@ groups:
|
|||
field: appliedMixerPreset
|
||||
min: -1
|
||||
max: INT16_MAX
|
||||
- name: output_mode
|
||||
description: "Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors"
|
||||
default_value: "AUTO"
|
||||
field: outputMode
|
||||
table: output_mode
|
||||
|
||||
- name: PG_REVERSIBLE_MOTORS_CONFIG
|
||||
type: reversibleMotorsConfig_t
|
||||
|
@ -2564,10 +2571,11 @@ groups:
|
|||
field: general.flags.rth_alt_control_override
|
||||
type: bool
|
||||
- name: nav_rth_abort_threshold
|
||||
description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm]"
|
||||
description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. Set to 0 to disable. [cm]"
|
||||
default_value: 50000
|
||||
field: general.rth_abort_threshold
|
||||
max: 65000
|
||||
min: 0
|
||||
- name: nav_max_terrain_follow_alt
|
||||
field: general.max_terrain_follow_altitude
|
||||
default_value: "100"
|
||||
|
|
|
@ -83,13 +83,14 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig,
|
|||
.neutral = SETTING_3D_NEUTRAL_DEFAULT
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 4);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 5);
|
||||
|
||||
PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
|
||||
.motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT,
|
||||
.platformType = SETTING_PLATFORM_TYPE_DEFAULT,
|
||||
.hasFlaps = SETTING_HAS_FLAPS_DEFAULT,
|
||||
.appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only
|
||||
.outputMode = SETTING_OUTPUT_MODE_DEFAULT,
|
||||
);
|
||||
|
||||
#ifdef BRUSHED_MOTORS
|
||||
|
|
|
@ -42,6 +42,13 @@ typedef enum {
|
|||
PLATFORM_OTHER = 6
|
||||
} flyingPlatformType_e;
|
||||
|
||||
|
||||
typedef enum {
|
||||
OUTPUT_MODE_AUTO = 0,
|
||||
OUTPUT_MODE_MOTORS,
|
||||
OUTPUT_MODE_SERVOS
|
||||
} outputMode_e;
|
||||
|
||||
typedef struct motorAxisCorrectionLimits_s {
|
||||
int16_t min;
|
||||
int16_t max;
|
||||
|
@ -62,6 +69,7 @@ typedef struct mixerConfig_s {
|
|||
uint8_t platformType;
|
||||
bool hasFlaps;
|
||||
int16_t appliedMixerPreset;
|
||||
uint8_t outputMode;
|
||||
} mixerConfig_t;
|
||||
|
||||
PG_DECLARE(mixerConfig_t, mixerConfig);
|
||||
|
|
|
@ -254,7 +254,7 @@ static navigationFSMEvent_t nextForNonGeoStates(void);
|
|||
static bool isWaypointMissionValid(void);
|
||||
void missionPlannerSetWaypoint(void);
|
||||
|
||||
void initializeRTHSanityChecker(const fpVector3_t * pos);
|
||||
void initializeRTHSanityChecker(void);
|
||||
bool validateRTHSanityChecker(void);
|
||||
void updateHomePosition(void);
|
||||
bool abortLaunchAllowed(void);
|
||||
|
@ -824,6 +824,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_ERROR] = NAV_STATE_IDLE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE,
|
||||
}
|
||||
},
|
||||
|
@ -841,6 +842,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_FINISHED,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE,
|
||||
}
|
||||
},
|
||||
|
@ -1181,7 +1183,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
|
|||
|
||||
// Initialize RTH sanity check to prevent fly-aways on RTH
|
||||
// For airplanes this is delayed until climb-out is finished
|
||||
initializeRTHSanityChecker(&targetHoldPos);
|
||||
initializeRTHSanityChecker();
|
||||
}
|
||||
|
||||
setDesiredPosition(&targetHoldPos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_HEADING);
|
||||
|
@ -1222,7 +1224,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_CLIMB_TO_SAFE_ALT(n
|
|||
|
||||
// Delayed initialization for RTH sanity check on airplanes - allow to finish climb first as it can take some distance
|
||||
if (STATE(FIXED_WING_LEGACY)) {
|
||||
initializeRTHSanityChecker(&navGetCurrentActualPositionAndVelocity()->pos);
|
||||
initializeRTHSanityChecker();
|
||||
}
|
||||
|
||||
// Save initial home distance for future use
|
||||
|
@ -1791,33 +1793,18 @@ static void navProcessFSMEvents(navigationFSMEvent_t injectedEvent)
|
|||
navigationFSMState_t previousState;
|
||||
static timeMs_t lastStateProcessTime = 0;
|
||||
|
||||
/* If timeout event defined and timeout reached - switch state */
|
||||
if ((navFSM[posControl.navState].timeoutMs > 0) && (navFSM[posControl.navState].onEvent[NAV_FSM_EVENT_TIMEOUT] != NAV_STATE_UNDEFINED) &&
|
||||
((currentMillis - lastStateProcessTime) >= navFSM[posControl.navState].timeoutMs)) {
|
||||
/* Update state */
|
||||
previousState = navSetNewFSMState(navFSM[posControl.navState].onEvent[NAV_FSM_EVENT_TIMEOUT]);
|
||||
|
||||
/* Call new state's entry function */
|
||||
while (navFSM[posControl.navState].onEntry) {
|
||||
navigationFSMEvent_t newEvent = navFSM[posControl.navState].onEntry(previousState);
|
||||
|
||||
if ((newEvent != NAV_FSM_EVENT_NONE) && (navFSM[posControl.navState].onEvent[newEvent] != NAV_STATE_UNDEFINED)) {
|
||||
previousState = navSetNewFSMState(navFSM[posControl.navState].onEvent[newEvent]);
|
||||
}
|
||||
else {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
lastStateProcessTime = currentMillis;
|
||||
}
|
||||
|
||||
/* Inject new event */
|
||||
/* Process new injected event if event defined,
|
||||
* otherwise process timeout event if defined */
|
||||
if (injectedEvent != NAV_FSM_EVENT_NONE && navFSM[posControl.navState].onEvent[injectedEvent] != NAV_STATE_UNDEFINED) {
|
||||
/* Update state */
|
||||
previousState = navSetNewFSMState(navFSM[posControl.navState].onEvent[injectedEvent]);
|
||||
} else if ((navFSM[posControl.navState].timeoutMs > 0) && (navFSM[posControl.navState].onEvent[NAV_FSM_EVENT_TIMEOUT] != NAV_STATE_UNDEFINED) &&
|
||||
((currentMillis - lastStateProcessTime) >= navFSM[posControl.navState].timeoutMs)) {
|
||||
/* Update state */
|
||||
previousState = navSetNewFSMState(navFSM[posControl.navState].onEvent[NAV_FSM_EVENT_TIMEOUT]);
|
||||
}
|
||||
|
||||
/* Call new state's entry function */
|
||||
if (previousState) { /* If state updated call new state's entry function */
|
||||
while (navFSM[posControl.navState].onEntry) {
|
||||
navigationFSMEvent_t newEvent = navFSM[posControl.navState].onEntry(previousState);
|
||||
|
||||
|
@ -2243,21 +2230,20 @@ static void updateDesiredRTHAltitude(void)
|
|||
/*-----------------------------------------------------------
|
||||
* RTH sanity test logic
|
||||
*-----------------------------------------------------------*/
|
||||
void initializeRTHSanityChecker(const fpVector3_t * pos)
|
||||
void initializeRTHSanityChecker(void)
|
||||
{
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
|
||||
posControl.rthSanityChecker.lastCheckTime = currentTimeMs;
|
||||
posControl.rthSanityChecker.initialPosition = *pos;
|
||||
posControl.rthSanityChecker.rthSanityOK = true;
|
||||
posControl.rthSanityChecker.minimalDistanceToHome = calculateDistanceToDestination(&posControl.rthState.homePosition.pos);
|
||||
}
|
||||
|
||||
bool validateRTHSanityChecker(void)
|
||||
{
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
bool checkResult = true; // Between the checks return the "good" status
|
||||
|
||||
// Ability to disable this
|
||||
// Ability to disable sanity checker
|
||||
if (navConfig()->general.rth_abort_threshold == 0) {
|
||||
return true;
|
||||
}
|
||||
|
@ -2265,19 +2251,17 @@ bool validateRTHSanityChecker(void)
|
|||
// Check at 10Hz rate
|
||||
if ((currentTimeMs - posControl.rthSanityChecker.lastCheckTime) > 100) {
|
||||
const float currentDistanceToHome = calculateDistanceToDestination(&posControl.rthState.homePosition.pos);
|
||||
posControl.rthSanityChecker.lastCheckTime = currentTimeMs;
|
||||
|
||||
if (currentDistanceToHome < posControl.rthSanityChecker.minimalDistanceToHome) {
|
||||
posControl.rthSanityChecker.minimalDistanceToHome = currentDistanceToHome;
|
||||
}
|
||||
else if ((currentDistanceToHome - posControl.rthSanityChecker.minimalDistanceToHome) > navConfig()->general.rth_abort_threshold) {
|
||||
} else {
|
||||
// If while doing RTH we got even farther away from home - RTH is doing something crazy
|
||||
checkResult = false;
|
||||
posControl.rthSanityChecker.rthSanityOK = (currentDistanceToHome - posControl.rthSanityChecker.minimalDistanceToHome) < navConfig()->general.rth_abort_threshold;
|
||||
}
|
||||
}
|
||||
|
||||
posControl.rthSanityChecker.lastCheckTime = currentTimeMs;
|
||||
}
|
||||
|
||||
return checkResult;
|
||||
return posControl.rthSanityChecker.rthSanityOK;
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
|
@ -2601,6 +2585,9 @@ void updateLandingStatus(void)
|
|||
|
||||
static bool landingDetectorIsActive;
|
||||
|
||||
DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive);
|
||||
DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED));
|
||||
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
resetLandingDetector();
|
||||
landingDetectorIsActive = false;
|
||||
|
@ -3343,18 +3330,21 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
|
|||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||
}
|
||||
|
||||
/* Keep Emergency landing mode active once triggered. Is cancelled when landing in progress if position sensors working again.
|
||||
* If failsafe not active landing also cancelled if WP or RTH deselected or if Manual or Althold modes selected.
|
||||
* Remains active if landing finished regardless of sensor status or flight mode selection */
|
||||
bool autonomousNavNotPossible = !(canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME));
|
||||
bool emergLandingCancel = IS_RC_MODE_ACTIVE(BOXMANUAL) || (IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) && canActivateAltHold) ||
|
||||
!(IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVRTH));
|
||||
|
||||
/* Keep Emergency landing mode active once triggered.
|
||||
* If caused by sensor failure - landing auto cancelled if sensors working again or when WP and RTH deselected or if Althold selected.
|
||||
* If caused by RTH Sanity Checking - landing cancelled if RTH deselected.
|
||||
* Remains active if failsafe active regardless of mode selections */
|
||||
if (navigationIsExecutingAnEmergencyLanding()) {
|
||||
if (autonomousNavNotPossible && (!emergLandingCancel || FLIGHT_MODE(FAILSAFE_MODE))) {
|
||||
bool autonomousNavIsPossible = canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME);
|
||||
bool emergLandingCancel = (!autonomousNavIsPossible &&
|
||||
((IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) && canActivateAltHold) || !(IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVRTH)))) ||
|
||||
(autonomousNavIsPossible && !IS_RC_MODE_ACTIVE(BOXNAVRTH));
|
||||
|
||||
if ((!posControl.rthSanityChecker.rthSanityOK || !autonomousNavIsPossible) && (!emergLandingCancel || FLIGHT_MODE(FAILSAFE_MODE))) {
|
||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||
}
|
||||
}
|
||||
posControl.rthSanityChecker.rthSanityOK = true;
|
||||
|
||||
// Keep canActivateWaypoint flag at FALSE if there is no mission loaded
|
||||
// Also block WP mission if we are executing RTH
|
||||
|
|
|
@ -612,6 +612,7 @@ bool isFixedWingFlying(void)
|
|||
*-----------------------------------------------------------*/
|
||||
bool isFixedWingLandingDetected(void)
|
||||
{
|
||||
DEBUG_SET(DEBUG_LANDING, 4, 0);
|
||||
static bool fixAxisCheck = false;
|
||||
const bool throttleIsLow = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW;
|
||||
|
||||
|
@ -623,6 +624,7 @@ bool isFixedWingLandingDetected(void)
|
|||
if (!startCondition || posControl.flags.resetLandingDetector) {
|
||||
return fixAxisCheck = posControl.flags.resetLandingDetector = false;
|
||||
}
|
||||
DEBUG_SET(DEBUG_LANDING, 4, 1);
|
||||
|
||||
static timeMs_t fwLandingTimerStartAt;
|
||||
static int16_t fwLandSetRollDatum;
|
||||
|
@ -634,8 +636,12 @@ bool isFixedWingLandingDetected(void)
|
|||
bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < 50.0f && posControl.actualState.velXY < 100.0f;
|
||||
// Check angular rates are low (degs/s)
|
||||
bool gyroCondition = averageAbsGyroRates() < 2.0f;
|
||||
DEBUG_SET(DEBUG_LANDING, 2, velCondition);
|
||||
DEBUG_SET(DEBUG_LANDING, 3, gyroCondition);
|
||||
|
||||
if (velCondition && gyroCondition){
|
||||
DEBUG_SET(DEBUG_LANDING, 4, 2);
|
||||
DEBUG_SET(DEBUG_LANDING, 5, fixAxisCheck);
|
||||
if (!fixAxisCheck) { // capture roll and pitch angles to be used as datums to check for absolute change
|
||||
fwLandSetRollDatum = attitude.values.roll; //0.1 deg increments
|
||||
fwLandSetPitchDatum = attitude.values.pitch;
|
||||
|
@ -644,6 +650,8 @@ bool isFixedWingLandingDetected(void)
|
|||
} else {
|
||||
bool isRollAxisStatic = ABS(fwLandSetRollDatum - attitude.values.roll) < 5;
|
||||
bool isPitchAxisStatic = ABS(fwLandSetPitchDatum - attitude.values.pitch) < 5;
|
||||
DEBUG_SET(DEBUG_LANDING, 6, isRollAxisStatic);
|
||||
DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic);
|
||||
if (isRollAxisStatic && isPitchAxisStatic) {
|
||||
// Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch
|
||||
timeMs_t safetyTimeDelay = 2000 + navConfig()->fw.auto_disarm_delay;
|
||||
|
|
|
@ -66,17 +66,13 @@ static sqrt_controller_t alt_hold_sqrt_controller;
|
|||
// Position to velocity controller for Z axis
|
||||
static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros)
|
||||
{
|
||||
float pos_desired_z = posControl.desiredState.pos.z;
|
||||
|
||||
float targetVel = sqrtControllerApply(
|
||||
&alt_hold_sqrt_controller,
|
||||
&pos_desired_z,
|
||||
posControl.desiredState.pos.z,
|
||||
navGetCurrentActualPositionAndVelocity()->pos.z,
|
||||
US2S(deltaMicros)
|
||||
);
|
||||
|
||||
posControl.desiredState.pos.z = pos_desired_z;
|
||||
|
||||
// hard limit desired target velocity to max_climb_rate
|
||||
float vel_max_z = 0.0f;
|
||||
|
||||
|
@ -726,6 +722,7 @@ bool isMulticopterFlying(void)
|
|||
*-----------------------------------------------------------*/
|
||||
bool isMulticopterLandingDetected(void)
|
||||
{
|
||||
DEBUG_SET(DEBUG_LANDING, 4, 0);
|
||||
static timeUs_t landingDetectorStartedAt;
|
||||
const bool throttleIsLow = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW;
|
||||
|
||||
|
@ -745,6 +742,8 @@ bool isMulticopterLandingDetected(void)
|
|||
posControl.actualState.velXY < MC_LAND_CHECK_VEL_XY_MOVING;
|
||||
// check gyro rates are low (degs/s)
|
||||
bool gyroCondition = averageAbsGyroRates() < 2.0f;
|
||||
DEBUG_SET(DEBUG_LANDING, 2, velCondition);
|
||||
DEBUG_SET(DEBUG_LANDING, 3, gyroCondition);
|
||||
|
||||
bool possibleLandingDetected = false;
|
||||
const timeUs_t currentTimeUs = micros();
|
||||
|
@ -753,6 +752,7 @@ bool isMulticopterLandingDetected(void)
|
|||
// We have likely landed if throttle is 40 units below average descend throttle
|
||||
// We use rcCommandAdjustedThrottle to keep track of NAV corrected throttle (isLandingDetected is executed
|
||||
// from processRx() and rcCommand at that moment holds rc input, not adjusted values from NAV core)
|
||||
DEBUG_SET(DEBUG_LANDING, 4, 1);
|
||||
|
||||
static int32_t landingThrSum;
|
||||
static int32_t landingThrSamples;
|
||||
|
@ -774,7 +774,11 @@ bool isMulticopterLandingDetected(void)
|
|||
isAtMinimalThrust = rcCommandAdjustedThrottle < (landingThrSum / landingThrSamples - MC_LAND_DESCEND_THROTTLE);
|
||||
|
||||
possibleLandingDetected = isAtMinimalThrust && velCondition;
|
||||
|
||||
DEBUG_SET(DEBUG_LANDING, 6, rcCommandAdjustedThrottle);
|
||||
DEBUG_SET(DEBUG_LANDING, 7, landingThrSum / landingThrSamples - MC_LAND_DESCEND_THROTTLE);
|
||||
} else { // non autonomous and emergency landing
|
||||
DEBUG_SET(DEBUG_LANDING, 4, 2);
|
||||
if (landingDetectorStartedAt) {
|
||||
possibleLandingDetected = velCondition && gyroCondition;
|
||||
} else {
|
||||
|
@ -790,6 +794,7 @@ bool isMulticopterLandingDetected(void)
|
|||
// surfaceMin is our ground reference. If we are less than 5cm above the ground - we are likely landed
|
||||
possibleLandingDetected = possibleLandingDetected && (posControl.actualState.agl.pos.z <= (posControl.actualState.surfaceMin + MC_LAND_SAFE_SURFACE));
|
||||
}
|
||||
DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected);
|
||||
|
||||
if (possibleLandingDetected) {
|
||||
timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->mc.auto_disarm_delay); // check conditions stable for 2s + optional extra delay
|
||||
|
|
|
@ -303,7 +303,7 @@ typedef struct {
|
|||
|
||||
typedef struct {
|
||||
timeMs_t lastCheckTime;
|
||||
fpVector3_t initialPosition;
|
||||
bool rthSanityOK;
|
||||
float minimalDistanceToHome;
|
||||
} rthSanityChecker_t;
|
||||
|
||||
|
|
|
@ -25,7 +25,12 @@
|
|||
|
||||
#include "navigation/sqrt_controller.h"
|
||||
|
||||
// inverse of the sqrt controller. Calculates the input (aka error) to the sqrt_controller required to achieve a given output
|
||||
/*
|
||||
Square Root Controller calculates the correction based on a proportional controller (kP).
|
||||
Used only in AutoPilot System for Vertical (Z) control.
|
||||
*/
|
||||
|
||||
// Inverse of the sqrt controller. Calculates the input (aka error) to the sqrt_controller required to achieve a given output
|
||||
static float sqrtControllerInverse(float kp, float derivative_max, float output)
|
||||
{
|
||||
if ((derivative_max > 0.0f) && (kp == 0.0f)) {
|
||||
|
@ -40,11 +45,11 @@ static float sqrtControllerInverse(float kp, float derivative_max, float output)
|
|||
return 0.0f;
|
||||
}
|
||||
|
||||
// calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
|
||||
// Calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
|
||||
const float linear_velocity = derivative_max / kp;
|
||||
|
||||
if (fabsf(output) < linear_velocity) {
|
||||
// if our current velocity is below the cross-over point we use a linear function
|
||||
// If our current velocity is below the cross-over point we use a linear function
|
||||
return output / kp;
|
||||
}
|
||||
|
||||
|
@ -53,33 +58,25 @@ static float sqrtControllerInverse(float kp, float derivative_max, float output)
|
|||
return (output > 0.0f) ? stopping_dist : -stopping_dist;
|
||||
}
|
||||
|
||||
// proportional controller with piecewise sqrt sections to constrainf second derivative
|
||||
float sqrtControllerApply(sqrt_controller_t *sqrt_controller_pointer, float *target, float measurement, float deltaTime)
|
||||
// Proportional controller with piecewise sqrt sections to constrain derivative
|
||||
float sqrtControllerApply(sqrt_controller_t *sqrt_controller_pointer, float target, float measurement, float deltaTime)
|
||||
{
|
||||
|
||||
// In case kP is zero, we can't calculate the error, so we return 0.
|
||||
if (sqrt_controller_pointer->kp == 0.0f) {
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
float correction_rate;
|
||||
|
||||
// calculate distance p_error
|
||||
sqrt_controller_pointer->error = *target - measurement;
|
||||
// Calculate distance error
|
||||
sqrt_controller_pointer->error = target - measurement;
|
||||
|
||||
if ((sqrt_controller_pointer->error_min < 0.0f) && (sqrt_controller_pointer->error < sqrt_controller_pointer->error_min)) {
|
||||
sqrt_controller_pointer->error = sqrt_controller_pointer->error_min;
|
||||
*target = measurement + sqrt_controller_pointer->error;
|
||||
} else if ((sqrt_controller_pointer->error_max > 0.0f) && (sqrt_controller_pointer->error > sqrt_controller_pointer->error_max)) {
|
||||
sqrt_controller_pointer->error = sqrt_controller_pointer->error_max;
|
||||
*target = measurement + sqrt_controller_pointer->error;
|
||||
}
|
||||
|
||||
if ((sqrt_controller_pointer->derivative_max < 0.0f) || sqrt_controller_pointer->derivative_max == 0.0f) {
|
||||
// second order limit is zero or negative.
|
||||
// Derivative Max is zero or negative.
|
||||
correction_rate = sqrt_controller_pointer->error * sqrt_controller_pointer->kp;
|
||||
} else if (sqrt_controller_pointer->kp == 0.0f) {
|
||||
// P term is zero but we have a second order limit.
|
||||
// Proportional term is zero but we have a Derivative Max.
|
||||
if (sqrt_controller_pointer->error > 0.0f) {
|
||||
correction_rate = fast_fsqrtf(2.0f * sqrt_controller_pointer->derivative_max * (sqrt_controller_pointer->error));
|
||||
} else if (sqrt_controller_pointer->error < 0.0f) {
|
||||
|
@ -88,7 +85,7 @@ float sqrtControllerApply(sqrt_controller_t *sqrt_controller_pointer, float *tar
|
|||
correction_rate = 0.0f;
|
||||
}
|
||||
} else {
|
||||
// Both the P and second order limit have been defined.
|
||||
// Both the Proportional and Derivative Max have been defined.
|
||||
const float linear_dist = sqrt_controller_pointer->derivative_max / sq(sqrt_controller_pointer->kp);
|
||||
if (sqrt_controller_pointer->error > linear_dist) {
|
||||
correction_rate = fast_fsqrtf(2.0f * sqrt_controller_pointer->derivative_max * (sqrt_controller_pointer->error - (linear_dist / 2.0f)));
|
||||
|
@ -100,25 +97,19 @@ float sqrtControllerApply(sqrt_controller_t *sqrt_controller_pointer, float *tar
|
|||
}
|
||||
|
||||
if (deltaTime != 0.0f) {
|
||||
// this ensures we do not get small oscillations by over shooting the error correction in the last time step.
|
||||
// This ensures we do not get small oscillations by over shooting the error correction in the last time step.
|
||||
return constrainf(correction_rate, -fabsf(sqrt_controller_pointer->error) / deltaTime, fabsf(sqrt_controller_pointer->error) / deltaTime);
|
||||
}
|
||||
|
||||
return correction_rate;
|
||||
}
|
||||
|
||||
// sets the maximum error to limit output and first and second derivative of output
|
||||
void sqrtControllerInit(
|
||||
sqrt_controller_t *sqrt_controller_pointer,
|
||||
const float kp,
|
||||
const float output_min,
|
||||
const float output_max,
|
||||
const float derivative_out_max
|
||||
)
|
||||
// Sets the maximum error to limit output and derivative of output
|
||||
void sqrtControllerInit(sqrt_controller_t *sqrt_controller_pointer,const float kp,const float output_min,const float output_max,const float derivative_out_max)
|
||||
{
|
||||
// reset the variables
|
||||
sqrt_controller_pointer->kp = kp;
|
||||
|
||||
// Reset the variables
|
||||
sqrt_controller_pointer->kp = kp;
|
||||
sqrt_controller_pointer->derivative_max = 0.0f;
|
||||
sqrt_controller_pointer->error_min = 0.0f;
|
||||
sqrt_controller_pointer->error_max = 0.0f;
|
||||
|
@ -127,7 +118,7 @@ void sqrtControllerInit(
|
|||
sqrt_controller_pointer->derivative_max = derivative_out_max;
|
||||
}
|
||||
|
||||
if ((output_min > 0.0f) && (sqrt_controller_pointer->kp > 0.0f)) {
|
||||
if ((output_min < 0.0f) && (sqrt_controller_pointer->kp > 0.0f)) {
|
||||
sqrt_controller_pointer->error_min = sqrtControllerInverse(sqrt_controller_pointer->kp, sqrt_controller_pointer->derivative_max, output_min);
|
||||
}
|
||||
|
||||
|
|
|
@ -25,11 +25,5 @@ typedef struct sqrt_controller_s {
|
|||
float derivative_max; // maximum derivative of output
|
||||
} sqrt_controller_t;
|
||||
|
||||
float sqrtControllerApply(sqrt_controller_t *sqrt_controller_pointer, float *target, float measurement, float deltaTime);
|
||||
void sqrtControllerInit(
|
||||
sqrt_controller_t *sqrt_controller_pointer,
|
||||
const float kp,
|
||||
const float output_min,
|
||||
const float output_max,
|
||||
const float derivative_out_max
|
||||
);
|
||||
float sqrtControllerApply(sqrt_controller_t *sqrt_controller_pointer, float target, float measurement, float deltaTime);
|
||||
void sqrtControllerInit(sqrt_controller_t *sqrt_controller_pointer, const float kp, const float output_min, const float output_max, const float derivative_out_max);
|
|
@ -27,7 +27,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM2, CH2, PB3, TIM_USE_CAMERA_CONTROL, 0, 0), // There is not camera control in INAV
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D1_ST6
|
||||
|
|
|
@ -41,7 +41,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6000, DEVHW_MPU6000, GYRO_1_SPI_BUS,
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6500, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_1_ALIGN);
|
||||
#endif
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // Cam control, SS, UNUSED
|
||||
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0),
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0),
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// up to 10 Motor Outputs
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PB15 - NONE
|
||||
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PB14 - DMA1_CH5
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_SERVO, 0, 0), // PWM1 - DMA2_ST2
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_SERVO, 0, 0), // PWM2 - DMA1_ST5
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
|
||||
|
|
|
@ -141,8 +141,6 @@
|
|||
|
||||
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
||||
|
||||
#define NAV_GPS_GLITCH_DETECTION
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define TIM_EN TIMER_OUTPUT_ENABLED
|
||||
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // PPM - timer clash with SS1_TX
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1, 1), // M1 - D(2, 4, 7)
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // PPM - timer clash with SS1_TX
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1, 0), // M1 - D(2, 4, 7)
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
|
||||
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 - DMAR: DMA2_ST5
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0), // PPM DMA(1,4)
|
||||
|
||||
// Motors 1-4
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
/*#include "drivers/dma.h"*/
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
// Motors
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S1 D(1, 4, 5)
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0),
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0),
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S2_IN
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S3_IN
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PWM1 - PA8
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PC6
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PC7
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S1 (1,7)
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
#define TIM_EN TIMER_OUTPUT_ENABLED
|
||||
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM ,0, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR,0,0), //S1 DMA2_ST2 T8CH1
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // S1_IN
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_PWM, 0, 0), // S2_IN
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// MOTOR outputs
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR, 1),
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR, 1),
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0),
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0),
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0 ), // S1_OUT - DMA1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0 ), // S2_OUT - DMA1_ST2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1 ), // S3_OUT - DMA1_ST6
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
#define TIM_EN TIMER_OUTPUT_ENABLED
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
#if defined(FF_PIKOF4OSD)
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ),
|
||||
DEF_TIM(TIM3, CH3, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ),
|
||||
|
|
|
@ -43,7 +43,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_1_mpu6500, DEVHW_MPU6500, IMU_1_SPI_BUS, IMU_
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6000, DEVHW_MPU6000, IMU_2_SPI_BUS, IMU_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6500, DEVHW_MPU6500, IMU_2_SPI_BUS, IMU_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
// Motor output 1: use different set of timers for MC and FW
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0 ),
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0 ),
|
||||
|
|
|
@ -150,7 +150,6 @@
|
|||
// #define USE_RANGEFINDER_SRF10
|
||||
|
||||
// *************** NAV *****************************
|
||||
#define NAV_GPS_GLITCH_DETECTION
|
||||
#define NAV_MAX_WAYPOINTS 60
|
||||
|
||||
// *************** Others *****************************
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN
|
||||
#ifdef FLYWOOF411_V2
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - D(2,1)
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#include "drivers/bus.h"
|
||||
#include "drivers/pinio.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7
|
||||
|
|
|
@ -37,7 +37,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_1, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_2, DEVHW_MPU6000, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, GYRO_2_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_2_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, GYRO_2_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_2_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS
|
||||
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - D(1,2)
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 (1,7)
|
||||
|
|
|
@ -28,7 +28,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS,
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||
#endif
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
|
||||
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - D(2, 1, 6)
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP - D(2, 6, 0)
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1
|
||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1_OUT
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2_OUT
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S3_OUT
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S2
|
||||
DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), // M1
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0), // M2
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR, 0, 0), // M3
|
||||
|
|
|
@ -7,7 +7,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_PPM, 0), // PPM IN
|
||||
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0),
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1_OUT - D(1, 6, 3)
|
||||
|
|
|
@ -34,8 +34,9 @@
|
|||
#include "drivers/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5)
|
||||
|
|
|
@ -51,6 +51,12 @@
|
|||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
|
||||
#define USE_IMU_BMI270
|
||||
#define IMU_BMI270_ALIGN CW180_DEG_FLIP
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
#define BMI270_CS_PIN PB2
|
||||
#define BMI270_EXTI_PIN PC4
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0),
|
||||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0),
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6500_0_CS_PIN, MPU6500_0_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_0_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, MPU6500_1_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_1_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
// Motors
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6500_0_CS_PIN, MPU6500_0_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_0_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, MPU6500_1_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_1_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 DMA1_S2_CH5
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 DMA1_S7_CH5
|
||||
|
||||
|
|
|
@ -36,6 +36,11 @@
|
|||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define GYRO_INT_EXTI PC4
|
||||
|
||||
#define USE_IMU_BMI270
|
||||
#define IMU_BMI270_ALIGN CW0_DEG
|
||||
#define BMI270_CS_PIN PA4
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG
|
||||
#define MPU6000_CS_PIN PA4
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT - DMA1_ST7
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include "drivers/pinio.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
|
||||
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN
|
||||
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR, 0, 0), // PWM4
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PWM1 - PA8
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PC6
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
#ifdef MAMBAF405US_I2C
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7)
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
#ifdef MATEKF405_SERVOS6
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S1 D(2,2,7)
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S2 D(2,3,7)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S3 D(2,4,7)
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1 D(1,3,2)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2 D(1,0,2)
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
|
||||
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5)
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,5,5)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 D(2,1,6)
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1, 4, 5)
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP2-1 D(2, 4, 7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP2-1 D(2, 7, 7)
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5)
|
||||
|
|
|
@ -33,7 +33,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_SPI_BUS,
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_imu3, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||
#endif
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP(1,7), D(1,5,3)
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP(1,7), D(1,6,3)
|
||||
|
||||
|
|
|
@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU600
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_imu2, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 2, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PA4 - *TIM3_CH2
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_PPM, 0, 0), //PPM
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), //2812LED
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
// PWM1 PPM Pad
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0), // PPM - PB4
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
|
||||
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), // S2_IN
|
||||
|
|
|
@ -34,7 +34,7 @@ BUSDEV_REGISTER_I2C( busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS, 0x0E
|
|||
|
||||
BUSDEV_REGISTER_SPI( busdev_max7456, DEVHW_MAX7456, MAX7456_SPI_BUS, MAX7456_CS_PIN, NONE, DEVFLAGS_USE_RAW_REGISTERS, 0);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0, 0 ), // UART2_RX, joined with PE13
|
||||
// DEF_TIM(TIM1, CH3, PE13, TIM_USE_NONE, 0, 0 ), // RC1 / PPM, unusable
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM / UART1_RX
|
||||
|
||||
// OUTPUT 1-4
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
|
||||
DEF_TIM(TIM3, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0),
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0),
|
||||
|
|
|
@ -36,7 +36,7 @@ BUSDEV_REGISTER_I2C_TAG(busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS,
|
|||
// PixRacer has built-in HMC5983 compass on the same SPI bus as MPU9250
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_hmc5983_spi, DEVHW_HMC5883, MPU9250_SPI_BUS, PE15, NONE, 1, DEVFLAGS_NONE, 0);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, 0, 0 ), // PPM shared uart6 pc7
|
||||
|
||||
DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S1_OUT
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/timer.h"
|
||||
|
||||
/* TIMERS */
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PPM, 0, 0), // PPM In
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR, 0, 0), // S2
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PA8
|
||||
DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0), // PWM2 - PA7
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PB0
|
||||
|
|
|
@ -33,7 +33,7 @@ BUSDEV_REGISTER_I2C_TAG(busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS_EXT,
|
|||
|
||||
|
||||
/* TIMERS */
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D1_ST6
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP2-1 D(2, 4, 7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP2-1 D(2, 7, 7)
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue