1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

Merge branch 'master' into abo_wp_mission_flight_select

This commit is contained in:
breadoven 2022-09-18 08:33:48 +01:00 committed by GitHub
commit 19918ee261
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
45 changed files with 973 additions and 243 deletions

View file

@ -2,7 +2,9 @@ FROM ubuntu:focal
ENV DEBIAN_FRONTEND noninteractive ENV DEBIAN_FRONTEND noninteractive
RUN apt-get update && apt-get install -y git cmake make ruby gcc RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip
RUN pip install pyyaml
RUN useradd inav RUN useradd inav

3
cmake/docker_docs.sh Normal file
View file

@ -0,0 +1,3 @@
#!/bin/bash
cd /src/
python3 src/utils/update_cli_docs.py

View file

@ -77,13 +77,24 @@ Parameters:
* `<lon>` - Longitude. * `<lon>` - Longitude.
* `<alt>` - Altitude in cm. * `<alt>` - Altitude in cm. See `p3` bit 0 for datum definition.
* `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI. * `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI.
* `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP. * `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP.
* `<p3>` - Reserved for future use. If `p2` is provided, then `p3` is also required. * `<p3>` - A bitfield with four bits reserved for user specified actions. It is anticipated that these actions will be exposed through the logic conditions.
* Bit 0 - Altitude (`alt`) : Relative (to home altitude) (0) or Absolute (AMSL) (1).
* Bit 1 - WP Action 1
* Bit 2 - WP Action 2
* Bit 3 - WP Action 3
* Bit 4 - WP Action 4
* Bits 5 - 15 : undefined / reserved.
Note:
* If `p2` is specified, then `p3` is also required.
* `p3` is only defined for navigable WP types (WAYPOINT, POSHOLD_TIME, LAND). The affect of specifying a non-zero `p3` for other WP types is undefined.
* `<flag>` - Last waypoint must have `flag` set to 165 (0xA5). * `<flag>` - Last waypoint must have `flag` set to 165 (0xA5).
@ -116,7 +127,8 @@ wp 59 0 0 0 0 0 0 0 0
Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers. Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers.
**Multi-missions**\ ## Multi-missions
Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command. Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command.
E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0). E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0).
@ -156,4 +168,4 @@ wp 11 0 0 0 0 0 0 0 0
wp 12 0 0 0 0 0 0 0 0 wp 12 0 0 0 0 0 0 0 0
... ...
wp 59 0 0 0 0 0 0 0 0 wp 59 0 0 0 0 0 0 0 0
``` ```

View file

@ -902,13 +902,13 @@ What failsafe procedure to initiate in Stage 2 when craft is closer to home than
--- ---
### failsafe_mission ### failsafe_mission_delay
If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end.
| Default | Min | Max | | Default | Min | Max |
| --- | --- | --- | | --- | --- | --- |
| ON | OFF | ON | | 0 | -1 | 600 |
--- ---

View file

@ -39,4 +39,6 @@ You'll have to manually execute the same steps that the build script does:
+ Where `<PATH_TO_REPO>` must be replaced with the absolute path of where you cloned this repo (see above), and `<TARGET>` with the name of the target that you want to build. + Where `<PATH_TO_REPO>` must be replaced with the absolute path of where you cloned this repo (see above), and `<TARGET>` with the name of the target that you want to build.
+ Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image. + Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image.
Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details. 3. If you need to update `Settings.md`, run `docker run --entrypoint /src/cmake/docker_docs.sh --rm -it -u root -v <PATH_TO_REPO>:/src inav-build`
Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details.

View file

@ -302,8 +302,6 @@ main_sources(COMMON_SRC
flight/failsafe.c flight/failsafe.c
flight/failsafe.h flight/failsafe.h
flight/hil.c
flight/hil.h
flight/imu.c flight/imu.c
flight/imu.h flight/imu.h
flight/kalman.c flight/kalman.c

View file

@ -191,7 +191,7 @@ static const OSD_Entry cmsx_menuMissionSettingsEntries[] =
OSD_LABEL_ENTRY("-- MISSIONS --"), OSD_LABEL_ENTRY("-- MISSIONS --"),
OSD_SETTING_ENTRY("MC WP SLOWDOWN", SETTING_NAV_MC_WP_SLOWDOWN), OSD_SETTING_ENTRY("MC WP SLOWDOWN", SETTING_NAV_MC_WP_SLOWDOWN),
OSD_SETTING_ENTRY("MISSION FAILSAFE", SETTING_FAILSAFE_MISSION), OSD_SETTING_ENTRY("WP FAILSAFE DELAY", SETTING_FAILSAFE_MISSION_DELAY),
OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT), OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT),
OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS), OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS),
OSD_SETTING_ENTRY("WP ENFORCE ALTITUDE", SETTING_NAV_WP_ENFORCE_ALTITUDE), OSD_SETTING_ENTRY("WP ENFORCE ALTITUDE", SETTING_NAV_WP_ENFORCE_ALTITUDE),

View file

@ -389,7 +389,7 @@ static bool emergencyArmingIsEnabled(void)
return emergencyArmingIsTriggered() && emergencyArmingCanOverrideArmingDisabled(); return emergencyArmingIsTriggered() && emergencyArmingCanOverrideArmingDisabled();
} }
void annexCode(float dT) static void processPilotAndFailSafeActions(float dT)
{ {
if (failsafeShouldApplyControlInput()) { if (failsafeShouldApplyControlInput()) {
// Failsafe will apply rcCommand for us // Failsafe will apply rcCommand for us
@ -436,8 +436,6 @@ void annexCode(float dT)
rcCommand[PITCH] = rcCommand_PITCH; rcCommand[PITCH] = rcCommand_PITCH;
} }
} }
updateArmingStatus();
} }
void disarm(disarmReason_t disarmReason) void disarm(disarmReason_t disarmReason)
@ -880,7 +878,9 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
imuUpdateAccelerometer(); imuUpdateAccelerometer();
imuUpdateAttitude(currentTimeUs); imuUpdateAttitude(currentTimeUs);
annexCode(dT); processPilotAndFailSafeActions(dT);
updateArmingStatus();
if (rxConfig()->rcFilterFrequency) { if (rxConfig()->rcFilterFrequency) {
rcInterpolationApply(isRXDataNew, currentTimeUs); rcInterpolationApply(isRXDataNew, currentTimeUs);
@ -924,13 +924,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
// Calculate stabilisation // Calculate stabilisation
pidController(dT); pidController(dT);
#ifdef HIL
if (hilActive) {
hilUpdateControlState();
motorControlEnable = false;
}
#endif
mixTable(); mixTable();
if (isMixerUsingServos()) { if (isMixerUsingServos()) {

View file

@ -73,7 +73,6 @@
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/hil.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/servos.h" #include "flight/servos.h"
@ -402,15 +401,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteData(dst, shortGitRevision, GIT_SHORT_REVISION_LENGTH); sbufWriteData(dst, shortGitRevision, GIT_SHORT_REVISION_LENGTH);
break; break;
#ifdef HIL
case MSP_HIL_STATE:
sbufWriteU16(dst, hilToSIM.pidCommand[ROLL]);
sbufWriteU16(dst, hilToSIM.pidCommand[PITCH]);
sbufWriteU16(dst, hilToSIM.pidCommand[YAW]);
sbufWriteU16(dst, hilToSIM.pidCommand[THROTTLE]);
break;
#endif
case MSP_SENSOR_STATUS: case MSP_SENSOR_STATUS:
sbufWriteU8(dst, isHardwareHealthy() ? 1 : 0); sbufWriteU8(dst, isHardwareHealthy() ? 1 : 0);
sbufWriteU8(dst, getHwGyroStatus()); sbufWriteU8(dst, getHwGyroStatus());

View file

@ -87,14 +87,14 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ .boxId = BOXUSER1, .boxName = "USER1", .permanentId = BOX_PERMANENT_ID_USER1 }, { .boxId = BOXUSER1, .boxName = "USER1", .permanentId = BOX_PERMANENT_ID_USER1 },
{ .boxId = BOXUSER2, .boxName = "USER2", .permanentId = BOX_PERMANENT_ID_USER2 }, { .boxId = BOXUSER2, .boxName = "USER2", .permanentId = BOX_PERMANENT_ID_USER2 },
{ .boxId = BOXUSER3, .boxName = "USER3", .permanentId = BOX_PERMANENT_ID_USER3 }, { .boxId = BOXUSER3, .boxName = "USER3", .permanentId = BOX_PERMANENT_ID_USER3 },
{ .boxId = BOXLOITERDIRCHN, .boxName = "LOITER CHANGE", .permanentId = 50 }, { .boxId = BOXMSPRCOVERRIDE, .boxName = "MSP RC OVERRIDE", .permanentId = 50 },
{ .boxId = BOXMSPRCOVERRIDE, .boxName = "MSP RC OVERRIDE", .permanentId = 51 }, { .boxId = BOXPREARM, .boxName = "PREARM", .permanentId = 51 },
{ .boxId = BOXPREARM, .boxName = "PREARM", .permanentId = 52 }, { .boxId = BOXTURTLE, .boxName = "TURTLE", .permanentId = 52 },
{ .boxId = BOXTURTLE, .boxName = "TURTLE", .permanentId = 53 }, { .boxId = BOXNAVCRUISE, .boxName = "NAV CRUISE", .permanentId = 53 },
{ .boxId = BOXNAVCRUISE, .boxName = "NAV CRUISE", .permanentId = 54 }, { .boxId = BOXAUTOLEVEL, .boxName = "AUTO LEVEL", .permanentId = 54 },
{ .boxId = BOXAUTOLEVEL, .boxName = "AUTO LEVEL", .permanentId = 55 }, { .boxId = BOXPLANWPMISSION, .boxName = "WP PLANNER", .permanentId = 55 },
{ .boxId = BOXPLANWPMISSION, .boxName = "WP PLANNER", .permanentId = 56 }, { .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 56 },
{ .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 57 }, { .boxId = BOXLOITERDIRCHN, .boxName = "LOITER CHANGE", .permanentId = 57 },
{ .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 58 }, { .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 58 },
{ .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF }
}; };

View file

@ -927,10 +927,11 @@ groups:
description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
default_value: "DROP" default_value: "DROP"
table: failsafe_procedure table: failsafe_procedure
- name: failsafe_mission - name: failsafe_mission_delay
description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode" description: "Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end."
default_value: ON default_value: 0
type: bool min: -1
max: 600
- name: PG_LIGHTS_CONFIG - name: PG_LIGHTS_CONFIG
type: lightsConfig_t type: lightsConfig_t

View file

@ -67,13 +67,13 @@
static failsafeState_t failsafeState; static failsafeState_t failsafeState;
PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 2); PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 3);
PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
.failsafe_delay = SETTING_FAILSAFE_DELAY_DEFAULT, // 0.5 sec .failsafe_delay = SETTING_FAILSAFE_DELAY_DEFAULT, // 0.5 sec
.failsafe_recovery_delay = SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT, // 0.5 seconds (plus 200ms explicit delay) .failsafe_recovery_delay = SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT, // 0.5 seconds (plus 200ms explicit delay)
.failsafe_off_delay = SETTING_FAILSAFE_OFF_DELAY_DEFAULT, // 20sec .failsafe_off_delay = SETTING_FAILSAFE_OFF_DELAY_DEFAULT, // 20sec
.failsafe_throttle_low_delay = SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT, // default throttle low delay for "just disarm" on failsafe condition .failsafe_throttle_low_delay = SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT, // default throttle low delay for "just disarm" on failsafe condition
.failsafe_procedure = SETTING_FAILSAFE_PROCEDURE_DEFAULT, // default full failsafe procedure .failsafe_procedure = SETTING_FAILSAFE_PROCEDURE_DEFAULT, // default full failsafe procedure
.failsafe_fw_roll_angle = SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT, // 20 deg left .failsafe_fw_roll_angle = SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT, // 20 deg left
.failsafe_fw_pitch_angle = SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT, // 10 deg dive (yes, positive means dive) .failsafe_fw_pitch_angle = SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT, // 10 deg dive (yes, positive means dive)
@ -81,7 +81,7 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
.failsafe_stick_motion_threshold = SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT, .failsafe_stick_motion_threshold = SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT,
.failsafe_min_distance = SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT, // No minimum distance for failsafe by default .failsafe_min_distance = SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT, // No minimum distance for failsafe by default
.failsafe_min_distance_procedure = SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT, // default minimum distance failsafe procedure .failsafe_min_distance_procedure = SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT, // default minimum distance failsafe procedure
.failsafe_mission = SETTING_FAILSAFE_MISSION_DEFAULT, // Enable failsafe in WP mode or not .failsafe_mission_delay = SETTING_FAILSAFE_MISSION_DELAY_DEFAULT, // Time delay before Failsafe activated during WP mission (s)
); );
typedef enum { typedef enum {
@ -336,8 +336,14 @@ static bool failsafeCheckStickMotion(void)
static failsafeProcedure_e failsafeChooseFailsafeProcedure(void) static failsafeProcedure_e failsafeChooseFailsafeProcedure(void)
{ {
if ((FLIGHT_MODE(NAV_WP_MODE) || isWaypointMissionRTHActive()) && !failsafeConfig()->failsafe_mission) { if ((FLIGHT_MODE(NAV_WP_MODE) || isWaypointMissionRTHActive()) && failsafeConfig()->failsafe_mission_delay) {
return FAILSAFE_PROCEDURE_NONE; if (!failsafeState.wpModeDelayedFailsafeStart) {
failsafeState.wpModeDelayedFailsafeStart = millis();
return FAILSAFE_PROCEDURE_NONE;
} else if ((millis() - failsafeState.wpModeDelayedFailsafeStart < (MILLIS_PER_SECOND * (uint16_t)failsafeConfig()->failsafe_mission_delay)) ||
failsafeConfig()->failsafe_mission_delay == -1) {
return FAILSAFE_PROCEDURE_NONE;
}
} }
// Craft is closer than minimum failsafe procedure distance (if set to non-zero) // Craft is closer than minimum failsafe procedure distance (if set to non-zero)
@ -393,6 +399,7 @@ void failsafeUpdateState(void)
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_3_SECONDS; // require 3 seconds of valid rxData failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_3_SECONDS; // require 3 seconds of valid rxData
} else { } else {
failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED; failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED;
failsafeState.wpModeDelayedFailsafeStart = 0;
} }
reprocessState = true; reprocessState = true;
} }
@ -448,6 +455,9 @@ void failsafeUpdateState(void)
if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) {
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED; failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
reprocessState = true; reprocessState = true;
} else if (failsafeChooseFailsafeProcedure() != FAILSAFE_PROCEDURE_NONE) { // trigger new failsafe procedure if changed
failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED;
reprocessState = true;
} }
break; break;

View file

@ -42,7 +42,7 @@ typedef struct failsafeConfig_s {
uint16_t failsafe_stick_motion_threshold; uint16_t failsafe_stick_motion_threshold;
uint16_t failsafe_min_distance; // Minimum distance required for failsafe procedure to be taken. 1 step = 1 centimeter. 0 = Regular failsafe_procedure always active (default) uint16_t failsafe_min_distance; // Minimum distance required for failsafe procedure to be taken. 1 step = 1 centimeter. 0 = Regular failsafe_procedure always active (default)
uint8_t failsafe_min_distance_procedure; // selected minimum distance failsafe procedure is 0: auto-landing, 1: Drop it, 2: Return To Home (RTH) uint8_t failsafe_min_distance_procedure; // selected minimum distance failsafe procedure is 0: auto-landing, 1: Drop it, 2: Return To Home (RTH)
bool failsafe_mission; // Enable failsafe in WP mode or not int16_t failsafe_mission_delay; // Time delay before Failsafe triggered when WP mission in progress (s)
} failsafeConfig_t; } failsafeConfig_t;
PG_DECLARE(failsafeConfig_t, failsafeConfig); PG_DECLARE(failsafeConfig_t, failsafeConfig);
@ -148,6 +148,7 @@ typedef struct failsafeState_s {
timeMs_t landingShouldBeFinishedAt; timeMs_t landingShouldBeFinishedAt;
timeMs_t receivingRxDataPeriod; // period for the required period of valid rxData timeMs_t receivingRxDataPeriod; // period for the required period of valid rxData
timeMs_t receivingRxDataPeriodPreset; // preset for the required period of valid rxData timeMs_t receivingRxDataPeriodPreset; // preset for the required period of valid rxData
timeMs_t wpModeDelayedFailsafeStart; // waypoint mission delayed failsafe timer start time
failsafeProcedure_e activeProcedure; failsafeProcedure_e activeProcedure;
failsafePhase_e phase; failsafePhase_e phase;
failsafeRxLinkState_e rxLinkState; failsafeRxLinkState_e rxLinkState;

View file

@ -1,73 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
// Inertial Measurement Unit (IMU)
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "platform.h"
#ifdef HIL
#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/filter.h"
#include "drivers/time.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "sensors/boardalignment.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/hil.h"
#include "fc/config.h"
#include "fc/runtime_config.h"
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
bool hilActive = false;
hilIncomingStateData_t hilToFC;
hilOutgoingStateData_t hilToSIM;
void hilUpdateControlState(void)
{
// FIXME: There must be a cleaner way to to this
// If HIL active, store PID outout into hilState and disable motor control
if (FLIGHT_MODE(MANUAL_MODE) || !STATE(AIRPLANE)) {
hilToSIM.pidCommand[ROLL] = rcCommand[ROLL];
hilToSIM.pidCommand[PITCH] = rcCommand[PITCH];
hilToSIM.pidCommand[YAW] = rcCommand[YAW];
} else {
hilToSIM.pidCommand[ROLL] = axisPID[ROLL];
hilToSIM.pidCommand[PITCH] = axisPID[PITCH];
hilToSIM.pidCommand[YAW] = axisPID[YAW];
}
hilToSIM.pidCommand[THROTTLE] = rcCommand[THROTTLE];
}
#endif

View file

@ -1,42 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#ifdef HIL
typedef struct {
int16_t rollAngle; // deg * 10
int16_t pitchAngle; // deg * 10
int16_t yawAngle; // deg * 10
int32_t baroAlt; // cm above launch
int16_t bodyAccel[3]; // cm/s/s // forward, right, up
} hilIncomingStateData_t;
typedef struct {
int16_t pidCommand[4];
} hilOutgoingStateData_t;
extern bool hilActive;
extern hilIncomingStateData_t hilToFC;
extern hilOutgoingStateData_t hilToSIM;
void hilUpdateControlState(void);
#endif

View file

@ -47,7 +47,6 @@ FILE_COMPILE_FOR_SPEED
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/settings.h" #include "fc/settings.h"
#include "flight/hil.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
@ -194,7 +193,7 @@ void imuTransformVectorEarthToBody(fpVector3_t * v)
quaternionRotateVector(v, v, &orientation); quaternionRotateVector(v, v, &orientation);
} }
#if defined(USE_GPS) || defined(HIL) #if defined(USE_GPS)
STATIC_UNIT_TESTED void imuComputeQuaternionFromRPY(int16_t initialRoll, int16_t initialPitch, int16_t initialYaw) STATIC_UNIT_TESTED void imuComputeQuaternionFromRPY(int16_t initialRoll, int16_t initialPitch, int16_t initialYaw)
{ {
if (initialRoll > 1800) initialRoll -= 3600; if (initialRoll > 1800) initialRoll -= 3600;
@ -600,37 +599,12 @@ static void imuCalculateEstimatedAttitude(float dT)
imuUpdateEulerAngles(); imuUpdateEulerAngles();
} }
#ifdef HIL
void imuHILUpdate(void)
{
/* Set attitude */
attitude.values.roll = hilToFC.rollAngle;
attitude.values.pitch = hilToFC.pitchAngle;
attitude.values.yaw = hilToFC.yawAngle;
/* Compute rotation quaternion for future use */
imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw);
/* Fake accADC readings */
accADCf[X] = hilToFC.bodyAccel[X] / GRAVITY_CMSS;
accADCf[Y] = hilToFC.bodyAccel[Y] / GRAVITY_CMSS;
accADCf[Z] = hilToFC.bodyAccel[Z] / GRAVITY_CMSS;
}
#endif
void imuUpdateAccelerometer(void) void imuUpdateAccelerometer(void)
{ {
#ifdef HIL
if (sensors(SENSOR_ACC) && !hilActive) {
accUpdate();
isAccelUpdatedAtLeastOnce = true;
}
#else
if (sensors(SENSOR_ACC)) { if (sensors(SENSOR_ACC)) {
accUpdate(); accUpdate();
isAccelUpdatedAtLeastOnce = true; isAccelUpdatedAtLeastOnce = true;
} }
#endif
} }
void imuCheckVibrationLevels(void) void imuCheckVibrationLevels(void)
@ -655,23 +629,10 @@ void imuUpdateAttitude(timeUs_t currentTimeUs)
previousIMUUpdateTimeUs = currentTimeUs; previousIMUUpdateTimeUs = currentTimeUs;
if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) { if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) {
#ifdef HIL
if (!hilActive) {
gyroGetMeasuredRotationRate(&imuMeasuredRotationBF); // Calculate gyro rate in body frame in rad/s
accGetMeasuredAcceleration(&imuMeasuredAccelBF); // Calculate accel in body frame in cm/s/s
imuCheckVibrationLevels();
imuCalculateEstimatedAttitude(dT); // Update attitude estimate
}
else {
imuHILUpdate();
imuUpdateMeasuredAcceleration();
}
#else
gyroGetMeasuredRotationRate(&imuMeasuredRotationBF); // Calculate gyro rate in body frame in rad/s gyroGetMeasuredRotationRate(&imuMeasuredRotationBF); // Calculate gyro rate in body frame in rad/s
accGetMeasuredAcceleration(&imuMeasuredAccelBF); // Calculate accel in body frame in cm/s/s accGetMeasuredAcceleration(&imuMeasuredAccelBF); // Calculate accel in body frame in cm/s/s
imuCheckVibrationLevels(); imuCheckVibrationLevels();
imuCalculateEstimatedAttitude(dT); // Update attitude estimate imuCalculateEstimatedAttitude(dT); // Update attitude estimate
#endif
} else { } else {
acc.accADCf[X] = 0.0f; acc.accADCf[X] = 0.0f;
acc.accADCf[Y] = 0.0f; acc.accADCf[Y] = 0.0f;

View file

@ -4413,7 +4413,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL); messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL);
} }
if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) { if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); messages[messageCount++] = STATE(LANDING_DETECTED) ? OSD_MESSAGE_STR(OSD_MSG_WP_LANDED) : OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED);
} else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) { } else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) {
// Countdown display for remaining Waypoints // Countdown display for remaining Waypoints
char buf[6]; char buf[6];

View file

@ -94,6 +94,7 @@
#define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING" #define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING"
#define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME" #define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME"
#define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION" #define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION"
#define OSD_MSG_WP_LANDED "WP END>LANDED"
#define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT" #define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT"
#define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE" #define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE"
#define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)" #define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)"

View file

@ -202,6 +202,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended
.launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees
.launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg
.launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT,// OFF
.launch_abort_deadband = SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT, // 100 us
.cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps .cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps
.allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT, .allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT,
.useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT, .useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT,
@ -658,7 +661,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
.persistentId = NAV_PERSISTENT_ID_RTH_FINISHING, .persistentId = NAV_PERSISTENT_ID_RTH_FINISHING,
.onEntry = navOnEnteringState_NAV_STATE_RTH_FINISHING, .onEntry = navOnEnteringState_NAV_STATE_RTH_FINISHING,
.timeoutMs = 0, .timeoutMs = 0,
.stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_CTL_LAND | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH,
.mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE, .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE,
.mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS,
.mwError = MW_NAV_ERROR_LANDING, .mwError = MW_NAV_ERROR_LANDING,
@ -672,7 +675,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
.persistentId = NAV_PERSISTENT_ID_RTH_FINISHED, .persistentId = NAV_PERSISTENT_ID_RTH_FINISHED,
.onEntry = navOnEnteringState_NAV_STATE_RTH_FINISHED, .onEntry = navOnEnteringState_NAV_STATE_RTH_FINISHED,
.timeoutMs = 10, .timeoutMs = 10,
.stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, .stateFlags = NAV_CTL_ALT | NAV_CTL_LAND | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH,
.mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE, .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE,
.mwState = MW_NAV_STATE_LANDED, .mwState = MW_NAV_STATE_LANDED,
.mwError = MW_NAV_ERROR_NONE, .mwError = MW_NAV_ERROR_NONE,
@ -1463,6 +1466,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF
} }
float descentVelLimited = 0; float descentVelLimited = 0;
int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z;
// A safeguard - if surface altitude sensors is available and it is reading < 50cm altitude - drop to low descend speed // A safeguard - if surface altitude sensors is available and it is reading < 50cm altitude - drop to low descend speed
if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) { if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) {
@ -1472,8 +1476,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF
} else { } else {
// Ramp down descent velocity from 100% at maxAlt altitude to 25% from minAlt to 0cm. // Ramp down descent velocity from 100% at maxAlt altitude to 25% from minAlt to 0cm.
float descentVelScaled = scaleRangef(navGetCurrentActualPositionAndVelocity()->pos.z, float descentVelScaled = scaleRangef(navGetCurrentActualPositionAndVelocity()->pos.z,
navConfig()->general.land_slowdown_minalt, navConfig()->general.land_slowdown_maxalt, navConfig()->general.land_slowdown_minalt + landingElevation,
navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd); navConfig()->general.land_slowdown_maxalt + landingElevation,
navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd);
descentVelLimited = constrainf(descentVelScaled, navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd); descentVelLimited = constrainf(descentVelScaled, navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd);
} }
@ -1806,8 +1811,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_FINIS
{ {
UNUSED(previousState); UNUSED(previousState);
rcCommand[THROTTLE] = getThrottleIdleValue(); disarm(DISARM_NAVIGATION);
ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
return NAV_FSM_EVENT_NONE; return NAV_FSM_EVENT_NONE;
} }
@ -3377,7 +3381,7 @@ static void calculateAndSetActiveWaypointToLocalPosition(const fpVector3_t * pos
geoAltitudeConversionMode_e waypointMissionAltConvMode(geoAltitudeDatumFlag_e datumFlag) geoAltitudeConversionMode_e waypointMissionAltConvMode(geoAltitudeDatumFlag_e datumFlag)
{ {
return datumFlag == NAV_WP_MSL_DATUM ? GEO_ALT_ABSOLUTE : GEO_ALT_RELATIVE; return ((datumFlag & NAV_WP_MSL_DATUM) == NAV_WP_MSL_DATUM) ? GEO_ALT_ABSOLUTE : GEO_ALT_RELATIVE;
} }
static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint) static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint)
@ -3960,7 +3964,7 @@ void missionPlannerSetWaypoint(void)
posControl.waypointList[posControl.wpPlannerActiveWPIndex].lon = wpLLH.lon; posControl.waypointList[posControl.wpPlannerActiveWPIndex].lon = wpLLH.lon;
posControl.waypointList[posControl.wpPlannerActiveWPIndex].alt = wpLLH.alt; posControl.waypointList[posControl.wpPlannerActiveWPIndex].alt = wpLLH.alt;
posControl.waypointList[posControl.wpPlannerActiveWPIndex].p1 = posControl.waypointList[posControl.wpPlannerActiveWPIndex].p2 = 0; posControl.waypointList[posControl.wpPlannerActiveWPIndex].p1 = posControl.waypointList[posControl.wpPlannerActiveWPIndex].p2 = 0;
posControl.waypointList[posControl.wpPlannerActiveWPIndex].p3 = 1; // use absolute altitude datum posControl.waypointList[posControl.wpPlannerActiveWPIndex].p3 |= NAV_WP_ALTMODE; // use absolute altitude datum
posControl.waypointList[posControl.wpPlannerActiveWPIndex].flag = NAV_WP_FLAG_LAST; posControl.waypointList[posControl.wpPlannerActiveWPIndex].flag = NAV_WP_FLAG_LAST;
posControl.waypointListValid = true; posControl.waypointListValid = true;

View file

@ -352,6 +352,15 @@ typedef enum {
NAV_WP_FLAG_LAST = 0xA5 NAV_WP_FLAG_LAST = 0xA5
} navWaypointFlags_e; } navWaypointFlags_e;
/* A reminder that P3 is a bitfield */
typedef enum {
NAV_WP_ALTMODE = (1<<0),
NAV_WP_USER1 = (1<<1),
NAV_WP_USER2 = (1<<2),
NAV_WP_USER3 = (1<<3),
NAV_WP_USER4 = (1<<4)
} navWaypointP3Flags_e;
typedef struct { typedef struct {
int32_t lat; int32_t lat;
int32_t lon; int32_t lon;

View file

@ -635,9 +635,11 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
* Then altitude is below landing slowdown min. altitude, enable final approach procedure * Then altitude is below landing slowdown min. altitude, enable final approach procedure
* TODO refactor conditions in this metod if logic is proven to be correct * TODO refactor conditions in this metod if logic is proven to be correct
*/ */
if (navStateFlags & NAV_CTL_LAND) { if (navStateFlags & NAV_CTL_LAND || STATE(LANDING_DETECTED)) {
if ( ((posControl.flags.estAltStatus >= EST_USABLE) && (navGetCurrentActualPositionAndVelocity()->pos.z <= navConfig()->general.land_slowdown_minalt)) || int32_t finalAltitude = navConfig()->general.land_slowdown_minalt + posControl.rthState.homeTmpWaypoint.z;
((posControl.flags.estAglStatus == EST_TRUSTED) && (posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) ) {
if ((posControl.flags.estAltStatus >= EST_USABLE && navGetCurrentActualPositionAndVelocity()->pos.z <= finalAltitude) ||
(posControl.flags.estAglStatus == EST_TRUSTED && posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) {
// Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled
rcCommand[THROTTLE] = getThrottleIdleValue(); rcCommand[THROTTLE] = getThrottleIdleValue();

View file

@ -50,8 +50,6 @@
#include "sensors/barometer.h" #include "sensors/barometer.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "flight/hil.h"
#ifdef USE_HARDWARE_REVISION_DETECTION #ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h" #include "hardware_revision.h"
#endif #endif
@ -325,12 +323,6 @@ int32_t baroCalculateAltitude(void)
baro.BaroAlt = 0; baro.BaroAlt = 0;
} }
else { else {
#ifdef HIL
if (hilActive) {
baro.BaroAlt = hilToFC.baroAlt;
return baro.BaroAlt;
}
#endif
// calculates height from ground via baro readings // calculates height from ground via baro readings
baro.BaroAlt = pressureToAltitude(baro.baroPressure) - baroGroundAltitude; baro.BaroAlt = pressureToAltitude(baro.baroPressure) - baroGroundAltitude;
} }

View file

@ -100,8 +100,6 @@
#define I2C_DEVICE_2_SHARES_UART3 #define I2C_DEVICE_2_SHARES_UART3
//#define USE_I2C_PULLUP //#define USE_I2C_PULLUP
//#define HIL
#define USE_ADC #define USE_ADC
#define ADC_CHANNEL_1_PIN PC0 #define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1 #define ADC_CHANNEL_2_PIN PC1

View file

@ -0,0 +1 @@
target_stm32f405xg(HAKRCF405D)

View file

@ -0,0 +1,28 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
}

View file

@ -0,0 +1,42 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
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
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6
DEF_TIM(TIM4, CH1, PB8, TIM_USE_LED, 0, 0), // LED STRIP(2,6)
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // PWM1
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // PWM2
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PWM3
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,180 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "H40D"
#define USBD_PRODUCT_STRING "HAKRCF405D"
#define USE_TARGET_CONFIG
/*** Indicators ***/
#define LED0 PB9
#define LED1 PA14
#define BEEPER PC13
#define BEEPER_INVERTED
/*** SPI & I2C ***/
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PC2
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB10
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PC0
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
/*** IMU sensors ***/
#define USE_EXTI
#define GYRO_INT_EXTI PC3
#define USE_MPU_DATA_READY_SIGNAL
// MPU6000
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN SPI1_NSS_PIN
#define MPU6000_EXTI_PIN GYRO_INT_EXTI
// ICM42605/ICM42688P
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN SPI1_NSS_PIN
#define ICM42605_EXTI_PIN GYRO_INT_EXTI
//BMI270
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW270_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN SPI1_NSS_PIN
#define BMI270_EXTI_PIN GYRO_INT_EXTI
/*** OSD ***/
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN SPI2_NSS_PIN
/*** Onboard flash ***/
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN SPI3_NSS_PIN
#define M25P16_SPI_BUS BUS_SPI3
/*** PINIO ***/
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC14
#define PINIO2_PIN PC15
/*** Serial ports ***/
#define USE_VCP
#define USB_DETECT_PIN PB12
#define USE_USB_DETECT
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PC11
#define UART3_TX_PIN PC10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define SERIAL_PORT_COUNT 6
/*** BARO & MAG ***/
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_BARO_SPL06
#define USE_BARO_DPS310
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
/*** ADC ***/
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC5
#define ADC_CHANNEL_2_PIN PB1
#define ADC_CHANNEL_3_PIN PC4
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define RSSI_METER_ADC_CHANNEL ADC_CHN_2
/*** LED STRIP ***/
#define USE_LED_STRIP
#define WS2811_PIN PB8
/*** Default settings ***/
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define CURRENT_METER_SCALE 179
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
/*** Timer/PWM output ***/
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define MAX_PWM_OUTPUT_PORTS 6
#define USE_DSHOT
#define USE_ESC_SENSOR
/*** Optical Flow & Lidar ***/
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_OPFLOW
#define USE_OPFLOW_MSP
/*** Misc ***/
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

View file

@ -0,0 +1 @@
target_stm32f411xe(HAKRCF411D)

View file

@ -0,0 +1,31 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
#include "sensors/boardalignment.h"
void targetConfiguration(void)
{
boardAlignmentMutable()->yawDeciDegrees = -900;
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
}

View file

@ -0,0 +1,39 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
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
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_TX_PIN
DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_RX_PIN
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // 2812LED
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,163 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "H41D"
#define USBD_PRODUCT_STRING "HAKRCF411D"
#define USE_TARGET_CONFIG
/*** Indicators ***/
#define LED0 PC13
#define LED1 PC14
#define BEEPER PB2
#define BEEPER_INVERTED
/*** SPI & I2C ***/
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
/*** IMU sensors ***/
#define USE_EXTI
#define GYRO_INT_EXTI PA1
#define USE_MPU_DATA_READY_SIGNAL
// MPU6000
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN SPI1_NSS_PIN
#define MPU6000_EXTI_PIN GYRO_INT_EXTI
// ICM42605/ICM42688P
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW180_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN SPI1_NSS_PIN
#define ICM42605_EXTI_PIN GYRO_INT_EXTI
//BMI270
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW180_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN SPI1_NSS_PIN
#define BMI270_EXTI_PIN GYRO_INT_EXTI
/*** OSD ***/
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
/*** Onboard flash ***/
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PA0
#define M25P16_SPI_BUS BUS_SPI2
/*** UARTs ***/
#define USE_VCP
#define VBUS_SENSING_PIN PC15
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define USE_UART2
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define USE_SOFTSERIAL1
#define SOFTSERIAL_1_TX_PIN PA15
#define SOFTSERIAL_1_RX_PIN PB3
#define SERIAL_PORT_COUNT 4
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
/*** I2C (Baro/Mag/Pitot) ***/
#define DEFAULT_I2C_BUS BUS_I2C1
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_BARO_SPL06
#define USE_BARO_DPS310
#define TEMPERATURE_I2C_BUS BUS_I2C1
#define BNO055_I2C_BUS BUS_I2C1
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define PITOT_I2C_BUS BUS_I2C1
/*** PINIO ***/
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PB10
#define PINIO2_PIN PC14
/*** ADC ***/
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PB0
#define ADC_CHANNEL_2_PIN PB1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
/*** WS2812 LEDs ***/
#define USE_LED_STRIP
#define WS2811_PIN PA8
/*** Misc ***/
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
#define USE_DSHOT
//#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define MAX_PWM_OUTPUT_PORTS 4

View file

@ -0,0 +1 @@
target_stm32f722xe(HAKRCKD722)

View file

@ -0,0 +1,28 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; // VTX power switch
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
}

View file

@ -0,0 +1,46 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,177 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "KD7D"
#define USBD_PRODUCT_STRING "HAKRCKD722"
#define LED0 PA14
#define LED1 PA13
#define USE_BEEPER
#define BEEPER PC13
#define BEEPER_INVERTED
/*** PINIO ***/
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC8
#define PINIO2_PIN PC9
/*** UART ***/
#define USB_IO
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 6
/*** Gyro & Acc ***/
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW180_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN PB2
#define ICM42605_EXTI_PIN PC4
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW180_DEG
#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
/*** I2C (Baro & Mag) ***/
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
// Baro
#define USE_BARO
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define BARO_I2C_BUS BUS_I2C1
// Mag
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
/*** Onboard Flash ***/
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define M25P16_SPI_BUS BUS_SPI3
#define M25P16_CS_PIN PD2
#define W25N01G_SPI_BUS BUS_SPI3
#define W25N01G_CS_PIN PD2
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_FLASH_W25N01G
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
/*** OSD ***/
#define USE_OSD
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
/*** ADC ***/
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC0
#define ADC_CHANNEL_3_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define RSSI_ADC_CHANNEL ADC_CHN_2
/*** LED ***/
#define USE_LED_STRIP
#define WS2811_PIN PA8
/*** Optical Flow & Lidar ***/
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_OPFLOW
#define USE_OPFLOW_MSP
/*** Misc ***/
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define SERIALRX_UART SERIAL_PORT_USART2
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define MAX_PWM_OUTPUT_PORTS 8
#define CURRENT_METER_SCALE 250
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

View file

@ -1 +1,2 @@
target_stm32f405xg(MAMBAF405_2022A) target_stm32f405xg(MAMBAF405_2022A)
target_stm32f405xg(MAMBAF405_2022B)

View file

@ -19,9 +19,14 @@
#define USE_TARGET_CONFIG #define USE_TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "M42A"
#ifdef MAMBAF405_2022B
#define USBD_PRODUCT_STRING "MAMBAF405_2022B"
#define TARGET_BOARD_IDENTIFIER "M42B"
#else
#define TARGET_BOARD_IDENTIFIER "M42A"
#define USBD_PRODUCT_STRING "MAMBAF405_2022A" #define USBD_PRODUCT_STRING "MAMBAF405_2022A"
#endif
// ******** Board LEDs ********************** // ******** Board LEDs **********************
#define LED0 PC15 #define LED0 PC15
@ -56,6 +61,16 @@
#define BMI270_CS_PIN SPI1_NSS_PIN #define BMI270_CS_PIN SPI1_NSS_PIN
#define BMI270_EXTI_PIN GYRO_INT_EXTI #define BMI270_EXTI_PIN GYRO_INT_EXTI
#ifdef MAMBAF405_2022B
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN SPI1_NSS_PIN
#define ICM42605_EXTI_PIN GYRO_INT_EXTI
#endif
// *************** Baro ************************** // *************** Baro **************************
#define USE_I2C #define USE_I2C
@ -147,6 +162,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define VBAT_SCALE_DEFAULT 1100 #define VBAT_SCALE_DEFAULT 1100
#define CURRENT_METER_SCALE 183
// ******* OSD ******** // ******* OSD ********
#define USE_MAX7456 #define USE_MAX7456

View file

@ -1 +1,2 @@
target_stm32f722xe(MAMBAF722_2022A) target_stm32f722xe(MAMBAF722_2022A)
target_stm32f722xe(MAMBAF722_2022B)

View file

@ -19,9 +19,18 @@
#define USE_TARGET_CONFIG #define USE_TARGET_CONFIG
#ifdef MAMBAF722_2022B
#define TARGET_BOARD_IDENTIFIER "M72B"
#define USBD_PRODUCT_STRING "MAMBAF722_2022B"
#else
#define TARGET_BOARD_IDENTIFIER "M72A" #define TARGET_BOARD_IDENTIFIER "M72A"
#define USBD_PRODUCT_STRING "MAMBAF722_2022A" #define USBD_PRODUCT_STRING "MAMBAF722_2022A"
#endif
// ******** Board LEDs ********************** // ******** Board LEDs **********************
#define LED0 PC15 #define LED0 PC15
#define LED1 PC14 #define LED1 PC14
@ -54,6 +63,16 @@
#define BMI270_CS_PIN SPI1_NSS_PIN #define BMI270_CS_PIN SPI1_NSS_PIN
#define BMI270_EXTI_PIN GYRO_INT_EXTI #define BMI270_EXTI_PIN GYRO_INT_EXTI
#ifdef MAMBAF722_2022B
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN SPI1_NSS_PIN
#define ICM42605_EXTI_PIN GYRO_INT_EXTI
#endif
#define USE_I2C #define USE_I2C
#define USE_I2C_DEVICE_1 #define USE_I2C_DEVICE_1

View file

@ -1 +1,2 @@
target_stm32h743xi(MAMBAH743) target_stm32h743xi(MAMBAH743)
target_stm32h743xi(MAMBAH743_2022B)

View file

@ -15,16 +15,54 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include "platform.h" #include <platform.h>
#include "fc/fc_msp_box.h" #include "common/axis.h"
#include "fc/config.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "drivers/sensor.h"
#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "drivers/serial.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "rx/rx.h"
#include "io/serial.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "telemetry/telemetry.h"
#include "io/piniobox.h" #include "io/piniobox.h"
void targetConfiguration(void) void targetConfiguration(void)
{ {
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
#ifdef MAMBAH743_2022B
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
#endif
/*
* UART1 is SerialRX
*/
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL;
/*
* Enable MSP at 115200 at UART4
*/
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200;
} }

View file

@ -26,8 +26,12 @@
#include "drivers/pinio.h" #include "drivers/pinio.h"
#include "drivers/sensor.h" #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_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); BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
#ifdef MAMBAH743_2022B
BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
#endif
timerHardware_t timerHardware[] = { timerHardware_t timerHardware[] = {

View file

@ -17,9 +17,18 @@
#pragma once #pragma once
#ifdef MAMBAH743_2022B
#define TARGET_BOARD_IDENTIFIER "M743"
#define USBD_PRODUCT_STRING "MAMBAH743_2022B"
#else
#define TARGET_BOARD_IDENTIFIER "M743" #define TARGET_BOARD_IDENTIFIER "M743"
#define USBD_PRODUCT_STRING "MAMBAH743" #define USBD_PRODUCT_STRING "MAMBAH743"
#endif
#define USE_TARGET_CONFIG #define USE_TARGET_CONFIG
#define LED0 PE5 #define LED0 PE5
@ -42,12 +51,6 @@
#define SPI1_MISO_PIN PA6 #define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7 #define SPI1_MOSI_PIN PA7
// SPI4 is used on the second MPU6000 gyro, we do not use it at the moment
// #define USE_SPI_DEVICE_4
// #define SPI4_SCK_PIN PE12
// #define SPI4_MISO_PIN PE13
// #define SPI4_MOSI_PIN PE14
#define USE_IMU_MPU6000 #define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG #define IMU_MPU6000_ALIGN CW180_DEG
#define MPU6000_SPI_BUS BUS_SPI1 #define MPU6000_SPI_BUS BUS_SPI1
@ -60,6 +63,22 @@
#define BMI270_CS_PIN PA4 #define BMI270_CS_PIN PA4
#define BMI270_EXTI_PIN PC4 #define BMI270_EXTI_PIN PC4
#ifdef MAMBAH743_2022B
// SPI4 is used on the second MPU6000 gyro, we do not use it at the moment
// #define USE_SPI_DEVICE_4
// #define SPI4_SCK_PIN PE12
// #define SPI4_MISO_PIN PE13
// #define SPI4_MOSI_PIN PE14
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW90_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN PA4
#define ICM42605_EXTI_PIN PC4
#endif
// *************** SPI2 OSD *********************** // *************** SPI2 OSD ***********************
#define USE_SPI_DEVICE_2 #define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13 #define SPI2_SCK_PIN PB13
@ -164,12 +183,23 @@
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART6
// *************** ADC ***************************** // *************** ADC *****************************
#define USE_ADC #define USE_ADC
#define ADC_INSTANCE ADC3 #define ADC_INSTANCE ADC3
#ifdef MAMBAH743_2022B
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC3
#define ADC_CHANNEL_3_PIN PC0
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define AIRSPEED_ADC_CHANNEL ADC_CHN_3
#else
#define ADC_CHANNEL_1_PIN PC1 #define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC3 #define ADC_CHANNEL_2_PIN PC3
#define ADC_CHANNEL_3_PIN PC2 #define ADC_CHANNEL_3_PIN PC2
@ -180,11 +210,23 @@
#define RSSI_ADC_CHANNEL ADC_CHN_3 #define RSSI_ADC_CHANNEL ADC_CHN_3
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 #define AIRSPEED_ADC_CHANNEL ADC_CHN_4
#endif
// *************** PINIO *************************** // *************** PINIO ***************************
#define USE_PINIO #define USE_PINIO
#define USE_PINIOBOX #define USE_PINIOBOX
#ifdef MAMBAH743_2022B
#define PINIO1_PIN PC2
#define PINIO2_PIN PC5
#else
#define PINIO1_PIN PC5 #define PINIO1_PIN PC5
#endif
// *************** LEDSTRIP ************************ // *************** LEDSTRIP ************************
#define USE_LED_STRIP #define USE_LED_STRIP
#define WS2811_PIN PA8 #define WS2811_PIN PA8

View file

@ -86,6 +86,13 @@
#define MPU6500_SPI_BUS MPU6000_SPI_BUS #define MPU6500_SPI_BUS MPU6000_SPI_BUS
#define USE_IMU_MPU6500 #define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN IMU_MPU6000_ALIGN #define IMU_MPU6500_ALIGN IMU_MPU6000_ALIGN
//BMI270
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN IMU_MPU6000_ALIGN
#define BMI270_SPI_BUS MPU6000_SPI_BUS
#define BMI270_CS_PIN MPU6000_CS_PIN
#define BMI270_EXTI_PIN GYRO_INT_EXTI
#endif #endif
#define USE_MAG #define USE_MAG

View file

@ -24,7 +24,7 @@
#define USBD_PRODUCT_STRING "SpeedyBeeF7V3" #define USBD_PRODUCT_STRING "SpeedyBeeF7V3"
#define LED0 PA14 #define LED0 PA14
#define LED1 PA15 #define LED1 PA13
#define USE_BEEPER #define USE_BEEPER
#define BEEPER PC13 #define BEEPER PC13