diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 09e27045ca6..111a0cc35c0 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -100,7 +100,7 @@ jobs: - name: Build SITL run: | mkdir -p build_SITL && cd build_SITL - cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. + cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -G Ninja .. ninja - name: Upload artifacts diff --git a/.vscode/tasks.json b/.vscode/tasks.json index 3ca90b787d3..7be2cd3d176 100755 --- a/.vscode/tasks.json +++ b/.vscode/tasks.json @@ -4,9 +4,9 @@ "version": "2.0.0", "tasks": [ { - "label": "Build Matek F722-SE", + "label": "Build AOCODARCH7DUAL", "type": "shell", - "command": "make MATEKF722SE", + "command": "make AOCODARCH7DUAL", "group": "build", "problemMatcher": [], "options": { @@ -14,9 +14,9 @@ } }, { - "label": "Build Matek F722", + "label": "Build AOCODARCH7DUAL", "type": "shell", - "command": "make MATEKF722", + "command": "make AOCODARCH7DUAL", "group": { "kind": "build", "isDefault": true diff --git a/docs/Fixed Wing Landing.md b/docs/Fixed Wing Landing.md index 9a4c3a5b4ad..c89a5ee2075 100644 --- a/docs/Fixed Wing Landing.md +++ b/docs/Fixed Wing Landing.md @@ -5,6 +5,8 @@ INAV supports advanced automatic landings for fixed wing aircraft from version 7.1. The procedure is based on landings for man-carrying aircraft, so that safe landings at a specific location are possible. Supported are landings at safehome after "Return to Home" or at a defined LAND waypoint for missions. +Every landing locations can be defined with a target point and 2 different approach headings (colinear to the landing strips) with exclusive direction or opposite directions allowed. +This enables up to 4 different approach directions, based on the landing site and surrounding area. ## General procedure: @@ -34,7 +36,7 @@ The following graphics illustrate the process: ### The following parameters are set for each landing site (Safefome/LAND waypoint): -All settings can also be conveniently made in the Configurator via Missionplanner. +All settings can also be conveniently made in the Configurator via Mission Control. CLI command `fwapproach`: `fwapproach ` diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md index 0c127135781..df3279f6d31 100644 --- a/docs/SITL/SITL.md +++ b/docs/SITL/SITL.md @@ -16,6 +16,10 @@ Currently supported are INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the Configurator or the command line options. +AS SITL is still an inav software, but running on PC, it is possible to use HITL interface for communication. + +INAV-X-Plane-HITL plugin https://github.com/RomanLut/INAV-X-Plane-HITL can be used with SITL. + ## Sensors The following sensors are emulated: - IMU (Gyro, Accelerometer) @@ -30,13 +34,18 @@ The following sensors are emulated: Select "FAKE" as type for all mentioned, so that they receive the data from the simulator. -## Serial ports+ -UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 5761, ... -By default, UART1 and UART2 are available as MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned. -To connect the Configurator to SITL: Select TCP and connect to ```localhost:5760``` (or ```127.0.0.1:5760``` if your OS doesn't understand `localhost`) (if SITL is running on the same machine). +## Serial ports +UARTs are replaced by TCP starting with port 5760 ascending. UART1 is mapped to port 5760, UART2 to 5761, etc. + +By default, UART1 and UART2 are configured for MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned. + +To connect the Configurator to SITL, select "SITL". + +Alternativelly, select "TCP" and connect to ```localhost:5760``` (or ```127.0.0.1:5760``` if your OS doesn't understand `localhost`) (if SITL is running on the same machine). + IPv4 and IPv6 are supported, either raw addresses or host-name lookup. -The assignment and status of user UART/TCP connections is displayed on the console. +The assignment and status of used UART/TCP connections is displayed on the console. ``` INAV 6.1.0 SITL @@ -51,39 +60,73 @@ INAV 6.1.0 SITL All other interfaces (I2C, SPI, etc.) are not emulated. ## Remote control -MSP_RX (TCP/IP) or joystick (via simulator) or serial receiver via USB/Serial interface are supported. +Multiple methods for connecting RC Controllers are available: +- MSP_RX (TCP/IP) +- joystick (via simulator) +- serial receiver via USB to serial converter +- any receiver with proxy flight controller + ### MSP_RX -MSP_RX is the default, 18 channels are supported over TCP/IP serial emulation. +MSP_RX is the default, 18 channels are supported over TCP/IP connection. ### Joystick interface Only 8 channels are supported. -Select "SIM (SITL)" as the receiver and set up a joystick in the simulator, details of which can be found in the documentation for the individual simulators. + +Select "SIM (SITL)" as the receiver and set up a joystick in the simulator. + +*Not available with INAV-X-Plane-HITL plugin.* ### Serial Receiver via USB -Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual. +- Connect a serial receiver to the PC via a USB-to-serial adapter +- Configure the receiver in the SITL as usual +- While starting SITL from configurator, enable "Serial receiver" option + +The SITL offers a built-in option for forwarding the host's serial port to the SITL UART. + +Please note that 100000(SBUS) and 420000(CRSF) are non-standart baud rates which may not be supported by some USB-to-serial adapters. FDTI and CH340 should work. CP2102/9 does not work. -The Configurator offers a built-in option for forwarding the serial data to the SITL TCP port, if SITL is started manually the following option can be used: -The connection can then be established with a programme that forwards the serial data unaltered to TCP, e.g. with the Python script tcp_serial_redirect.py (https://github.com/Scavanger/TCP-Serial-Redirect) -If necessary, please download the required runtime environment from https://www.python.org/. -Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow. +#### Example SBUS: +For this you need a USB-to-serial adapter, receiver with inverter, or receiver which can output inverted SBUS (normal UART). -### Example SBUS: -For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) the signals can be inverted: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD. +SBUS protocol is inverted UART. + +Receiver's SBUS output should be connected to the USB-to-serial adapter's RX pin (via inverter). + +With FT-Prog (https://ftdichip.com/utilities/) the signal can be inverted by adapter: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD. ![SITL-SBUS-FT232](assets/SITL-SBUS-FT232.png) -For SBUS, the command line arguments of the python script are: -```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` +![SITL-SBUS](assets/serial_receiver_sbus.png) ### Telemetry +In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "SBUS". + +#### Example CRSF: + +On receiver side, CRSF is normal UART. + +Connect receiver's RX/TX pins (and GND, 5V of course) to USB-To-Serial adapter's TX/RX pins (RX to TX, TX to RX). + +![SITL-SBUS](assets/serial_receiver_crsf.png) + +In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "CRSF". + +### Proxy Flight controller + +The last, but probably the most easiest way to connect receiver to the SITL, is to use any inav/betaflight Flight controler as proxy. + +Connect receiver of any type to FC and configure FC to the point where channels are correctly updated in the "Receiver" tab. Inav and Betaflight are supported. -LTM and MAVLink telemetry are supported, either as a discrete function or shared with MSP. +You also can use your plane/quad ( if receiver is powered from USB). + +![SITL-SBUS](assets/serial_receiver_proxy.png) + +In the SITL configuration, select "Receiver type: SIM" regardles of the kind of receiver used. -RX Telemetry via a return channel through the receiver is not yet supported by SITL. ## OSD For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD. @@ -91,6 +134,8 @@ For this, activate MSP-Displayport on a UART/TCP port and connect to the corresp Note: INAV-Sim-OSD only works if the simulator is in window mode. +*With INAV-X-Plane-HITL plugin, OSD is supported natively.* + ## Command line The command line options are only necessary if the SITL executable is started by hand. @@ -103,7 +148,7 @@ If SITL is started without command line options, only a serial MSP / CLI connect ```--path``` Path and file name to config file. If not present, eeprom.bin in the current directory is used. Example: ```C:\INAV_SITL\flying-wing.bin```, ```/home/user/sitl-eeproms/test-eeprom.bin```. -```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp``` +```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp```. If not specified, configurator-only mode is started. Omit for usage with INAV-X-Plane-HITL plugin. ```--simip=[ip]``` Hostname or IP address of the simulator, if you specify a simulator with "--sim" and omit this option IPv4 localhost (`127.0.0.1`) will be used. Example: ```--simip=172.65.21.15```, ```--simip acme-sims.org```, ```--sim ::1```. @@ -118,6 +163,18 @@ To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2 ```--chanmap:M01-01,S01-02,S02-03``` Please also read the documentation of the individual simulators. +```--serialport``` Use serial receiver or proxy FC connected to host's serial port, f.e. ```--serialportCOM5``` or ```--serialportdev/ttyACM3``` + +```--serialuart``` Map serial receiver to SITL UART, f.e. ```--serialuart=3``` for UART3. Omit if using ```--fcproxy```. + +```--baudrate``` Serial receiver baudrate (default: 115200) + +```--stopbits=[None|One|Two]``` Serial receiver stopbits (default: One) + +```--parity=[Even|None|Odd]``` Serial receiver parity (default: None) + +```--fcproxy``` Use inav/betaflight FC as a proxy for serial receiver. + ```--help``` Displays help for the command line options. For options that take an argument, either form `--flag=value` or `--flag value` may be used. @@ -125,46 +182,13 @@ For options that take an argument, either form `--flag=value` or `--flag value` ## Running SITL It is recommended to start the tools in the following order: 1. Simulator, aircraft should be ready for take-off -2. INAV-SITL +2. SITL 3. OSD -4. serial redirect for RC input - -## Compile - -### Linux and FreeBSD: -Almost like normal, ruby, cmake and make are also required. -With cmake, the option "-DSITL=ON" must be specified. - -``` -mkdir build_SITL -cd build_SITL -cmake -DSITL=ON .. -make -``` - -### Windows: -Compile under cygwin, then as in Linux. -Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH. - -If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help. - -#### Build manager - -`ninja` may also be used (parallel builds without `-j $(nproc)`): - -``` -cmake -GNinja -DSITL=ON .. -ninja -``` - -### Compiler requirements -* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work. -* Unix sockets networking. Cygwin is required on Windows (vice `winsock`). -* Pthreads +For INav-X-Plane-HITL plugin: +1. SITL (Run in configurator-only mode) +2. X-Plane -## Supported environments +# #Forwarding serial data for other UART -* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2) -* Windows on x86_64 -* FreeBSD (x86_64 at least). +Other UARTs can then be mapped to host's serial port using external tool, which can be found in directories ```inav-configurator\resources\sitl\linux\Ser2TCP```, ```inav-configurator\resources\sitl\windows\Ser2TCP.exe``` diff --git a/docs/SITL/assets/serial_receiver_crsf.png b/docs/SITL/assets/serial_receiver_crsf.png new file mode 100644 index 00000000000..55ae6af98b6 Binary files /dev/null and b/docs/SITL/assets/serial_receiver_crsf.png differ diff --git a/docs/SITL/assets/serial_receiver_proxy.png b/docs/SITL/assets/serial_receiver_proxy.png new file mode 100644 index 00000000000..6f22f5dbac6 Binary files /dev/null and b/docs/SITL/assets/serial_receiver_proxy.png differ diff --git a/docs/SITL/assets/serial_receiver_sbus.png b/docs/SITL/assets/serial_receiver_sbus.png new file mode 100644 index 00000000000..ce4ebcce169 Binary files /dev/null and b/docs/SITL/assets/serial_receiver_sbus.png differ diff --git a/docs/Settings.md b/docs/Settings.md index b6fd431d950..7ed9437ced1 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -658,7 +658,7 @@ These are values (in us) by how much RC input can be different before it's consi | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 32 | +| 2 | 0 | 32 | --- @@ -932,6 +932,16 @@ EzTune response --- +### ez_snappiness + +EzTune snappiness + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 100 | + +--- + ### ez_stability EzTune stability @@ -2372,16 +2382,6 @@ These are min/max values (in us) which, when a channel is smaller (min) or large --- -### max_throttle - -This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. - -| Default | Min | Max | -| --- | --- | --- | -| 1850 | PWM_RANGE_MIN | PWM_RANGE_MAX | - ---- - ### mc_cd_lpf_hz Cutoff frequency for Control Derivative. This controls the cutoff for the LPF that is applied to the CD (Feed Forward) signal to the PID controller. Lower value will produce a smoother CD gain to the controller, but it will be more delayed. Higher values will produce CD gain that may have more noise in the signal depending on your RC link but wil be less delayed. @@ -3724,7 +3724,7 @@ When ON, NAV engine will slow down when switching to the next waypoint. This pri ### nav_min_ground_speed -Minimum ground speed for navigation flight modes [m/s]. Default 7 m/s. +Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s. | Default | Min | Max | | --- | --- | --- | @@ -5062,26 +5062,6 @@ Allows to set type of PID controller used in control loop. Possible values: `NON --- -### pidsum_limit - -A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help - -| Default | Min | Max | -| --- | --- | --- | -| 500 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | - ---- - -### pidsum_limit_yaw - -A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help - -| Default | Min | Max | -| --- | --- | --- | -| 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | - ---- - ### pilot_name Pilot name @@ -6218,7 +6198,7 @@ These are values (in us) by how much RC input can be different before it's consi | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 100 | +| 2 | 0 | 100 | --- diff --git a/docs/development/Building SITL.md b/docs/development/Building SITL.md new file mode 100644 index 00000000000..33ba7ee3d5c --- /dev/null +++ b/docs/development/Building SITL.md @@ -0,0 +1,39 @@ +## Building SITL + +### Linux and FreeBSD: +Almost like normal, ruby, cmake and make are also required. +With cmake, the option "-DSITL=ON" must be specified. + +``` +mkdir build_SITL +cd build_SITL +cmake -DSITL=ON .. +make +``` + +### Windows: +Compile under cygwin, then as in Linux. +Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH. + +If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help. + +#### Build manager + +`ninja` may also be used (parallel builds without `-j $(nproc)`): + +``` +cmake -GNinja -DSITL=ON .. +ninja +``` + +### Compiler requirements + +* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work. +* Unix sockets networking. Cygwin is required on Windows (vice `winsock`). +* Pthreads + +## Supported environments + +* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2) +* Windows on x86_64 +* FreeBSD (x86_64 at least). diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 4606e8a1787..b16f03de775 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1844,9 +1844,9 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", systemConfig()->craftName); BLACKBOX_PRINT_HEADER_LINE("P interval", "%u/%u", blackboxConfig()->rate_num, blackboxConfig()->rate_denom); BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", getThrottleIdleValue()); - BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", getMaxThrottle()); BLACKBOX_PRINT_HEADER_LINE("gyro_scale", "0x%x", castFloatBytesToInt(1.0f)); - BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),motorConfig()->maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),getMaxThrottle()); BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G); #ifdef USE_ADC @@ -1939,8 +1939,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid()); BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz); BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff); - BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit); - BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitRollPitch", "%d", pidProfile()->axisAccelerationLimitRollPitch); #ifdef USE_RPM_FILTER diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index d97e6d300ce..75bb46668d7 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -40,7 +40,7 @@ #endif #ifdef __APPLE__ -#define FASTRAM __attribute__ ((section("__DATA,__.fastram_bss"), aligned(4))) +#define FASTRAM __attribute__ ((section("__DATA,__.fastram_bss"), aligned(8))) #else #define FASTRAM __attribute__ ((section(".fastram_bss"), aligned(4))) #endif diff --git a/src/main/cms/cms_types.h b/src/main/cms/cms_types.h index 9b2b06646c5..a07e55eaaa4 100644 --- a/src/main/cms/cms_types.h +++ b/src/main/cms/cms_types.h @@ -26,6 +26,12 @@ //type of elements +#ifndef __APPLE__ +#define OSD_ENTRY_ATTR __attribute__((packed)) +#else +#define OSD_ENTRY_ATTR +#endif + typedef enum { OME_Label, @@ -71,7 +77,7 @@ typedef struct const void * const data; const uint8_t type; // from OSD_MenuElement uint8_t flags; -} __attribute__((packed)) OSD_Entry; +} OSD_ENTRY_ATTR OSD_Entry; // Bits in flags #define PRINT_VALUE (1 << 0) // Value has been changed, need to redraw diff --git a/src/main/config/parameter_group.h b/src/main/config/parameter_group.h index 9594ad96c41..28a647ecb96 100644 --- a/src/main/config/parameter_group.h +++ b/src/main/config/parameter_group.h @@ -64,7 +64,7 @@ static inline uint16_t pgIsProfile(const pgRegistry_t* reg) {return (reg->size & #ifdef __APPLE__ extern const pgRegistry_t __pg_registry_start[] __asm("section$start$__DATA$__pg_registry"); extern const pgRegistry_t __pg_registry_end[] __asm("section$end$__DATA$__pg_registry"); -#define PG_REGISTER_ATTRIBUTES __attribute__ ((section("__DATA,__pg_registry"), used, aligned(4))) +#define PG_REGISTER_ATTRIBUTES __attribute__ ((section("__DATA,__pg_registry"), used, aligned(8))) extern const uint8_t __pg_resetdata_start[] __asm("section$start$__DATA$__pg_resetdata"); extern const uint8_t __pg_resetdata_end[] __asm("section$end$__DATA$__pg_resetdata"); diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c index 48522508ce8..765f8308cd3 100644 --- a/src/main/drivers/serial_tcp.c +++ b/src/main/drivers/serial_tcp.c @@ -43,6 +43,7 @@ #include "drivers/serial.h" #include "drivers/serial_tcp.h" +#include "target/SITL/serial_proxy.h" static const struct serialPortVTable tcpVTable[]; static tcpPort_t tcpPorts[SERIAL_PORT_COUNT]; @@ -118,6 +119,23 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) return port; } +void tcpReceiveBytes( tcpPort_t *port, const uint8_t* buffer, ssize_t recvSize ) { + for (ssize_t i = 0; i < recvSize; i++) { + if (port->serialPort.rxCallback) { + port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData); + } else { + pthread_mutex_lock(&port->receiveMutex); + port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i]; + port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize; + pthread_mutex_unlock(&port->receiveMutex); + } + } +} + +void tcpReceiveBytesEx( int portIndex, const uint8_t* buffer, ssize_t recvSize ) { + tcpReceiveBytes( &tcpPorts[portIndex], buffer, recvSize ); +} + int tcpReceive(tcpPort_t *port) { char addrbuf[IPADDRESS_PRINT_BUFLEN]; @@ -162,22 +180,12 @@ int tcpReceive(tcpPort_t *port) return 0; } - for (ssize_t i = 0; i < recvSize; i++) { - - if (port->serialPort.rxCallback) { - port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData); - } else { - pthread_mutex_lock(&port->receiveMutex); - port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i]; - port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize; - pthread_mutex_unlock(&port->receiveMutex); - } - } - if (recvSize < 0) { recvSize = 0; } + tcpReceiveBytes( port, buffer, recvSize ); + return (int)recvSize; } @@ -240,9 +248,21 @@ void tcpWritBuf(serialPort_t *instance, const void *data, int count) send(port->clientSocketFd, data, count, 0); } +int getTcpPortIndex(const serialPort_t *instance) { + for (int i = 0; i < SERIAL_PORT_COUNT; i++) { + if ( &(tcpPorts[i].serialPort) == instance) return i; + } + return -1; +} + void tcpWrite(serialPort_t *instance, uint8_t ch) { tcpWritBuf(instance, (void*)&ch, 1); + + int index = getTcpPortIndex(instance); + if ( !serialFCProxy && serialProxyIsConnected() && (index == (serialUartIndex-1)) ) { + serialProxyWriteData( (unsigned char *)&ch, 1); + } } uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) @@ -263,6 +283,10 @@ uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) return count; } +uint32_t tcpRXBytesFree(int portIndex) { + return tcpPorts[portIndex].serialPort.rxBufferSize - tcpTotalRxBytesWaiting( &tcpPorts[portIndex].serialPort); +} + uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) { UNUSED(instance); @@ -272,7 +296,6 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) bool isTcpTransmitBufferEmpty(const serialPort_t *instance) { UNUSED(instance); - return true; } diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h index d27610eb805..7f394b8ccd3 100644 --- a/src/main/drivers/serial_tcp.h +++ b/src/main/drivers/serial_tcp.h @@ -26,6 +26,8 @@ #include #include +#include "drivers/serial.h" + #define BASE_IP_ADDRESS 5760 #define TCP_BUFFER_SIZE 2048 #define TCP_MAX_PACKET_SIZE 65535 @@ -50,5 +52,7 @@ typedef struct serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); -void tcpSend(tcpPort_t *port); -int tcpReceive(tcpPort_t *port); +extern void tcpSend(tcpPort_t *port); +extern int tcpReceive(tcpPort_t *port); +extern void tcpReceiveBytesEx( int portIndex, const uint8_t* buffer, ssize_t recvSize ); +extern uint32_t tcpRXBytesFree(int portIndex); \ No newline at end of file diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 48345583412..97de1bd6ed1 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1171,7 +1171,7 @@ static void cliRxRange(char *cmdline) ptr = cmdline; i = fastA2I(ptr); if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) { - int rangeMin, rangeMax; + int rangeMin = 0, rangeMax = 0; ptr = nextArg(ptr); if (ptr) { diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 2839a338f22..b1352c1ce27 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -147,6 +147,10 @@ #include "telemetry/telemetry.h" +#if defined(SITL_BUILD) +#include "target/SITL/serial_proxy.h" +#endif + #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif @@ -223,6 +227,10 @@ void init(void) flashDeviceInitialized = flashInit(); #endif +#if defined(SITL_BUILD) + serialProxyInit(); +#endif + initEEPROM(); ensureEEPROMContainsValidData(); suspendRxSignal(); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 63c7468ea69..d44a6e1fcad 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -504,6 +504,14 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU32(dst, 0); //Input reversing is not required since it can be done on mixer level } break; + case MSP2_INAV_SERVO_CONFIG: + for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { + sbufWriteU16(dst, servoParams(i)->min); + sbufWriteU16(dst, servoParams(i)->max); + sbufWriteU16(dst, servoParams(i)->middle); + sbufWriteU8(dst, servoParams(i)->rate); + } + break; case MSP_SERVO_MIX_RULES: for (int i = 0; i < MAX_SERVO_RULES; i++) { sbufWriteU8(dst, customServoMixers(i)->targetChannel); @@ -764,7 +772,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, PWM_RANGE_MIDDLE); sbufWriteU16(dst, 0); // Was min_throttle - sbufWriteU16(dst, motorConfig()->maxthrottle); + sbufWriteU16(dst, getMaxThrottle()); sbufWriteU16(dst, motorConfig()->mincommand); sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); @@ -805,7 +813,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, PWM_RANGE_MIDDLE); sbufWriteU16(dst, 0); //Was min_throttle - sbufWriteU16(dst, motorConfig()->maxthrottle); + sbufWriteU16(dst, getMaxThrottle()); sbufWriteU16(dst, motorConfig()->mincommand); sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); @@ -1270,7 +1278,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, 0); //BF: pidProfile()->vbatPidCompensation sbufWriteU8(dst, 0); //BF: pidProfile()->setpointRelaxRatio sbufWriteU8(dst, 0); - sbufWriteU16(dst, pidProfile()->pidSumLimit); + sbufWriteU16(dst, 0); //Was pidsum limit sbufWriteU8(dst, 0); //BF: pidProfile()->itermThrottleGain /* @@ -1644,6 +1652,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, ezTune()->aggressiveness); sbufWriteU8(dst, ezTune()->rate); sbufWriteU8(dst, ezTune()->expo); + sbufWriteU8(dst, ezTune()->snappiness); } break; #endif @@ -1951,7 +1960,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU16(src); // midrc sbufReadU16(src); //Was min_throttle - motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + sbufReadU16(src); //Was maxThrottle motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); currentBatteryProfileMutable->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); @@ -1999,7 +2008,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU16(src); // midrc sbufReadU16(src); // was min_throttle - motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + sbufReadU16(src); // was maxThrottle motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); currentBatteryProfileMutable->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); @@ -2129,6 +2138,22 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } break; + case MSP2_INAV_SET_SERVO_CONFIG: + if (dataSize != 8) { + return MSP_RESULT_ERROR; + } + tmp_u8 = sbufReadU8(src); + if (tmp_u8 >= MAX_SUPPORTED_SERVOS) { + return MSP_RESULT_ERROR; + } else { + servoParamsMutable(tmp_u8)->min = sbufReadU16(src); + servoParamsMutable(tmp_u8)->max = sbufReadU16(src); + servoParamsMutable(tmp_u8)->middle = sbufReadU16(src); + servoParamsMutable(tmp_u8)->rate = sbufReadU8(src); + servoComputeScalingFactors(tmp_u8); + } + break; + case MSP_SET_SERVO_MIX_RULE: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 9) && (tmp_u8 < MAX_SERVO_RULES)) { @@ -2307,7 +2332,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU8(src); //BF: pidProfileMutable()->vbatPidCompensation sbufReadU8(src); //BF: pidProfileMutable()->setpointRelaxRatio sbufReadU8(src); - pidProfileMutable()->pidSumLimit = sbufReadU16(src); + sbufReadU16(src); // Was pidsumLimit sbufReadU8(src); //BF: pidProfileMutable()->itermThrottleGain /* @@ -3232,21 +3257,25 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_INAV_EZ_TUNE_SET: { - if (dataSize == 10) { - ezTuneMutable()->enabled = sbufReadU8(src); - ezTuneMutable()->filterHz = sbufReadU16(src); - ezTuneMutable()->axisRatio = sbufReadU8(src); - ezTuneMutable()->response = sbufReadU8(src); - ezTuneMutable()->damping = sbufReadU8(src); - ezTuneMutable()->stability = sbufReadU8(src); - ezTuneMutable()->aggressiveness = sbufReadU8(src); - ezTuneMutable()->rate = sbufReadU8(src); - ezTuneMutable()->expo = sbufReadU8(src); - - ezTuneUpdate(); - } else { + + if (dataSize < 10 || dataSize > 11) { return MSP_RESULT_ERROR; } + + ezTuneMutable()->enabled = sbufReadU8(src); + ezTuneMutable()->filterHz = sbufReadU16(src); + ezTuneMutable()->axisRatio = sbufReadU8(src); + ezTuneMutable()->response = sbufReadU8(src); + ezTuneMutable()->damping = sbufReadU8(src); + ezTuneMutable()->stability = sbufReadU8(src); + ezTuneMutable()->aggressiveness = sbufReadU8(src); + ezTuneMutable()->rate = sbufReadU8(src); + ezTuneMutable()->expo = sbufReadU8(src); + + if (dataSize == 11) { + ezTuneMutable()->snappiness = sbufReadU8(src); + } + ezTuneUpdate(); } break; diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 74be2f42258..8da10280a9d 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -94,6 +94,10 @@ #include "config/feature.h" +#if defined(SITL_BUILD) +#include "target/SITL/serial_proxy.h" +#endif + void taskHandleSerial(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); @@ -426,6 +430,10 @@ void fcTasksInit(void) #ifdef USE_ADAPTIVE_FILTER setTaskEnabled(TASK_ADAPTIVE_FILTER, true); #endif + +#if defined(SITL_BUILD) + serialProxyStart(); +#endif } cfTask_t cfTasks[TASK_COUNT] = { diff --git a/src/main/fc/rc_curves.c b/src/main/fc/rc_curves.c index 47da45113bc..5453083d279 100644 --- a/src/main/fc/rc_curves.c +++ b/src/main/fc/rc_curves.c @@ -39,7 +39,7 @@ int16_t lookupThrottleRCMid; // THROTTLE curve mid point void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) { const int minThrottle = getThrottleIdleValue(); - lookupThrottleRCMid = minThrottle + (int32_t)(motorConfig()->maxthrottle - minThrottle) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRCMid = minThrottle + (int32_t)(getMaxThrottle() - minThrottle) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) { const int16_t tmp = 10 * i - controlRateConfig->throttle.rcMid8; @@ -49,7 +49,7 @@ void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) if (tmp < 0) y = controlRateConfig->throttle.rcMid8; lookupThrottleRC[i] = 10 * controlRateConfig->throttle.rcMid8 + tmp * (100 - controlRateConfig->throttle.rcExpo8 + (int32_t) controlRateConfig->throttle.rcExpo8 * (tmp * tmp) / (y * y)) / 10; - lookupThrottleRC[i] = minThrottle + (int32_t) (motorConfig()->maxthrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRC[i] = minThrottle + (int32_t) (getMaxThrottle() - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] } } @@ -62,7 +62,7 @@ int16_t rcLookup(int32_t stickDeflection, uint8_t expo) uint16_t rcLookupThrottle(uint16_t absoluteDeflection) { if (absoluteDeflection > 999) - return motorConfig()->maxthrottle; + return getMaxThrottle(); const uint8_t lookupStep = absoluteDeflection / 100; return lookupThrottleRC[lookupStep] + (absoluteDeflection - lookupStep * 100) * (lookupThrottleRC[lookupStep + 1] - lookupThrottleRC[lookupStep]) / 100; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a495e691cbc..40ca93c829d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -787,12 +787,6 @@ groups: type: motorConfig_t headers: ["flight/mixer.h"] members: - - name: max_throttle - description: "This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000." - default_value: 1850 - field: maxthrottle - min: PWM_RANGE_MIN - max: PWM_RANGE_MAX - name: min_command description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once." default_value: 1000 @@ -1616,6 +1610,12 @@ groups: field: expo min: 0 max: 200 + - name: ez_snappiness + description: "EzTune snappiness" + default_value: 0 + field: snappiness + min: 0 + max: 100 - name: PG_RPM_FILTER_CONFIG headers: ["flight/rpm_filter.h"] @@ -1723,12 +1723,12 @@ groups: members: - name: deadband description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." - default_value: 5 + default_value: 2 min: 0 max: 32 - name: yaw_deadband description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." - default_value: 5 + default_value: 2 min: 0 max: 100 - name: pos_hold_deadband @@ -2001,18 +2001,6 @@ groups: field: fixedWingYawItermBankFreeze min: 0 max: 90 - - name: pidsum_limit - description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" - default_value: 500 - field: pidSumLimit - min: PID_SUM_LIMIT_MIN - max: PID_SUM_LIMIT_MAX - - name: pidsum_limit_yaw - description: "A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" - default_value: 350 - field: pidSumLimitYaw - min: PID_SUM_LIMIT_MIN - max: PID_SUM_LIMIT_MAX - name: iterm_windup description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" default_value: 50 @@ -2548,7 +2536,7 @@ groups: min: 10 max: 2000 - name: nav_min_ground_speed - description: "Minimum ground speed for navigation flight modes [m/s]. Default 7 m/s." + description: "Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s." default_value: 7 field: general.min_ground_speed min: 6 diff --git a/src/main/flight/dynamic_lpf.c b/src/main/flight/dynamic_lpf.c index 5751c84e85e..0e5b4f6ef28 100644 --- a/src/main/flight/dynamic_lpf.c +++ b/src/main/flight/dynamic_lpf.c @@ -41,8 +41,8 @@ void dynamicLpfGyroTask(void) { return; } - const float throttleConstrained = (float) constrain(rcCommand[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); - const float throttle = scaleRangef(throttleConstrained, getThrottleIdleValue(), motorConfig()->maxthrottle, 0.0f, 1.0f); + const float throttleConstrained = (float) constrain(rcCommand[THROTTLE], getThrottleIdleValue(), getMaxThrottle()); + const float throttle = scaleRangef(throttleConstrained, getThrottleIdleValue(), getMaxThrottle(), 0.0f, 1.0f); const float cutoffFreq = dynLpfCutoffFreq(throttle, gyroConfig()->gyroDynamicLpfMinHz, gyroConfig()->gyroDynamicLpfMaxHz, gyroConfig()->gyroDynamicLpfCurveExpo); DEBUG_SET(DEBUG_DYNAMIC_GYRO_LPF, 0, cutoffFreq); diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index 128a108ccb0..4bde5b645e8 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -34,7 +34,9 @@ #include "sensors/gyro.h" #include "fc/controlrate_profile.h" -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 0); +#include "rx/rx.h" + +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 1); PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, .enabled = SETTING_EZ_ENABLED_DEFAULT, @@ -46,6 +48,7 @@ PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, .aggressiveness = SETTING_EZ_AGGRESSIVENESS_DEFAULT, .rate = SETTING_EZ_RATE_DEFAULT, .expo = SETTING_EZ_EXPO_DEFAULT, + .snappiness = SETTING_EZ_SNAPPINESS_DEFAULT, ); #define EZ_TUNE_PID_RP_DEFAULT { 40, 75, 23, 100 } @@ -70,6 +73,9 @@ static float getYawPidScale(float input) { void ezTuneUpdate(void) { if (ezTune()->enabled) { + //Enforce RC auto smoothing + rxConfigMutable()->autoSmooth = 1; + // Setup filtering //Set Dterm LPF pidProfileMutable()->dterm_lpf_hz = MAX(ezTune()->filterHz - 5, 50); @@ -137,5 +143,8 @@ void ezTuneUpdate(void) { ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcExpo8 = scaleRange(ezTune()->rate, 0, 200, 40, 100); ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcYawExpo8 = scaleRange(ezTune()->rate, 0, 200, 40, 100); + //D-Boost snappiness + pidProfileMutable()->dBoostMin = scaleRangef(ezTune()->snappiness, 0, 100, 1.0f, 0.0f); + } } \ No newline at end of file diff --git a/src/main/flight/ez_tune.h b/src/main/flight/ez_tune.h index 5fcc1ef6f7f..d923dca2199 100644 --- a/src/main/flight/ez_tune.h +++ b/src/main/flight/ez_tune.h @@ -36,6 +36,7 @@ typedef struct ezTuneSettings_s { uint8_t aggressiveness; uint8_t rate; uint8_t expo; + uint8_t snappiness; } ezTuneSettings_t; PG_DECLARE_PROFILE(ezTuneSettings_t, ezTune); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 834841e6580..716b48d7aa4 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -57,6 +57,9 @@ #include "sensors/battery.h" +#define MAX_THROTTLE 2000 +#define MAX_THROTTLE_ROVER 1850 + FASTRAM int16_t motor[MAX_SUPPORTED_MOTORS]; FASTRAM int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; static float motorMixRange; @@ -83,12 +86,11 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 10); +PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 11); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT, .motorPwmRate = SETTING_MOTOR_PWM_RATE_DEFAULT, - .maxthrottle = SETTING_MAX_THROTTLE_DEFAULT, .mincommand = SETTING_MIN_COMMAND_DEFAULT, .motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles ); @@ -106,7 +108,7 @@ void pgResetFn_timerOverrides(timerOverride_t *instance) int getThrottleIdleValue(void) { if (!throttleIdleValue) { - throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * currentBatteryProfile->motor.throttleIdle); + throttleIdleValue = motorConfig()->mincommand + (((getMaxThrottle() - motorConfig()->mincommand) / 100.0f) * currentBatteryProfile->motor.throttleIdle); } return throttleIdleValue; @@ -242,11 +244,11 @@ void mixerResetDisarmedMotors(void) if (feature(FEATURE_REVERSIBLE_MOTORS)) { motorZeroCommand = reversibleMotorsConfig()->neutral; throttleRangeMin = throttleDeadbandHigh; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); } else { motorZeroCommand = motorConfig()->mincommand; throttleRangeMin = throttleIdleValue; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); } reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; @@ -357,7 +359,7 @@ static void applyTurtleModeToMotors(void) { motorOutputNormalised = MIN(1.0f, flipPower * motorOutputNormalised); - motor[i] = (int16_t)scaleRangef(motorOutputNormalised, 0, 1, motorConfig()->mincommand, motorConfig()->maxthrottle); + motor[i] = (int16_t)scaleRangef(motorOutputNormalised, 0, 1, motorConfig()->mincommand, getMaxThrottle()); } } else { // Disarmed mode @@ -407,7 +409,7 @@ void FAST_CODE writeMotors(void) throttleIdleValue, DSHOT_DISARM_COMMAND, motorConfig()->mincommand, - motorConfig()->maxthrottle, + getMaxThrottle(), DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE, true @@ -424,7 +426,7 @@ void FAST_CODE writeMotors(void) throttleRangeMin, throttleRangeMax, reversibleMotorsConfig()->deadband_high, - motorConfig()->maxthrottle, + getMaxThrottle(), true ); } else { @@ -551,7 +553,7 @@ void FAST_CODE mixTable(void) #ifdef USE_PROGRAMMING_FRAMEWORK if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE)) { throttleRangeMin = throttleIdleValue; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); mixerThrottleCommand = constrain(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax); } else #endif @@ -562,7 +564,7 @@ void FAST_CODE mixTable(void) * Throttle is above deadband, FORWARD direction */ reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); throttleRangeMin = throttleDeadbandHigh; DISABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD); } else if (rcCommand[THROTTLE] <= throttleDeadbandLow) { @@ -591,7 +593,7 @@ void FAST_CODE mixTable(void) } else { mixerThrottleCommand = rcCommand[THROTTLE]; throttleRangeMin = throttleIdleValue; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); // Throttle scaling to limit max throttle when battery is full #ifdef USE_PROGRAMMING_FRAMEWORK @@ -630,7 +632,7 @@ void FAST_CODE mixTable(void) motor[i] = rpyMix[i] + constrain(mixerThrottleCommand * currentMixer[i].throttle, throttleMin, throttleMax); if (failsafeIsActive()) { - motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle); + motor[i] = constrain(motor[i], motorConfig()->mincommand, getMaxThrottle()); } else { motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax); } @@ -652,7 +654,7 @@ int16_t getThrottlePercent(bool useScaled) int16_t thr = constrain(mixerThrottleCommand, PWM_RANGE_MIN, PWM_RANGE_MAX); if (useScaled) { - thr = (thr - throttleIdleValue) * 100 / (motorConfig()->maxthrottle - throttleIdleValue); + thr = (thr - throttleIdleValue) * 100 / (getMaxThrottle() - throttleIdleValue); } else { thr = (rxGetChannelValue(THROTTLE) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); } @@ -667,7 +669,7 @@ uint16_t setDesiredThrottle(uint16_t throttle, bool allowMotorStop) ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); return throttle; } - return constrain(throttle, throttleIdleValue, motorConfig()->maxthrottle); + return constrain(throttle, throttleIdleValue, getMaxThrottle()); } motorStatus_e getMotorStatus(void) @@ -725,3 +727,18 @@ bool areMotorsRunning(void) return false; } + +uint16_t getMaxThrottle(void) { + + static uint16_t throttle = 0; + + if (throttle == 0) { + if (STATE(ROVER) || STATE(BOAT)) { + throttle = MAX_THROTTLE_ROVER; + } else { + throttle = MAX_THROTTLE; + } + } + + return throttle; +} \ No newline at end of file diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 9ee6a20654e..0d40fdc11ec 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -81,7 +81,6 @@ PG_DECLARE(reversibleMotorsConfig_t, reversibleMotorsConfig); typedef struct motorConfig_s { // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms) - uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz) uint8_t motorPwmProtocol; @@ -130,4 +129,6 @@ void stopMotorsNoDelay(void); void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); -bool areMotorsRunning(void); \ No newline at end of file +bool areMotorsRunning(void); + +uint16_t getMaxThrottle(void); \ No newline at end of file diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 7b2590ff70b..5769b56fbdb 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -79,7 +79,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) } } -void activateMixerConfig(){ +void activateMixerConfig(void){ currentMixerProfileIndex = getConfigMixerProfile(); currentMixerConfig = *mixerConfig(); nextMixerProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 61a5083dfe0..558d722b2d3 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -100,7 +100,6 @@ typedef struct { biquadFilter_t dBoostGyroLpf; float dBoostTargetAcceleration; #endif - uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; bool itermLimitActive; bool itermFreezeActive; @@ -171,7 +170,7 @@ static EXTENDED_FASTRAM bool angleHoldIsLevel = false; static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 6); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 7); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -265,8 +264,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .max_angle_inclination[FD_ROLL] = SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT, .max_angle_inclination[FD_PITCH] = SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT, - .pidSumLimit = SETTING_PIDSUM_LIMIT_DEFAULT, - .pidSumLimitYaw = SETTING_PIDSUM_LIMIT_YAW_DEFAULT, .pidItermLimitPercent = SETTING_PID_ITERM_LIMIT_PERCENT_DEFAULT, .fixedWingReferenceAirspeed = SETTING_FW_REFERENCE_AIRSPEED_DEFAULT, @@ -467,8 +464,8 @@ static float calculateMultirotorTPAFactor(void) // TPA should be updated only when TPA is actually set if (currentControlRateProfile->throttle.dynPID == 0 || rcCommand[THROTTLE] < currentControlRateProfile->throttle.pa_breakpoint) { tpaFactor = 1.0f; - } else if (rcCommand[THROTTLE] < motorConfig()->maxthrottle) { - tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (rcCommand[THROTTLE] - currentControlRateProfile->throttle.pa_breakpoint) / (float)(motorConfig()->maxthrottle - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; + } else if (rcCommand[THROTTLE] < getMaxThrottle()) { + tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (rcCommand[THROTTLE] - currentControlRateProfile->throttle.pa_breakpoint) / (float)(getMaxThrottle() - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; } else { tpaFactor = (100 - currentControlRateProfile->throttle.dynPID) / 100.0f; } @@ -773,12 +770,14 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh applyItermLimiting(pidState); + const uint16_t limit = getPidSumLimit(axis); + if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; + float itermLimit = limit * pidProfile()->pidItermLimitPercent * 0.01f; pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } - axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); + axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -limit, +limit); if (FLIGHT_MODE(SOARING_MODE) && axis == FD_PITCH && calculateRollPitchCenterStatus() == CENTERED) { if (!angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw.soaring_pitch_deadband), FD_PITCH)) { @@ -788,7 +787,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh #ifdef USE_AUTOTUNE_FIXED_WING if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) { - autotuneFixedWingUpdate(axis, rateTarget, pidState->gyroRate, constrainf(newPTerm + newFFTerm, -pidState->pidSumLimit, +pidState->pidSumLimit)); + autotuneFixedWingUpdate(axis, rateTarget, pidState->gyroRate, constrainf(newPTerm + newFFTerm, -limit, +limit)); } #endif @@ -837,9 +836,11 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid */ const float newCDTerm = rateTargetDeltaFiltered * pidState->kCD; + const uint16_t limit = getPidSumLimit(axis); + // TODO: Get feedback from mixer on available correction range for each axis const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; - const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); + const float newOutputLimited = constrainf(newOutput, -limit, +limit); float itermErrorRate = applyItermRelax(axis, rateTarget, rateError); @@ -851,7 +852,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; + float itermLimit = limit * pidProfile()->pidItermLimitPercent * 0.01f; pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } @@ -1289,14 +1290,12 @@ void pidInit(void) pidState[axis].axis = axis; if (axis == FD_YAW) { - pidState[axis].pidSumLimit = pidProfile()->pidSumLimitYaw; if (yawLpfHz) { pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) pt1FilterApply4; } else { pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) nullFilterApply4; } } else { - pidState[axis].pidSumLimit = pidProfile()->pidSumLimit; pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) nullFilterApply4; } } @@ -1413,3 +1412,11 @@ float getFixedWingLevelTrim(void) { return STATE(AIRPLANE) ? fixedWingLevelTrim : 0; } + +uint16_t getPidSumLimit(const flight_dynamics_index_t axis) { + if (axis == FD_YAW) { + return STATE(MULTIROTOR) ? 400 : 500; + } else { + return 500; + } +} \ No newline at end of file diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index e0a8b9d310b..e088ccffadf 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -115,8 +115,6 @@ typedef struct pidProfile_s { int16_t max_angle_inclination[ANGLE_INDEX_COUNT]; // Max possible inclination (roll and pitch axis separately - uint16_t pidSumLimit; - uint16_t pidSumLimitYaw; uint16_t pidItermLimitPercent; // Airplane-specific parameters @@ -221,3 +219,4 @@ bool isFixedWingLevelTrimActive(void); void updateFixedWingLevelTrim(timeUs_t currentTimeUs); float getFixedWingLevelTrim(void); bool isAngleHoldLevel(void); +uint16_t getPidSumLimit(const flight_dynamics_index_t axis); \ No newline at end of file diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index 140c4ab61d9..af6896f4233 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -171,7 +171,7 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa float gainFF = tuneCurrent[axis].gainFF; float maxDesiredRate = maxRateSetting; - const float pidSumLimit = (axis == FD_YAW) ? pidProfile()->pidSumLimitYaw : pidProfile()->pidSumLimit; + const float pidSumLimit = getPidSumLimit(axis); const float absDesiredRate = fabsf(desiredRate); const float absReachedRate = fabsf(reachedRate); const float absPidOutput = fabsf(pidOutput); diff --git a/src/main/io/displayport_msp_osd.c b/src/main/io/displayport_msp_osd.c index e1e6cb29676..0d797e1f756 100644 --- a/src/main/io/displayport_msp_osd.c +++ b/src/main/io/displayport_msp_osd.c @@ -525,7 +525,7 @@ void mspOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn) } } -mspPort_t *getMspOsdPort() +mspPort_t *getMspOsdPort(void) { if (mspPort.port) { return &mspPort; diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index 47cc96f834b..07bc181d1c1 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -122,8 +122,8 @@ int8_t radarGetNearestPOI(void) */ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitude, uint8_t poiType, uint16_t poiSymbol, int16_t poiP1, int16_t poiP2) { - int poi_x; - int poi_y; + int poi_x = -1; + int poi_y = -1; uint8_t center_x; uint8_t center_y; bool poi_is_oos = 0; diff --git a/src/main/main.c b/src/main/main.c index c002fbab25c..c303602dcbc 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -27,6 +27,11 @@ #include "scheduler/scheduler.h" +#if defined(SITL_BUILD) +#include "target/SITL/serial_proxy.h" +#endif + + #ifdef SOFTSERIAL_LOOPBACK serialPort_t *loopbackPort; #endif @@ -65,6 +70,9 @@ int main(void) loopbackInit(); while (true) { +#if defined(SITL_BUILD) + serialProxyProcess(); +#endif scheduler(); processLoopback(); } diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 66e883ab8c7..3312e5bc25d 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -108,3 +108,5 @@ #define MSP2_INAV_CUSTOM_OSD_ELEMENTS 0x2100 #define MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS 0x2101 +#define MSP2_INAV_SERVO_CONFIG 0x2200 +#define MSP2_INAV_SET_SERVO_CONFIG 0x2201 \ No newline at end of file diff --git a/src/main/navigation/navigation_declination_gen.c b/src/main/navigation/navigation_declination_gen.c index 04e1c731726..c7d632cd87c 100644 --- a/src/main/navigation/navigation_declination_gen.c +++ b/src/main/navigation/navigation_declination_gen.c @@ -1,7 +1,7 @@ /* this file is automatically generated by src/utils/declination.py - DO NOT EDIT! */ -/* Updated on 2019-05-16 19:59:45.672184 */ +/* Updated on 2024-04-19 12:54:15.842704 */ #include @@ -16,25 +16,25 @@ #define SAMPLING_MAX_LAT 90.00000f static const float declination_table[19][37] = { - {149.21545f,139.21545f,129.21545f,119.21545f,109.21545f,99.21545f,89.21545f,79.21545f,69.21545f,59.21545f,49.21545f,39.21545f,29.21545f,19.21545f,9.21545f,-0.78455f,-10.78455f,-20.78455f,-30.78455f,-40.78455f,-50.78455f,-60.78455f,-70.78455f,-80.78455f,-90.78455f,-100.78455f,-110.78455f,-120.78455f,-130.78455f,-140.78455f,-150.78455f,-160.78455f,-170.78455f,179.21545f,169.21545f,159.21545f,149.21545f}, - {129.49173f,117.24379f,106.10409f,95.92286f,86.51411f,77.69583f,69.30955f,61.22803f,53.35622f,45.62814f,38.00071f,30.44524f,22.93795f,15.45138f,7.94874f,0.38309f,-7.29841f,-15.14665f,-23.20230f,-31.49030f,-40.01947f,-48.78754f,-57.79007f,-67.03110f,-76.53295f,-86.34401f,-96.54357f,-107.24276f,-118.57946f,-130.70159f,-143.72988f,-157.69312f,-172.44642f,172.37735f,157.31228f,142.89420f,129.49173f}, - {85.58549f,77.67225f,71.30884f,65.86377f,60.92589f,56.17990f,51.37001f,46.30480f,40.87538f,35.06788f,28.95999f,22.69753f,16.44959f,10.34723f,4.42361f,-1.41547f,-7.36729f,-13.65814f,-20.45428f,-27.80115f,-35.61613f,-43.73164f,-51.96263f,-60.16701f,-68.28139f,-76.33426f,-84.45291f,-92.88710f,-102.08596f,-112.90534f,-127.14324f,-148.72029f,177.01697f,138.42469f,112.13402f,96.22709f,85.58549f}, - {47.63660f,46.34868f,44.88668f,43.46724f,42.13334f,40.75578f,39.03991f,36.60567f,33.13133f,28.48297f,22.78165f,16.40811f,9.93011f,3.92458f,-1.26916f,-5.73344f,-9.95561f,-14.59663f,-20.17634f,-26.83800f,-34.30473f,-42.04900f,-49.54378f,-56.41737f,-62.46557f,-67.58445f,-71.67147f,-74.48888f,-75.41488f,-72.72854f,-60.65739f,-20.78150f,26.31817f,42.64478f,47.39885f,48.29568f,47.63660f}, - {30.97061f,31.18244f,30.92007f,30.51421f,30.19783f,30.07382f,29.96272f,29.32724f,27.44230f,23.71829f,17.99066f,10.70786f,2.93356f,-4.02123f,-9.25421f,-12.72420f,-15.16719f,-17.68585f,-21.36741f,-26.80526f,-33.62817f,-40.77079f,-47.22749f,-52.37678f,-55.85085f,-57.33789f,-56.38997f,-52.20324f,-43.65581f,-30.23589f,-13.76879f,1.84396f,13.87138f,22.01689f,27.05355f,29.80197f,30.97061f}, - {22.35701f,22.87747f,22.95380f,22.77246f,22.50130f,22.37009f,22.48347f,22.51381f,21.59756f,18.63829f,12.92222f,4.75452f,-4.29892f,-12.13023f,-17.44827f,-20.36076f,-21.71093f,-22.23838f,-22.95576f,-25.55066f,-30.56100f,-36.48539f,-41.58017f,-44.82620f,-45.65465f,-43.72977f,-38.84914f,-30.98997f,-21.09926f,-11.31468f,-3.00404f,3.97652f,9.93802f,14.84528f,18.57977f,21.04644f,22.35701f}, - {16.83374f,17.31701f,17.52984f,17.52512f,17.27497f,16.89826f,16.64631f,16.52197f,15.82359f,13.20018f,7.50544f,-1.01430f,-10.31063f,-17.86218f,-22.52054f,-24.77956f,-25.51811f,-24.67883f,-22.16922f,-20.17352f,-21.46713f,-25.48482f,-29.63408f,-31.91043f,-31.42054f,-28.23519f,-22.87573f,-15.95318f,-8.88587f,-3.41726f,0.43088f,3.87433f,7.44305f,10.85242f,13.73685f,15.75505f,16.83374f}, - {13.16653f,13.42584f,13.56856f,13.64914f,13.49908f,13.04415f,12.54312f,12.17294f,11.33249f,8.62333f,2.85124f,-5.49975f,-14.06214f,-20.49962f,-23.98868f,-24.97282f,-24.13471f,-21.32697f,-16.43179f,-11.33581f,-9.07326f,-10.72561f,-14.43596f,-17.29905f,-17.69300f,-15.77796f,-12.24267f,-7.56947f,-3.00400f,-0.11834f,1.39928f,3.14408f,5.63638f,8.32414f,10.72028f,12.39111f,13.16653f}, - {10.90437f,10.88236f,10.81163f,10.86511f,10.80010f,10.39894f,9.91702f,9.49494f,8.41184f,5.36760f,-0.47690f,-8.26124f,-15.66061f,-20.76090f,-22.78986f,-21.89942f,-18.89020f,-14.52921f,-9.53528f,-4.91597f,-1.91353f,-1.76484f,-4.25201f,-7.17489f,-8.55660f,-8.15241f,-6.39303f,-3.54345f,-0.64444f,0.81130f,1.15035f,2.11074f,4.17898f,6.59237f,8.80142f,10.33532f,10.90437f}, - {9.69156f,9.50282f,9.23338f,9.25605f,9.28344f,8.98186f,8.56848f,8.04846f,6.56771f,3.06569f,-2.75457f,-9.75616f,-15.91853f,-19.62874f,-20.10653f,-17.62100f,-13.38807f,-8.80249f,-4.83206f,-1.62618f,0.85458f,1.72352f,0.35339f,-2.00271f,-3.58526f,-3.93648f,-3.30170f,-1.78891f,-0.13334f,0.41999f,0.14853f,0.72192f,2.61852f,5.02104f,7.34668f,9.06648f,9.69156f}, - {8.99220f,9.02256f,8.80901f,8.93941f,9.15462f,8.99412f,8.49413f,7.54605f,5.38233f,1.29060f,-4.51973f,-10.72800f,-15.61393f,-17.87879f,-17.08037f,-13.87843f,-9.54744f,-5.34026f,-2.15287f,0.11672f,2.02473f,3.04733f,2.31093f,0.47960f,-0.96646f,-1.54925f,-1.53032f,-1.00772f,-0.42112f,-0.63497f,-1.37540f,-1.17754f,0.48492f,2.94585f,5.61932f,7.87900f,8.99220f}, - {8.04368f,8.88487f,9.24731f,9.76871f,10.30385f,10.32830f,9.60849f,7.94603f,4.81731f,-0.08975f,-6.10101f,-11.65411f,-15.25677f,-16.15822f,-14.52060f,-11.22653f,-7.24580f,-3.44558f,-0.61333f,1.25309f,2.76805f,3.73177f,3.36695f,1.97948f,0.74967f,0.13075f,-0.18979f,-0.42444f,-0.85420f,-1.93961f,-3.28866f,-3.62225f,-2.35247f,0.08639f,3.11990f,6.05468f,8.04368f}, - {6.44887f,8.52898f,10.00772f,11.25814f,12.19628f,12.38325f,11.43950f,9.05774f,4.87180f,-1.07081f,-7.58681f,-12.76972f,-15.34699f,-15.21292f,-13.06213f,-9.80318f,-6.10115f,-2.52848f,0.26062f,2.11110f,3.47313f,4.40612f,4.43031f,3.60979f,2.68625f,2.01876f,1.34276f,0.35243f,-1.18272f,-3.35038f,-5.50704f,-6.45531f,-5.60558f,-3.25332f,0.01287f,3.49652f,6.44887f}, - {4.61309f,7.91484f,10.67459f,12.86217f,14.28349f,14.59916f,13.44634f,10.43327f,5.19620f,-1.95110f,-9.25904f,-14.43995f,-16.45824f,-15.72227f,-13.22423f,-9.85034f,-6.14231f,-2.53072f,0.48676f,2.68447f,4.29956f,5.52570f,6.19623f,6.20084f,5.73301f,4.92006f,3.60085f,1.53163f,-1.39438f,-4.87688f,-7.94536f,-9.43097f,-8.85100f,-6.51552f,-3.06017f,0.84306f,4.61309f}, - {3.21875f,7.41586f,11.19354f,14.28261f,16.32057f,16.89633f,15.56524f,11.80300f,5.20653f,-3.55470f,-11.97809f,-17.43029f,-19.22616f,-18.17302f,-15.37952f,-11.69571f,-7.65025f,-3.63286f,-0.01295f,2.99661f,5.46716f,7.56207f,9.25413f,10.31810f,10.49165f,9.54146f,7.26006f,3.54973f,-1.33752f,-6.50635f,-10.55663f,-12.38793f,-11.79132f,-9.25449f,-5.49875f,-1.18292f,3.21875f}, - {2.52051f,7.33138f,11.79037f,15.58977f,18.29190f,19.30865f,17.85567f,12.95067f,3.98293f,-7.53431f,-17.54806f,-23.19596f,-24.60407f,-23.07402f,-19.77569f,-15.49637f,-10.73649f,-5.85097f,-1.12175f,3.26826f,7.26895f,10.88888f,14.03678f,16.41453f,17.52792f,16.76756f,13.54324f,7.61980f,-0.22282f,-7.89770f,-13.19396f,-15.21847f,-14.33135f,-11.37454f,-7.18383f,-2.40863f,2.52051f}, - {2.02983f,7.36989f,12.37081f,16.71056f,19.89761f,21.11515f,18.97400f,11.40232f,-2.70274f,-18.81527f,-29.66002f,-33.88571f,-33.57644f,-30.58814f,-26.04521f,-20.59815f,-14.64262f,-8.44459f,-2.20066f,3.93897f,9.85468f,15.42277f,20.45728f,24.64081f,27.44761f,28.04182f,25.18387f,17.54097f,5.49796f,-6.72811f,-14.58218f,-17.34691f,-16.39748f,-13.14509f,-8.58967f,-3.38880f,2.02983f}, - {0.42359f,5.67280f,10.45897f,14.18719f,15.84273f,13.44387f,3.31185f,-17.06908f,-37.86930f,-48.41039f,-50.74957f,-48.66334f,-44.20871f,-38.40471f,-31.78712f,-24.66267f,-17.22360f,-9.60278f,-1.90231f,5.78964f,13.38658f,20.79088f,27.87654f,34.46122f,40.25514f,44.75763f,47.03469f,45.25758f,36.18138f,17.77476f,-1.60905f,-12.11869f,-14.89059f,-13.37813f,-9.65915f,-4.84192f,0.42359f}, - {-178.76222f,-168.76222f,-158.76222f,-148.76222f,-138.76222f,-128.76222f,-118.76222f,-108.76222f,-98.76222f,-88.76222f,-78.76222f,-68.76222f,-58.76222f,-48.76222f,-38.76222f,-28.76222f,-18.76222f,-8.76222f,1.23778f,11.23778f,21.23778f,31.23778f,41.23778f,51.23778f,61.23778f,71.23778f,81.23778f,91.23778f,101.23778f,111.23778f,121.23778f,131.23778f,141.23778f,151.23778f,161.23778f,171.23778f,-178.76222f} + {148.63040f,138.63040f,128.63040f,118.63040f,108.63040f,98.63040f,88.63040f,78.63040f,68.63040f,58.63040f,48.63040f,38.63040f,28.63040f,18.63040f,8.63040f,-1.36960f,-11.36960f,-21.36960f,-31.36960f,-41.36960f,-51.36960f,-61.36960f,-71.36960f,-81.36960f,-91.36960f,-101.36960f,-111.36960f,-121.36960f,-131.36960f,-141.36960f,-151.36960f,-161.36960f,-171.36960f,178.63040f,168.63040f,158.63040f,148.63040f}, + {128.87816f,116.70769f,105.62443f,95.48127f,86.09683f,77.29367f,68.91718f,60.84302f,52.97822f,45.25811f,37.64003f,30.09478f,22.59702f,15.11676f,7.61418f,0.03947f,-7.66207f,-15.54157f,-23.63819f,-31.97410f,-40.55489f,-49.37538f,-58.42917f,-67.71936f,-77.26833f,-87.12519f,-97.37007f,-108.11458f,-119.49579f,-131.65830f,-144.71588f,-158.68662f,-173.41452f,171.47213f,156.49935f,142.18469f,128.87816f}, + {85.86755f,77.88182f,71.42849f,65.89217f,60.86962f,56.04972f,51.17842f,46.06489f,40.60132f,34.77619f,28.67056f,22.43282f,16.23087f,10.18755f,4.31917f,-1.49067f,-7.45797f,-13.81467f,-20.71641f,-28.18762f,-36.12471f,-44.34676f,-52.66473f,-60.93937f,-69.11381f,-77.22546f,-85.41334f,-93.94372f,-103.29064f,-114.35005f,-128.97727f,-151.06023f,174.83520f,137.67818f,112.23020f,96.52063f,85.86756f}, + {48.43188f,46.98353f,45.36982f,43.80186f,42.32760f,40.82382f,38.99678f,36.46379f,32.90329f,28.18877f,22.45599f,16.10387f,9.71432f,3.86202f,-1.14650f,-5.45997f,-9.64078f,-14.38658f,-20.18766f,-27.11174f,-34.80967f,-42.71859f,-50.31107f,-57.23008f,-63.28782f,-68.39719f,-72.47622f,-75.31221f,-76.30788f,-73.74072f,-61.55512f,-18.96160f,29.20071f,44.46666f,48.67974f,49.28540f,48.43188f}, + {31.58850f,31.74835f,31.39924f,30.87678f,30.43574f,30.19800f,29.98360f,29.24010f,27.23113f,23.37602f,17.54538f,10.24099f,2.57680f,-4.11819f,-8.98330f,-12.08874f,-14.32383f,-16.91831f,-20.97106f,-26.92020f,-34.17714f,-41.56631f,-48.09571f,-53.19469f,-56.53278f,-57.82558f,-56.66031f,-52.27310f,-43.55594f,-29.95085f,-13.24765f,2.54212f,14.60798f,22.72224f,27.72553f,30.44935f,31.58850f}, + {22.79850f,23.32533f,23.34746f,23.05694f,22.66226f,22.42885f,22.46289f,22.41289f,21.37705f,18.23370f,12.30982f,4.02530f,-4.93197f,-12.42012f,-17.23389f,-19.62803f,-20.56810f,-20.93312f,-21.98947f,-25.41090f,-31.19026f,-37.44166f,-42.49725f,-45.51856f,-46.02918f,-43.74555f,-38.55838f,-30.56411f,-20.73773f,-11.07131f,-2.79308f,4.21937f,10.21441f,15.15242f,18.92948f,21.44642f,22.79850f}, + {17.16987f,17.68582f,17.85385f,17.73377f,17.34906f,16.86130f,16.52747f,16.34574f,15.56790f,12.74839f,6.74610f,-2.00418f,-11.22826f,-18.37193f,-22.46233f,-24.19496f,-24.47888f,-23.22908f,-20.72783f,-19.60150f,-21.98233f,-26.43395f,-30.43203f,-32.35125f,-31.47499f,-27.95264f,-22.40690f,-15.51422f,-8.63620f,-3.35146f,0.42144f,3.87188f,7.48128f,10.95260f,13.91406f,16.01563f,17.16987f}, + {13.46149f,13.75829f,13.85281f,13.81813f,13.52893f,12.94281f,12.32698f,11.88976f,11.00215f,8.11359f,1.99478f,-6.62228f,-15.08744f,-21.05798f,-23.92224f,-24.34577f,-23.04831f,-19.84546f,-14.88685f,-10.38631f,-9.06427f,-11.31395f,-15.06340f,-17.65505f,-17.71488f,-15.54256f,-11.89991f,-7.27581f,-2.87289f,-0.16517f,1.24684f,2.97092f,5.51371f,8.29954f,10.80542f,12.58786f,13.46149f}, + {11.19370f,11.20122f,11.07257f,11.02175f,10.82482f,10.26986f,9.62418f,9.09716f,7.97068f,4.77978f,-1.35469f,-9.31946f,-16.55524f,-21.15274f,-22.50861f,-21.01857f,-17.63827f,-13.15823f,-8.29683f,-4.01764f,-1.51484f,-1.87967f,-4.62279f,-7.47003f,-8.63091f,-8.05888f,-6.24442f,-3.42551f,-0.62936f,0.67783f,0.89029f,1.80510f,3.93778f,6.48671f,8.83523f,10.50781f,11.19370f}, + {9.96310f,9.79689f,9.46606f,9.40362f,9.31492f,8.84240f,8.22130f,7.55735f,6.02850f,2.43377f,-3.55150f,-10.60044f,-16.54723f,-19.75861f,-19.59018f,-16.58982f,-12.16100f,-7.67553f,-3.93189f,-0.91522f,1.34973f,1.87637f,0.22653f,-2.15228f,-3.61566f,-3.90720f,-3.29932f,-1.83286f,-0.23997f,0.20367f,-0.19418f,0.32122f,2.29252f,4.85536f,7.33778f,9.21090f,9.96310f}, + {9.18888f,9.24336f,8.98253f,9.05281f,9.17191f,8.83598f,8.10836f,7.00345f,4.80464f,0.69064f,-5.15618f,-11.30079f,-15.93916f,-17.74937f,-16.42349f,-12.86230f,-8.44857f,-4.38855f,-1.42704f,0.70613f,2.51072f,3.31152f,2.34785f,0.48172f,-0.89199f,-1.49634f,-1.59901f,-1.18437f,-0.66243f,-0.94842f,-1.78088f,-1.62463f,0.11657f,2.73547f,5.55820f,7.95812f,9.18888f}, + {8.09034f,8.95675f,9.30400f,9.80188f,10.27100f,10.13647f,9.19791f,7.38846f,4.25004f,-0.60600f,-6.53915f,-11.93135f,-15.26054f,-15.79066f,-13.79060f,-10.27561f,-6.25103f,-2.56551f,0.07346f,1.80766f,3.24155f,4.05015f,3.51428f,2.10305f,0.93136f,0.25053f,-0.27213f,-0.70545f,-1.24346f,-2.37500f,-3.75122f,-4.07408f,-2.71911f,-0.15132f,2.99380f,6.02278f,8.09034f}, + {6.27792f,8.37723f,9.88296f,11.16334f,12.08487f,12.15767f,11.03142f,8.51947f,4.34248f,-1.47518f,-7.78911f,-12.71269f,-15.01118f,-14.61457f,-12.25578f,-8.87216f,-5.13675f,-1.63793f,0.99774f,2.71417f,3.98293f,4.78698f,4.67468f,3.82712f,2.93970f,2.18792f,1.25958f,-0.01231f,-1.71794f,-3.92282f,-6.03566f,-6.90283f,-5.95491f,-3.51614f,-0.20102f,3.30598f,6.27792f}, + {4.15672f,7.47883f,10.31556f,12.59798f,14.06987f,14.34572f,13.08042f,9.97537f,4.77447f,-2.16465f,-9.14687f,-14.00316f,-15.77819f,-14.88455f,-12.28640f,-8.84845f,-5.11869f,-1.55612f,1.34605f,3.41756f,4.91977f,6.01696f,6.56254f,6.51350f,6.02774f,5.09138f,3.48456f,1.07344f,-2.08240f,-5.60383f,-8.56486f,-9.89888f,-9.20525f,-6.83312f,-3.41374f,0.42499f,4.15672f}, + {2.38746f,6.60961f,10.51138f,13.76537f,15.94256f,16.59043f,15.27093f,11.52705f,5.06990f,-3.36003f,-11.36932f,-16.51244f,-18.15167f,-17.03678f,-14.21651f,-10.51524f,-6.47146f,-2.49805f,1.03216f,3.92789f,6.27640f,8.24229f,9.81368f,10.78355f,10.85070f,9.68870f,7.04509f,2.91449f,-2.25894f,-7.44786f,-11.30963f,-12.92043f,-12.20858f,-9.70263f,-6.08438f,-1.92562f,2.38746f}, + {1.14371f,5.95768f,10.55039f,14.56595f,17.51248f,18.77049f,17.56825f,12.99646f,4.54568f,-6.33792f,-15.91121f,-21.43028f,-22.88293f,-21.44177f,-18.22110f,-13.99911f,-9.28961f,-4.46489f,0.18470f,4.47851f,8.37200f,11.87759f,14.90388f,17.13814f,18.04159f,16.93503f,13.18748f,6.66358f,-1.56678f,-9.20492f,-14.20053f,-15.96059f,-14.99797f,-12.15657f,-8.19328f,-3.64820f,1.14371f}, + {-0.35955f,4.92766f,9.99739f,14.51863f,17.99503f,19.64821f,18.23668f,11.99980f,-0.09657f,-14.74873f,-25.55246f,-30.33910f,-30.58104f,-28.00627f,-23.75441f,-18.51083f,-12.70165f,-6.61593f,-0.46628f,5.58665f,11.41580f,16.88997f,21.81133f,25.83916f,28.40134f,28.57592f,24.99531f,16.28607f,3.28542f,-9.10495f,-16.59733f,-19.05958f,-18.04316f,-14.91590f,-10.58486f,-5.61478f,-0.35955f}, + {-5.35521f,-0.10619f,4.69597f,8.54683f,10.65268f,9.65875f,3.42678f,-9.71040f,-26.04578f,-37.63969f,-42.28407f,-42.02380f,-38.82980f,-33.88684f,-27.86664f,-21.16414f,-14.02720f,-6.62426f,0.91924f,8.49972f,16.02040f,23.37681f,30.43782f,37.01500f,42.80483f,47.26542f,49.32663f,46.69337f,34.75696f,10.85970f,-10.89085f,-20.36338f,-21.94791f,-19.71753f,-15.63466f,-10.66363f,-5.35521f}, + {-166.99999f,-156.99999f,-146.99999f,-136.99999f,-126.99999f,-116.99999f,-106.99999f,-96.99999f,-86.99999f,-76.99999f,-66.99999f,-56.99999f,-46.99999f,-36.99999f,-26.99999f,-16.99999f,-6.99999f,3.00001f,13.00001f,23.00001f,33.00000f,43.00000f,53.00000f,63.00000f,73.00000f,83.00000f,93.00000f,103.00000f,113.00000f,123.00000f,133.00000f,143.00000f,153.00000f,163.00000f,173.00000f,-177.00000f,-167.00000f} }; #else /* !NAV_AUTO_MAG_DECLINATION_PRECISE */ @@ -45,19 +45,19 @@ static const float declination_table[19][37] = { #define SAMPLING_MAX_LAT 60.00000f static const int8_t declination_table[13][37] = { - {48,46,45,43,42,41,39,37,33,28,23,16,10,4,-1,-6,-10,-15,-20,-27,-34,-42,-50,-56,-62,-68,-72,-74,-75,-73,-61,-21,26,43,47,48,48}, - {31,31,31,31,30,30,30,29,27,24,18,11,3,-4,-9,-13,-15,-18,-21,-27,-34,-41,-47,-52,-56,-57,-56,-52,-44,-30,-14,2,14,22,27,30,31}, - {22,23,23,23,23,22,22,23,22,19,13,5,-4,-12,-17,-20,-22,-22,-23,-26,-31,-36,-42,-45,-46,-44,-39,-31,-21,-11,-3,4,10,15,19,21,22}, - {17,17,18,18,17,17,17,17,16,13,8,-1,-10,-18,-23,-25,-26,-25,-22,-20,-21,-25,-30,-32,-31,-28,-23,-16,-9,-3,0,4,7,11,14,16,17}, - {13,13,14,14,13,13,13,12,11,9,3,-5,-14,-20,-24,-25,-24,-21,-16,-11,-9,-11,-14,-17,-18,-16,-12,-8,-3,0,1,3,6,8,11,12,13}, - {11,11,11,11,11,10,10,9,8,5,0,-8,-16,-21,-23,-22,-19,-15,-10,-5,-2,-2,-4,-7,-9,-8,-6,-4,-1,1,1,2,4,7,9,10,11}, - {10,10,9,9,9,9,9,8,7,3,-3,-10,-16,-20,-20,-18,-13,-9,-5,-2,1,2,0,-2,-4,-4,-3,-2,0,0,0,1,3,5,7,9,10}, - {9,9,9,9,9,9,8,8,5,1,-5,-11,-16,-18,-17,-14,-10,-5,-2,0,2,3,2,0,-1,-2,-2,-1,0,-1,-1,-1,0,3,6,8,9}, - {8,9,9,10,10,10,10,8,5,0,-6,-12,-15,-16,-15,-11,-7,-3,-1,1,3,4,3,2,1,0,0,0,-1,-2,-3,-4,-2,0,3,6,8}, - {6,9,10,11,12,12,11,9,5,-1,-8,-13,-15,-15,-13,-10,-6,-3,0,2,3,4,4,4,3,2,1,0,-1,-3,-6,-6,-6,-3,0,3,6}, - {5,8,11,13,14,15,13,10,5,-2,-9,-14,-16,-16,-13,-10,-6,-3,0,3,4,6,6,6,6,5,4,2,-1,-5,-8,-9,-9,-7,-3,1,5}, - {3,7,11,14,16,17,16,12,5,-4,-12,-17,-19,-18,-15,-12,-8,-4,0,3,5,8,9,10,10,10,7,4,-1,-7,-11,-12,-12,-9,-5,-1,3}, - {3,7,12,16,18,19,18,13,4,-8,-18,-23,-25,-23,-20,-15,-11,-6,-1,3,7,11,14,16,18,17,14,8,0,-8,-13,-15,-14,-11,-7,-2,3} + {48,47,45,44,42,41,39,36,33,28,22,16,10,4,-1,-5,-10,-14,-20,-27,-35,-43,-50,-57,-63,-68,-72,-75,-76,-74,-62,-19,29,44,49,49,48}, + {32,32,31,31,30,30,30,29,27,23,18,10,3,-4,-9,-12,-14,-17,-21,-27,-34,-42,-48,-53,-57,-58,-57,-52,-44,-30,-13,3,15,23,28,30,32}, + {23,23,23,23,23,22,22,22,21,18,12,4,-5,-12,-17,-20,-21,-21,-22,-25,-31,-37,-42,-46,-46,-44,-39,-31,-21,-11,-3,4,10,15,19,21,23}, + {17,18,18,18,17,17,17,16,16,13,7,-2,-11,-18,-22,-24,-24,-23,-21,-20,-22,-26,-30,-32,-31,-28,-22,-16,-9,-3,0,4,7,11,14,16,17}, + {13,14,14,14,14,13,12,12,11,8,2,-7,-15,-21,-24,-24,-23,-20,-15,-10,-9,-11,-15,-18,-18,-16,-12,-7,-3,0,1,3,6,8,11,13,13}, + {11,11,11,11,11,10,10,9,8,5,-1,-9,-17,-21,-23,-21,-18,-13,-8,-4,-2,-2,-5,-7,-9,-8,-6,-3,-1,1,1,2,4,6,9,11,11}, + {10,10,9,9,9,9,8,8,6,2,-4,-11,-17,-20,-20,-17,-12,-8,-4,-1,1,2,0,-2,-4,-4,-3,-2,0,0,0,0,2,5,7,9,10}, + {9,9,9,9,9,9,8,7,5,1,-5,-11,-16,-18,-16,-13,-8,-4,-1,1,3,3,2,0,-1,-1,-2,-1,-1,-1,-2,-2,0,3,6,8,9}, + {8,9,9,10,10,10,9,7,4,-1,-7,-12,-15,-16,-14,-10,-6,-3,0,2,3,4,4,2,1,0,0,-1,-1,-2,-4,-4,-3,0,3,6,8}, + {6,8,10,11,12,12,11,9,4,-1,-8,-13,-15,-15,-12,-9,-5,-2,1,3,4,5,5,4,3,2,1,0,-2,-4,-6,-7,-6,-4,0,3,6}, + {4,7,10,13,14,14,13,10,5,-2,-9,-14,-16,-15,-12,-9,-5,-2,1,3,5,6,7,7,6,5,3,1,-2,-6,-9,-10,-9,-7,-3,0,4}, + {2,7,11,14,16,17,15,12,5,-3,-11,-17,-18,-17,-14,-11,-6,-2,1,4,6,8,10,11,11,10,7,3,-2,-7,-11,-13,-12,-10,-6,-2,2}, + {1,6,11,15,18,19,18,13,5,-6,-16,-21,-23,-21,-18,-14,-9,-4,0,4,8,12,15,17,18,17,13,7,-2,-9,-14,-16,-15,-12,-8,-4,1} }; #endif diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index e6209f460b7..49fbf11ab5b 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -647,7 +647,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat if (rcCommand[THROTTLE] < PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * 0.95){ correctedThrottleValue += MAX(0, rcCommand[THROTTLE] - currentBatteryProfile->nav.fw.cruise_throttle); } else { - correctedThrottleValue = motorConfig()->maxthrottle; + correctedThrottleValue = getMaxThrottle(); } isAutoThrottleManuallyIncreased = (rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle); } else { diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index a9a6997a9f0..54caccb52b5 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -114,7 +114,7 @@ static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) { // Calculate min and max throttle boundaries (to compensate for integral windup) const int16_t thrCorrectionMin = getThrottleIdleValue() - currentBatteryProfile->nav.mc.hover_throttle; - const int16_t thrCorrectionMax = motorConfig()->maxthrottle - currentBatteryProfile->nav.mc.hover_throttle; + const int16_t thrCorrectionMax = getMaxThrottle() - currentBatteryProfile->nav.mc.hover_throttle; float velocity_controller = navPidApply2(&posControl.pids.vel[Z], posControl.desiredState.vel.z, navGetCurrentActualPositionAndVelocity()->vel.z, US2S(deltaMicros), thrCorrectionMin, thrCorrectionMax, 0); @@ -127,7 +127,7 @@ static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) bool adjustMulticopterAltitudeFromRCInput(void) { if (posControl.flags.isTerrainFollowEnabled) { - const float altTarget = scaleRangef(rcCommand[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle, 0, navConfig()->general.max_terrain_follow_altitude); + const float altTarget = scaleRangef(rcCommand[THROTTLE], getThrottleIdleValue(), getMaxThrottle(), 0, navConfig()->general.max_terrain_follow_altitude); // In terrain follow mode we apply different logic for terrain control if (posControl.flags.estAglStatus == EST_TRUSTED && altTarget > 10.0f) { @@ -151,7 +151,7 @@ bool adjustMulticopterAltitudeFromRCInput(void) // Make sure we can satisfy max_manual_climb_rate in both up and down directions if (rcThrottleAdjustment > 0) { // Scaling from altHoldThrottleRCZero to maxthrottle - rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / (float)(motorConfig()->maxthrottle - altHoldThrottleRCZero - rcControlsConfig()->alt_hold_deadband); + rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / (float)(getMaxThrottle() - altHoldThrottleRCZero - rcControlsConfig()->alt_hold_deadband); } else { // Scaling from minthrottle to altHoldThrottleRCZero @@ -190,7 +190,7 @@ void setupMulticopterAltitudeController(void) // Make sure we are able to satisfy the deadband altHoldThrottleRCZero = constrain(altHoldThrottleRCZero, getThrottleIdleValue() + rcControlsConfig()->alt_hold_deadband + 10, - motorConfig()->maxthrottle - rcControlsConfig()->alt_hold_deadband - 10); + getMaxThrottle() - rcControlsConfig()->alt_hold_deadband - 10); // Force AH controller to initialize althold integral for pending takeoff on reset // Signal for that is low throttle _and_ low actual altitude diff --git a/src/main/navigation/navigation_rover_boat.c b/src/main/navigation/navigation_rover_boat.c index 5f8134c6a24..8816880388a 100644 --- a/src/main/navigation/navigation_rover_boat.c +++ b/src/main/navigation/navigation_rover_boat.c @@ -127,7 +127,7 @@ void applyRoverBoatPitchRollThrottleController(navigationFSMStateFlags_t navStat rcCommand[YAW] = posControl.rcAdjustment[YAW]; } - rcCommand[THROTTLE] = constrain(currentBatteryProfile->nav.fw.cruise_throttle, motorConfig()->mincommand, motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain(currentBatteryProfile->nav.fw.cruise_throttle, motorConfig()->mincommand, getMaxThrottle()); } } } diff --git a/src/main/rx/sim.c b/src/main/rx/sim.c index a2a336f612e..62d9a9b864c 100644 --- a/src/main/rx/sim.c +++ b/src/main/rx/sim.c @@ -31,15 +31,14 @@ static uint16_t channels[MAX_SUPPORTED_RC_CHANNEL_COUNT]; static bool hasNewData = false; +static uint16_t rssi = 0; -static uint16_t rxSimReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan) -{ +static uint16_t rxSimReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan) { UNUSED(rxRuntimeConfigPtr); return channels[chan]; } -void rxSimSetChannelValue(uint16_t* values, uint8_t count) -{ +void rxSimSetChannelValue(uint16_t* values, uint8_t count) { for (size_t i = 0; i < count; i++) { channels[i] = values[i]; } @@ -47,10 +46,11 @@ void rxSimSetChannelValue(uint16_t* values, uint8_t count) hasNewData = true; } -static uint8_t rxSimFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) -{ +static uint8_t rxSimFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) { UNUSED(rxRuntimeConfig); + lqTrackerSet(rxRuntimeConfig->lqTracker, rssi); + if (!hasNewData) { return RX_FRAME_PENDING; } @@ -59,8 +59,7 @@ static uint8_t rxSimFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) return RX_FRAME_COMPLETE; } -void rxSimInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) -{ +void rxSimInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) { UNUSED(rxConfig); rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT; @@ -68,4 +67,8 @@ void rxSimInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) rxRuntimeConfig->rcReadRawFn = rxSimReadRawRC; rxRuntimeConfig->rcFrameStatusFn = rxSimFrameStatus; } + +void rxSimSetRssi(uint16_t value) { + rssi = value; +} #endif diff --git a/src/main/rx/sim.h b/src/main/rx/sim.h index 88342acad73..9c8ff36d1b0 100644 --- a/src/main/rx/sim.h +++ b/src/main/rx/sim.h @@ -20,4 +20,5 @@ #include "rx/rx.h" void rxSimSetChannelValue(uint16_t* values, uint8_t count); +void rxSimSetRssi(uint16_t value); void rxSimInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 3745ed7a8ea..2ca7024694e 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -66,7 +66,7 @@ #define ADCVREF 3300 // in mV (3300 = 3.3V) #define VBATT_CELL_FULL_MAX_DIFF 10 // Max difference with cell max voltage for the battery to be considered full (10mV steps) -#define VBATT_PRESENT_THRESHOLD 100 // Minimum voltage to consider battery present +#define VBATT_PRESENT_THRESHOLD 220 // Minimum voltage to consider battery present #define VBATT_STABLE_DELAY 40 // Delay after connecting battery to begin monitoring #define VBATT_HYSTERESIS 10 // Batt Hysteresis of +/-100mV for changing battery state #define VBATT_LPF_FREQ 1 // Battery voltage filtering cutoff diff --git a/src/main/target/AOCODARCF4V3/CMakeLists.txt b/src/main/target/AOCODARCF4V3/CMakeLists.txt new file mode 100644 index 00000000000..706b818e2b8 --- /dev/null +++ b/src/main/target/AOCODARCF4V3/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f405xg(AOCODARCF4V3_SD) +target_stm32f405xg(AOCODARCF4V3) + diff --git a/src/main/target/AOCODARCF4V3/config.c b/src/main/target/AOCODARCF4V3/config.c new file mode 100644 index 00000000000..c80a92940a9 --- /dev/null +++ b/src/main/target/AOCODARCF4V3/config.c @@ -0,0 +1,40 @@ +/* + * 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 . + */ +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +//#include "fc/config.h" + +#include "io/piniobox.h" +#include "drivers/serial.h" +#include "io/serial.h" +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + pinioBoxConfigMutable()->permanentId[2] = BOX_PERMANENT_ID_USER3; + // beeperConfigMutable()->pwmMode = true; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].msp_baudrateIndex = BAUD_115200; + serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_VTX_TRAMP; + serialConfigMutable()->portConfigs[4].peripheral_baudrateIndex = BAUD_115200; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_RX_SERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_ESCSERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_GPS; +} diff --git a/src/main/target/AOCODARCF4V3/target.c b/src/main/target/AOCODARCF4V3/target.c new file mode 100644 index 00000000000..8581cc5bf11 --- /dev/null +++ b/src/main/target/AOCODARCF4V3/target.c @@ -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 . + */ + + +#include + +#include "platform.h" +#include "drivers/io.h" +#include "drivers/timer.h" +#include "drivers/pwm_mapping.h" +#include "drivers/bus.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN + + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4 + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S6 + + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8 + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), // LED_STRIP + + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF4V3/target.h b/src/main/target/AOCODARCF4V3/target.h new file mode 100644 index 00000000000..0c95564162e --- /dev/null +++ b/src/main/target/AOCODARCF4V3/target.h @@ -0,0 +1,192 @@ +/* + * 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 . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#ifdef AOCODARCF4V3 +#define TARGET_BOARD_IDENTIFIER "AOF4V3" +#define USBD_PRODUCT_STRING "AOCODARCF4V3" +#else +#define TARGET_BOARD_IDENTIFIER "AOF4V3SD" +#define USBD_PRODUCT_STRING "AOCODARCF4V3_SD" +#endif + +// ******** Board LEDs ********************** +#define LED0 PC13 + +// ******* Beeper *********** +#define BEEPER PB8 +#define BEEPER_INVERTED + + +// ******* GYRO and ACC ******** +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW90_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN PA4 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW90_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + + +// *************** Baro ************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 + +#define I2C1_SCL PB6 // SCL +#define I2C1_SDA PB7 // SDA +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS + +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#define USE_MAG_ALL + +// ******* SERIAL ******** +#define USE_VCP +#define VBUS_SENSING_PIN PB12 +#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_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + + +#define SERIAL_PORT_COUNT 6 + + +// ******* SPI ******** +#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_NSS_PIN PA13 +#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 + +// ******* ADC ******** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 + +#define VBAT_SCALE_DEFAULT 1100 +#define CURRENT_METER_SCALE 206 + +// ******* OSD ******** +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PA13 + +//******* FLASH ******** +#if defined(AOCODARCF4V3_SD) +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC0 +#define SDCARD_DETECT_INVERTED +#define SDCARD_DETECT_PIN PC14 +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#else +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PC0 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#endif +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC5 // VTX power switcher +#define PINIO2_PIN PA14 //bluetooth +#define PINIO3_PIN PC15 //Camera control +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED +#define PINIO2_FLAGS PINIO_FLAGS_INVERTED + +//************ LEDSTRIP ***************** +#define USE_LED_STRIP +#define WS2811_PIN PB1 + +// ******* FEATURES ******** +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART2 +#define SERIALRX_PROVIDER SERIALRX_CRSF + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_GPS | FEATURE_BLACKBOX | FEATURE_LED_STRIP) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 10 + +// ESC-related features +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/AOCODARCH7DUAL/target.c b/src/main/target/AOCODARCH7DUAL/target.c index 85e8b004937..ac3be127191 100644 --- a/src/main/target/AOCODARCH7DUAL/target.c +++ b/src/main/target/AOCODARCH7DUAL/target.c @@ -36,11 +36,11 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - - DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 + + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE diff --git a/src/main/target/ASGARD32F4/config.c b/src/main/target/ASGARD32F4/config.c index 9aaa2793ce3..fee09920388 100644 --- a/src/main/target/ASGARD32F4/config.c +++ b/src/main/target/ASGARD32F4/config.c @@ -36,5 +36,4 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; - motorConfigMutable()->maxthrottle = 1950; } diff --git a/src/main/target/ASGARD32F7/config.c b/src/main/target/ASGARD32F7/config.c index 9aaa2793ce3..fee09920388 100644 --- a/src/main/target/ASGARD32F7/config.c +++ b/src/main/target/ASGARD32F7/config.c @@ -36,5 +36,4 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; - motorConfigMutable()->maxthrottle = 1950; } diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.h b/src/main/target/IFLIGHT_BLITZ_F722/target.h index 0ced96ad5fb..cea6b4422ac 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.h @@ -42,6 +42,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + // *************** I2C /Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 diff --git a/src/main/target/JHEMCUF405WING/CMakeLists.txt b/src/main/target/JHEMCUF405WING/CMakeLists.txt new file mode 100644 index 00000000000..fb99881c9bd --- /dev/null +++ b/src/main/target/JHEMCUF405WING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(JHEMCUF405WING) diff --git a/src/main/target/JHEMCUF405WING/config.c b/src/main/target/JHEMCUF405WING/config.c new file mode 100644 index 00000000000..07f44ab29f7 --- /dev/null +++ b/src/main/target/JHEMCUF405WING/config.c @@ -0,0 +1,42 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" +#include "io/serial.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_GPS; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_MSP; + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} diff --git a/src/main/target/JHEMCUF405WING/target.c b/src/main/target/JHEMCUF405WING/target.c new file mode 100644 index 00000000000..e8187f936b2 --- /dev/null +++ b/src/main/target/JHEMCUF405WING/target.c @@ -0,0 +1,47 @@ +/* + * 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 . + */ +#include +#include +#include + +#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" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S2 D(1,0,2) + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(2,7,7) + + DEF_TIM(TIM8, CH2N,PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 + DEF_TIM(TIM12, CH2,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // 2812LED + DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), // TX2 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/JHEMCUF405WING/target.h b/src/main/target/JHEMCUF405WING/target.h new file mode 100644 index 00000000000..fd64ff153d6 --- /dev/null +++ b/src/main/target/JHEMCUF405WING/target.h @@ -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 . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "JH45" +#define USBD_PRODUCT_STRING "JHEMCUF405WING" + +// LEDs +#define LED0 PA14 //Blue +#define LED1 PA13 //Green + +// Beeper +#define BEEPER PC15 +#define BEEPER_INVERTED + +// SPI1 +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +// SPI2 +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +// SPI3 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// Serial ports +#define USE_VCP + +#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_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +// Optional Softserial on UART2 TX Pin PA2 +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 8 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + +// Baro +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_ALL + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +// OSD +#define USE_MAX7456 +#define MAX7456_CS_PIN PB12 +#define MAX7456_SPI_BUS BUS_SPI2 + +// SD Card +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC14 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART1 + +// ADC +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC5 +#define ADC_CHANNEL_4_PIN PC4 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_4 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 + +// LED2812 +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// PINIO +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC13 // 2xCamera switcher + +// OTHERS +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX | FEATURE_AIRMODE) +#define CURRENT_METER_SCALE 175 + +#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 11 \ No newline at end of file diff --git a/src/main/target/JHEMCUF745/CMakeLists.txt b/src/main/target/JHEMCUF745/CMakeLists.txt new file mode 100644 index 00000000000..5f5a85e7c5d --- /dev/null +++ b/src/main/target/JHEMCUF745/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f745xg(JHEMCUF745) diff --git a/src/main/target/JHEMCUF745/config.c b/src/main/target/JHEMCUF745/config.c new file mode 100644 index 00000000000..fb2fe04f963 --- /dev/null +++ b/src/main/target/JHEMCUF745/config.c @@ -0,0 +1,29 @@ +/* + * 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 . + */ + +#include +#include + +#include + +#include "drivers/pwm_mapping.h" + +void targetConfiguration(void) +{ + timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/JHEMCUF745/target.c b/src/main/target/JHEMCUF745/target.c new file mode 100644 index 00000000000..f603cbe43be --- /dev/null +++ b/src/main/target/JHEMCUF745/target.c @@ -0,0 +1,44 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/bus.h" +#include "drivers/pinio.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1, DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2, DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // M3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // M4, DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5, DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // M6, DMA1_ST1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/JHEMCUF745/target.h b/src/main/target/JHEMCUF745/target.h new file mode 100644 index 00000000000..dfd45749d2d --- /dev/null +++ b/src/main/target/JHEMCUF745/target.h @@ -0,0 +1,157 @@ +/* + * This file is part of INAV. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "JHF7" +#define USBD_PRODUCT_STRING "JHEMCUF745" + +#define LED0 PA2 + +#define BEEPER PD15 +#define BEEPER_INVERTED + +#define USE_DSHOT +#define USE_DSHOT_DMAR +#define USE_ESC_SENSOR + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define GYRO_INT_EXTI PE1 +#define MPU6000_CS_PIN SPI4_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_CS_PIN SPI4_NSS_PIN +#define ICM42605_SPI_BUS BUS_SPI4 +#define ICM42605_EXTI_PIN PE1 + +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_ENABLED +#define VBUS_SENSING_PIN PA8 + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_RX_PIN PE7 +#define UART7_TX_PIN PE8 + +#define SERIAL_PORT_COUNT 8 // VCP,UART1,UART2,UART3,UART4,UART5,UART6 + +#define USE_SPI +#define USE_SPI_DEVICE_1 // FLASH +#define USE_SPI_DEVICE_2 // OSD +#define USE_SPI_DEVICE_4 // ICM20689 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SPI4_NSS_PIN PE4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +#define M25P16_CS_PIN SPI1_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI1 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +// External I2C bus is the same as interal one +#define MAG_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define USE_BARO_ALL +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define USE_MAG_ALL + +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC5 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_VBAT | FEATURE_BLACKBOX) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define USE_LED_STRIP +#define WS2811_PIN PD12 + +#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 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 diff --git a/src/main/target/JHEMCUH743HD/CMakeLists.txt b/src/main/target/JHEMCUH743HD/CMakeLists.txt new file mode 100644 index 00000000000..b0192886d6c --- /dev/null +++ b/src/main/target/JHEMCUH743HD/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(JHEMCUH743HD) \ No newline at end of file diff --git a/src/main/target/JHEMCUH743HD/config.c b/src/main/target/JHEMCUH743HD/config.c new file mode 100644 index 00000000000..4f0aea919e7 --- /dev/null +++ b/src/main/target/JHEMCUH743HD/config.c @@ -0,0 +1,66 @@ +/* + * 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 . + */ + +#include +#include + +#include + +#include "common/axis.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" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + + + /* + * 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; +} diff --git a/src/main/target/JHEMCUH743HD/target.c b/src/main/target/JHEMCUH743HD/target.c new file mode 100644 index 00000000000..adb753b9d17 --- /dev/null +++ b/src/main/target/JHEMCUH743HD/target.c @@ -0,0 +1,49 @@ +/* + * 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 . + */ + +#include + +#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_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); + + +timerHardware_t timerHardware[] = { + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/JHEMCUH743HD/target.h b/src/main/target/JHEMCUH743HD/target.h new file mode 100644 index 00000000000..92300b52564 --- /dev/null +++ b/src/main/target/JHEMCUH743HD/target.h @@ -0,0 +1,205 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "JHEH743HD" +#define USBD_PRODUCT_STRING "JHEMCUH743HD" + +#define USE_TARGET_CONFIG + +#define LED0 PE5 +#define LED1 PE4 + +#define BEEPER PE3 +#define BEEPER_INVERTED + +// *************** IMU generic *********************** +#define USE_DUAL_GYRO +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +// *************** SPI1 IMU0 MPU6000 **************** +#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_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + +// *************** SPI2 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 + +// *************** SPI3 FLASH *********************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB2 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_AF GPIO_AF6_SPI3 +#define SPI3_MISO_AF GPIO_AF6_SPI3 +#define SPI3_MOSI_AF GPIO_AF7_SPI3 + +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN + +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN SPI3_NSS_PIN + +#define USE_BLACKBOX +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_ALL + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 + +#define USE_UART4 +#define UART4_TX_PIN PD1 +#define UART4_RX_PIN PD0 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define SERIAL_PORT_COUNT 9 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +// *************** ADC ***************************** +#define USE_ADC +#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_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC2 +#define ADC_CHANNEL_4_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +#endif + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX + +#define PINIO1_PIN PC2 +#define PINIO2_PIN PC5 + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL) +#define CURRENT_METER_SCALE 250 + +#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 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/SITL/serial_proxy.c b/src/main/target/SITL/serial_proxy.c new file mode 100644 index 00000000000..281fefd3ede --- /dev/null +++ b/src/main/target/SITL/serial_proxy.c @@ -0,0 +1,784 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#include "serial_proxy.h" + +#if defined(SITL_BUILD) + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#include +#include +#include +#include +#include + +#include "drivers/time.h" +#include "msp/msp_serial.h" +#include "msp/msp_protocol.h" +#include "common/crc.h" +#include "rx/sim.h" + +#include + +#ifdef __FreeBSD__ +# define __BSD_VISIBLE 1 +#endif + +#ifdef __linux__ +#include +#ifndef TCGETS2 +#include +#endif +#else +#include +#endif + +#ifdef __APPLE__ +#include +#endif + +#include "drivers/serial_tcp.h" + +#define SYM_BEGIN '$' +#define SYM_PROTO_V1 'M' +#define SYM_PROTO_V2 'X' +#define SYM_FROM_MWC '>' +#define SYM_TO_MWC '<' +#define SYM_UNSUPPORTED '!' + +#define JUMBO_FRAME_MIN_SIZE 255 +#define MAX_MSP_MESSAGE 1024 +#define RX_CONFIG_SIZE 24 + +typedef enum { + DS_IDLE, + DS_PROTO_IDENTIFIER, + DS_DIRECTION_V1, + DS_DIRECTION_V2, + DS_FLAG_V2, + DS_PAYLOAD_LENGTH_V1, + DS_PAYLOAD_LENGTH_JUMBO_LOW, + DS_PAYLOAD_LENGTH_JUMBO_HIGH, + DS_PAYLOAD_LENGTH_V2_LOW, + DS_PAYLOAD_LENGTH_V2_HIGH, + DS_CODE_V1, + DS_CODE_JUMBO_V1, + DS_CODE_V2_LOW, + DS_CODE_V2_HIGH, + DS_PAYLOAD_V1, + DS_PAYLOAD_V2, + DS_CHECKSUM_V1, + DS_CHECKSUM_V2, +} TDecoderState; + +static TDecoderState decoderState = DS_IDLE; + +typedef enum { + RXC_IDLE = 0, + RXC_RQ = 1, + RXC_DONE = 2 +} TRXConfigState; + +static TRXConfigState rxConfigState = RXC_IDLE; + +static int message_length_expected; +static unsigned char message_buffer[MAX_MSP_MESSAGE]; +static int message_length_received; +static int unsupported; +static int code; +static int message_direction; +static uint8_t message_checksum; +static int reqCount = 0; +static uint16_t rssi = 0; +static uint8_t rxConfigBuffer[RX_CONFIG_SIZE]; + +static timeMs_t lastWarning = 0; + +int serialUartIndex = -1; +char serialPort[64] = ""; +int serialBaudRate = 115200; +OptSerialStopBits_e serialStopBits = OPT_SERIAL_STOP_BITS_ONE; //0:None|1:One|2:OnePointFive|3:Two +OptSerialParity_e serialParity = OPT_SERIAL_PARITY_NONE; +bool serialFCProxy = false; + +#define FC_PROXY_REQUEST_PERIOD_MIN_MS 20 //inav can handle 100 msp messages per second max +#define FC_PROXY_REQUEST_PERIOD_TIMEOUT_MS 200 +#define FC_PROXY_REQUEST_PERIOD_RSSI_MS 300 +#define SERIAL_BUFFER_SIZE 256 + +#if defined(__CYGWIN__) +#include +static HANDLE hSerial; +#else +static int fd; +#endif + +static bool connected = false; +static bool started = false; + +static timeMs_t nextProxyRequestTimeout = 0; +static timeMs_t nextProxyRequestMin = 0; +static timeMs_t nextProxyRequestRssi = 0; + +static timeMs_t lastVisit = 0; + +#if !defined(__CYGWIN__) +#if !defined( __linux__) && !defined(__APPLE__) +static int rate_to_constant(int baudrate) +{ +#ifdef __FreeBSD__ + return baudrate; +#else +#define B(x) case x: return B##x + switch (baudrate) { + B(50); + B(75); + B(110); + B(134); + B(150); + B(200); + B(300); + B(600); + B(1200); + B(1800); + B(2400); + B(4800); + B(9600); + B(19200); + B(38400); + B(57600); + B(115200); + B(230400); + default: + return 0; + } +#undef B +#endif +} +#endif + +static void close_serial(void) +{ +#ifdef __linux__ + ioctl(fd, TCFLSH, TCIOFLUSH); +#else + tcflush(fd, TCIOFLUSH); +#endif + close(fd); +} + +static int set_fd_speed(void) +{ + int res = -1; +#ifdef __linux__ + // Just user BOTHER for everything (allows non-standard speeds) + struct termios2 t; + if ((res = ioctl(fd, TCGETS2, &t)) != -1) { + t.c_cflag &= ~CBAUD; + t.c_cflag |= BOTHER; + t.c_ospeed = t.c_ispeed = serialBaudRate; + res = ioctl(fd, TCSETS2, &t); + } +#elif __APPLE__ + speed_t speed = serialBaudRate; + res = ioctl(fd, IOSSIOSPEED, &speed); +#else + int speed = rate_to_constant(serialBaudRate); + struct termios term; + if (tcgetattr(fd, &term)) return -1; + if (speed == 0) { + res = -1; + } else { + if (cfsetispeed(&term, speed) != -1) { + cfsetospeed(&term, speed); + res = tcsetattr(fd, TCSANOW, &term); + } + if (res != -1) { + memset(&term, 0, sizeof(term)); + res = (tcgetattr(fd, &term)); + } + } +#endif + return res; +} + +static int set_attributes(void) +{ + struct termios tio; + memset (&tio, 0, sizeof(tio)); + int res = -1; +#ifdef __linux__ + res = ioctl(fd, TCGETS, &tio); +#else + res = tcgetattr(fd, &tio); +#endif + if (res != -1) { + // cfmakeraw ... + tio.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL | IXON); + tio.c_oflag &= ~OPOST; + tio.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN); + tio.c_cflag &= ~(CSIZE | PARENB); + tio.c_cflag |= CS8 | CREAD | CLOCAL; + tio.c_cc[VTIME] = 0; + tio.c_cc[VMIN] = 0; + + switch (serialStopBits) { + case OPT_SERIAL_STOP_BITS_ONE: + tio.c_cflag &= ~CSTOPB; + break; + case OPT_SERIAL_STOP_BITS_TWO: + tio.c_cflag |= CSTOPB; + break; + case OPT_SERIAL_STOP_BITS_INVALID: + break; + } + + switch (serialParity) { + case OPT_SERIAL_PARITY_EVEN: + tio.c_cflag |= PARENB; + tio.c_cflag &= ~PARODD; + break; + case OPT_SERIAL_PARITY_NONE: + tio.c_cflag &= ~PARENB; + tio.c_cflag &= ~PARODD; + break; + case OPT_SERIAL_PARITY_ODD: + tio.c_cflag |= PARENB; + tio.c_cflag |= PARODD; + break; + case OPT_SERIAL_PARITY_INVALID: + break; + } +#ifdef __linux__ + res = ioctl(fd, TCSETS, &tio); +#else + res = tcsetattr(fd, TCSANOW, &tio); +#endif + } + if (res != -1) { + res = set_fd_speed(); + } + return res; +} +#endif + +void serialProxyInit(void) +{ + char portName[64 + 20]; + if ( strlen(serialPort) < 1) { + return; + } + connected = false; + +#if defined(__CYGWIN__) + sprintf(portName, "\\\\.\\%s", serialPort); + + hSerial = CreateFile(portName, + GENERIC_READ | GENERIC_WRITE, + 0, + NULL, + OPEN_EXISTING, + FILE_ATTRIBUTE_NORMAL, + NULL); + + if (hSerial == INVALID_HANDLE_VALUE) { + if (GetLastError() == ERROR_FILE_NOT_FOUND) { + fprintf(stderr, "[SERIALPROXY] ERROR: Sserial port was not attached. Reason: %s not available.\n", portName); + } else { + fprintf(stderr, "[SERIALPROXY] ERROR: Can not connect to serial port, unknown error.\n"); + } + return; + } else { + DCB dcbSerialParams = { 0 }; + if (!GetCommState(hSerial, &dcbSerialParams)) { + fprintf(stderr, "[SERIALPROXY] ALERT: failed to get current serial parameters!\n"); + } else { + dcbSerialParams.BaudRate = serialBaudRate; + dcbSerialParams.ByteSize = 8; + + // Disable software flow control (XON/XOFF) + dcbSerialParams.fOutX = FALSE; + dcbSerialParams.fInX = FALSE; + + // Disable hardware flow control (RTS/CTS) + dcbSerialParams.fRtsControl = RTS_CONTROL_DISABLE; + dcbSerialParams.fDtrControl = DTR_CONTROL_DISABLE; + + // Disable any special processing of bytes + dcbSerialParams.fBinary = TRUE; + + switch (serialStopBits) { + case OPT_SERIAL_STOP_BITS_ONE: + dcbSerialParams.StopBits = ONESTOPBIT; + break; + case OPT_SERIAL_STOP_BITS_TWO: + dcbSerialParams.StopBits = TWOSTOPBITS; + break; + case OPT_SERIAL_STOP_BITS_INVALID: + break; + } + + switch (serialParity) { + case OPT_SERIAL_PARITY_EVEN: + dcbSerialParams.Parity = EVENPARITY; + break; + case OPT_SERIAL_PARITY_NONE: + dcbSerialParams.Parity = NOPARITY; + break; + case OPT_SERIAL_PARITY_ODD: + dcbSerialParams.Parity = ODDPARITY; + break; + case OPT_SERIAL_PARITY_INVALID: + break; + } + + if (!SetCommState(hSerial, &dcbSerialParams)) { + fprintf(stderr, "[SERIALPROXY] ALERT: Could not set Serial Port parameters\n"); + } else { + COMMTIMEOUTS comTimeOut; + comTimeOut.ReadIntervalTimeout = MAXDWORD; + comTimeOut.ReadTotalTimeoutMultiplier = 0; + comTimeOut.ReadTotalTimeoutConstant = 0; + comTimeOut.WriteTotalTimeoutMultiplier = 0; + comTimeOut.WriteTotalTimeoutConstant = 0; + SetCommTimeouts(hSerial, &comTimeOut); + } + } + } +#else + strcpy(portName, serialPort); // because, windows ... + fd = open(serialPort, O_RDWR | O_NOCTTY); + if (fd != -1) { + int res = 1; + res = set_attributes(); + if (res == -1) { + fprintf(stderr, "[SERIALPROXY] ALERT: Failed to configure device: %s %s\n", portName, strerror(errno)); + close(fd); + fd = -1; + } + } else { + fprintf(stderr, "[SERIALPROXY] ERROR: Can not connect to serial port %s\n", portName); + return; + } +#endif + connected = true; + + if ( !serialFCProxy ) { + fprintf(stderr, "[SERIALPROXY] Connected %s to UART%d\n", portName, serialUartIndex); + } else { + fprintf(stderr, "[SERIALPROXY] Using proxy flight controller on %s\n", portName); + } +} + +void serialProxyStart(void) +{ + started = true; +} + +void serialProxyClose(void) +{ + if (connected) { + connected = false; +#if defined(__CYGWIN__) + CloseHandle(hSerial); +#else + close_serial(); +#endif + started = false; + nextProxyRequestTimeout = 0; + nextProxyRequestMin = 0; + nextProxyRequestRssi = 0; + lastWarning = 0; + lastVisit = 0; + } +} + +static bool canOutputWarning(void) +{ + if ( millis() > lastWarning ) { + lastWarning = millis() + 5000; + return true; + } + return false; +} + +int serialProxyReadData(unsigned char *buffer, unsigned int nbChar) +{ + if (!connected) return 0; + +#if defined(__CYGWIN__) + COMSTAT status; + DWORD errors; + DWORD bytesRead; + + ClearCommError(hSerial, &errors, &status); + if (status.cbInQue > 0) { + unsigned int toRead = (status.cbInQue > nbChar) ? nbChar : status.cbInQue; + if (ReadFile(hSerial, buffer, toRead, &bytesRead, NULL) && (bytesRead != 0)) { + return bytesRead; + } + } + return 0; +#else + if (nbChar == 0) return 0; + int bytesRead = read(fd, buffer, nbChar); + return bytesRead; +#endif +} + +bool serialProxyWriteData(unsigned char *buffer, unsigned int nbChar) +{ + if (!connected) return false; + +#if defined(__CYGWIN__) + COMSTAT status; + DWORD errors; + DWORD bytesSent; + if (!WriteFile(hSerial, (void *)buffer, nbChar, &bytesSent, 0)) { + ClearCommError(hSerial, &errors, &status); + if ( canOutputWarning() ) { + fprintf(stderr, "[SERIALPROXY] ERROR: Can not write to serial port\n"); + } + return false; + } + if ( bytesSent != nbChar ) { + if ( canOutputWarning() ) { + fprintf(stderr, "[SERIALPROXY] ERROR: Can not write to serial port\n"); + } + } +#else + ssize_t l = write(fd, buffer, nbChar); + if ( l != (ssize_t)nbChar ) { + if ( canOutputWarning() ) { + fprintf(stderr, "[SERIALPROXY] ERROR: Can not write to serial port\n"); + } + return false; + } +#endif + return true; +} + +bool serialProxyIsConnected(void) +{ + return connected; +} + +static void mspSendCommand(int cmd, unsigned char *data, int dataLen) +{ + uint8_t msgBuf[MAX_MSP_MESSAGE] = { '$', 'X', '<' }; + int msgLen = 3; + + mspHeaderV2_t *hdrV2 = (mspHeaderV2_t *)&msgBuf[msgLen]; + hdrV2->flags = 0; + hdrV2->cmd = cmd; + hdrV2->size = dataLen; + msgLen += sizeof(mspHeaderV2_t); + + for ( int i = 0; i < dataLen; i++ ) { + msgBuf[msgLen++] = data[i]; + } + + uint8_t crc = crc8_dvb_s2_update(0, (uint8_t *)hdrV2, sizeof(mspHeaderV2_t)); + crc = crc8_dvb_s2_update(crc, data, dataLen); + msgBuf[msgLen] = crc; + msgLen++; + + serialProxyWriteData((unsigned char *)&msgBuf, msgLen); +} + +static void mspRequestChannels(void) +{ + mspSendCommand(MSP_RC, NULL, 0); +} + +static void mspRequestRssi(void) +{ + mspSendCommand(MSP_ANALOG, NULL, 0); +} + +static void requestRXConfigState(void) +{ + mspSendCommand(MSP_RX_CONFIG, NULL, 0); + rxConfigState = RXC_RQ; + fprintf(stderr, "[SERIALPROXY] Requesting RX config from proxy FC...\n"); +} + +static void processMessage(void) +{ + if ( code == MSP_RC ) { + if ( reqCount > 0 ) reqCount--; + int count = message_length_received / 2; + if ( count <= MAX_SUPPORTED_RC_CHANNEL_COUNT) { + uint16_t *channels = (uint16_t *)(&message_buffer[0]); + //AETR => AERT + uint v = channels[2]; + channels[2] = channels[3]; + channels[3] = v; + if ( rssi > 0 ) { + rxSimSetChannelValue(channels, count); + } + } + } else if ( code == MSP_ANALOG ) { + if ( reqCount > 0 ) reqCount--; + if ( message_length_received >= 7 ) { + rssi = *((uint16_t *)(&message_buffer[3])); + rxSimSetRssi( rssi ); + } + } else if ( code == MSP_RX_CONFIG ) { + memcpy( &(rxConfigBuffer[0]), &(message_buffer[0]), RX_CONFIG_SIZE ); + *((uint16_t *) & (rxConfigBuffer[1])) = 2500; //maxcheck + *((uint16_t *) & (rxConfigBuffer[5])) = 500; //mincheck + + mspSendCommand( MSP_SET_RX_CONFIG, rxConfigBuffer, RX_CONFIG_SIZE ); + rxConfigState = RXC_DONE; + fprintf(stderr, "[SERIALPROXY] Setting RX config on proxy FC...\n"); + } +} + +static void decodeProxyMessages(unsigned char *data, int len) +{ + for (int i = 0; i < len; i++) { + switch (decoderState) { + case DS_IDLE: // sync char 1 + if (data[i] == SYM_BEGIN) { + decoderState = DS_PROTO_IDENTIFIER; + } + break; + + case DS_PROTO_IDENTIFIER: // sync char 2 + switch (data[i]) { + case SYM_PROTO_V1: + decoderState = DS_DIRECTION_V1; + break; + case SYM_PROTO_V2: + decoderState = DS_DIRECTION_V2; + break; + default: + //unknown protocol + decoderState = DS_IDLE; + } + break; + + case DS_DIRECTION_V1: // direction (should be >) + + case DS_DIRECTION_V2: + unsupported = 0; + switch (data[i]) { + case SYM_FROM_MWC: + message_direction = 1; + break; + case SYM_TO_MWC: + message_direction = 0; + break; + case SYM_UNSUPPORTED: + unsupported = 1; + break; + } + decoderState = decoderState == DS_DIRECTION_V1 ? DS_PAYLOAD_LENGTH_V1 : DS_FLAG_V2; + break; + + case DS_FLAG_V2: + // Ignored for now + decoderState = DS_CODE_V2_LOW; + break; + + case DS_PAYLOAD_LENGTH_V1: + message_length_expected = data[i]; + + if (message_length_expected == JUMBO_FRAME_MIN_SIZE) { + decoderState = DS_CODE_JUMBO_V1; + } else { + message_length_received = 0; + decoderState = DS_CODE_V1; + } + break; + + case DS_PAYLOAD_LENGTH_V2_LOW: + message_length_expected = data[i]; + decoderState = DS_PAYLOAD_LENGTH_V2_HIGH; + break; + + case DS_PAYLOAD_LENGTH_V2_HIGH: + message_length_expected |= data[i] << 8; + message_length_received = 0; + if (message_length_expected <= MAX_MSP_MESSAGE) { + decoderState = message_length_expected > 0 ? DS_PAYLOAD_V2 : DS_CHECKSUM_V2; + } else { + //too large payload + decoderState = DS_IDLE; + } + break; + + case DS_CODE_V1: + case DS_CODE_JUMBO_V1: + code = data[i]; + if (message_length_expected > 0) { + // process payload + if (decoderState == DS_CODE_JUMBO_V1) { + decoderState = DS_PAYLOAD_LENGTH_JUMBO_LOW; + } else { + decoderState = DS_PAYLOAD_V1; + } + } else { + // no payload + decoderState = DS_CHECKSUM_V1; + } + break; + + case DS_CODE_V2_LOW: + code = data[i]; + decoderState = DS_CODE_V2_HIGH; + break; + + case DS_CODE_V2_HIGH: + code |= data[i] << 8; + decoderState = DS_PAYLOAD_LENGTH_V2_LOW; + break; + + case DS_PAYLOAD_LENGTH_JUMBO_LOW: + message_length_expected = data[i]; + decoderState = DS_PAYLOAD_LENGTH_JUMBO_HIGH; + break; + + case DS_PAYLOAD_LENGTH_JUMBO_HIGH: + message_length_expected |= data[i] << 8; + message_length_received = 0; + decoderState = DS_PAYLOAD_V1; + break; + + case DS_PAYLOAD_V1: + case DS_PAYLOAD_V2: + message_buffer[message_length_received] = data[i]; + message_length_received++; + + if (message_length_received >= message_length_expected) { + decoderState = decoderState == DS_PAYLOAD_V1 ? DS_CHECKSUM_V1 : DS_CHECKSUM_V2; + } + break; + + case DS_CHECKSUM_V1: + if (message_length_expected >= JUMBO_FRAME_MIN_SIZE) { + message_checksum = JUMBO_FRAME_MIN_SIZE; + } else { + message_checksum = message_length_expected; + } + message_checksum ^= code; + if (message_length_expected >= JUMBO_FRAME_MIN_SIZE) { + message_checksum ^= message_length_expected & 0xFF; + message_checksum ^= (message_length_expected & 0xFF00) >> 8; + } + for (int ii = 0; ii < message_length_received; ii++) { + message_checksum ^= message_buffer[ii]; + } + if (message_checksum == data[i]) { + processMessage(); + } + decoderState = DS_IDLE; + break; + + case DS_CHECKSUM_V2: + message_checksum = 0; + message_checksum = crc8_dvb_s2(message_checksum, 0); // flag + message_checksum = crc8_dvb_s2(message_checksum, code & 0xFF); + message_checksum = crc8_dvb_s2(message_checksum, (code & 0xFF00) >> 8); + message_checksum = crc8_dvb_s2(message_checksum, message_length_expected & 0xFF); + message_checksum = crc8_dvb_s2(message_checksum, (message_length_expected & 0xFF00) >> 8); + for (int ii = 0; ii < message_length_received; ii++) { + message_checksum = crc8_dvb_s2(message_checksum, message_buffer[ii]); + } + if (message_checksum == data[i]) { + processMessage(); + } + decoderState = DS_IDLE; + break; + + default: + break; + } + } +} + +void serialProxyProcess(void) +{ + + if (!started) return; + if (!connected) return; + + if ((millis() - lastVisit) > 500) { + if ( lastVisit > 0 ) { + fprintf(stderr, "timeout=%dms\n", millis() - lastVisit); + } + } + lastVisit = millis(); + + if ( serialFCProxy ) { + //first we have to change FC min_check and max_check thresholds to avoid activating stick commands on proxy FC + if ( rxConfigState == RXC_IDLE ) { + requestRXConfigState(); + } else if ( rxConfigState == RXC_DONE ) { + if ( (nextProxyRequestTimeout <= millis()) || ((reqCount == 0) && (nextProxyRequestMin <= millis()))) { + nextProxyRequestTimeout = millis() + FC_PROXY_REQUEST_PERIOD_TIMEOUT_MS; + nextProxyRequestMin = millis() + FC_PROXY_REQUEST_PERIOD_MIN_MS; + mspRequestChannels(); + reqCount++; + } + + if ( nextProxyRequestRssi <= millis()) { + nextProxyRequestRssi = millis() + FC_PROXY_REQUEST_PERIOD_RSSI_MS; + mspRequestRssi(); + reqCount++; + } + } + + unsigned char buf[SERIAL_BUFFER_SIZE]; + int count = serialProxyReadData(buf, SERIAL_BUFFER_SIZE); + if (count == 0) return; + decodeProxyMessages(buf, count); + + } else { + + if ( serialUartIndex == -1 ) return; + unsigned char buf[SERIAL_BUFFER_SIZE]; + uint32_t avail = tcpRXBytesFree(serialUartIndex - 1); + if ( avail == 0 ) return; + if (avail > SERIAL_BUFFER_SIZE) avail = SERIAL_BUFFER_SIZE; + + int count = serialProxyReadData(buf, avail); + if (count == 0) return; + + tcpReceiveBytesEx( serialUartIndex - 1, buf, count); + } + +} +#endif diff --git a/src/main/target/SITL/serial_proxy.h b/src/main/target/SITL/serial_proxy.h new file mode 100644 index 00000000000..5cb97516399 --- /dev/null +++ b/src/main/target/SITL/serial_proxy.h @@ -0,0 +1,64 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + + +#include +#include +#include + +#include + +#if defined(SITL_BUILD) + +typedef enum +{ + OPT_SERIAL_STOP_BITS_ONE, + OPT_SERIAL_STOP_BITS_TWO, + OPT_SERIAL_STOP_BITS_INVALID +} OptSerialStopBits_e; + +typedef enum +{ + OPT_SERIAL_PARITY_EVEN, + OPT_SERIAL_PARITY_NONE, + OPT_SERIAL_PARITY_ODD, + OPT_SERIAL_PARITY_INVALID +} OptSerialParity_e; + + +extern int serialUartIndex; ///1 for UART1 +extern char serialPort[64]; +extern int serialBaudRate; +extern OptSerialStopBits_e serialStopBits; +extern OptSerialParity_e serialParity; +extern bool serialFCProxy; + +extern void serialProxyInit(void); +extern void serialProxyStart(void); +extern void serialProxyProcess(void); +extern void serialProxyClose(void); +extern bool serialProxyIsConnected(void); +extern bool serialProxyWriteData(unsigned char *buffer, unsigned int nbChar); + +#endif \ No newline at end of file diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index e8861eec56d..e473c636981 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -56,6 +56,8 @@ #include "target/SITL/sim/realFlight.h" #include "target/SITL/sim/xplane.h" +#include "target/SITL/serial_proxy.h" + // More dummys const int timerHardwareCount = 0; timerHardware_t timerHardware[1]; @@ -170,19 +172,47 @@ bool parseMapping(char* mapStr) return true; } +OptSerialStopBits_e parseStopBits(const char* optarg){ + if ( strcmp(optarg, "One") == 0 ) { + return OPT_SERIAL_STOP_BITS_ONE; + } else if ( strcmp(optarg, "Two") == 0 ) { + return OPT_SERIAL_STOP_BITS_TWO; + } else { + return OPT_SERIAL_STOP_BITS_INVALID; + } +} + +OptSerialParity_e parseParity(const char* optarg){ + if ( strcmp(optarg, "Even") == 0 ) { + return OPT_SERIAL_PARITY_EVEN; + } else if ( strcmp(optarg, "None") == 0 ) { + return OPT_SERIAL_PARITY_NONE; + } else if ( strcmp(optarg, "Odd") == 0 ) { + return OPT_SERIAL_PARITY_ODD; + } else { + return OPT_SERIAL_PARITY_INVALID; + } +} + void printCmdLineOptions(void) { printVersion(); fprintf(stderr, "Avaiable options:\n"); - fprintf(stderr, "--path=[path] Path and filename of eeprom.bin. If not specified 'eeprom.bin' in program directory is used.\n"); - fprintf(stderr, "--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); - fprintf(stderr, "--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used.\n"); - fprintf(stderr, "--simport=[port] Port oft the simulator host.\n"); - fprintf(stderr, "--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended).\n"); - fprintf(stderr, "--chanmap=[mapstring] Channel mapping. Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); - fprintf(stderr, " The mapstring has the following format: M(otor)|S(servo)-,... All numbers must have two digits\n"); - fprintf(stderr, " For example: Map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); - fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); + fprintf(stderr, "--path=[path] Path and filename of eeprom.bin. If not specified 'eeprom.bin' in program directory is used.\n"); + fprintf(stderr, "--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); + fprintf(stderr, "--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used.\n"); + fprintf(stderr, "--simport=[port] Port oft the simulator host.\n"); + fprintf(stderr, "--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended).\n"); + fprintf(stderr, "--serialuart=[uart] UART number on which serial receiver is configured in SITL, f.e. 3 for UART3\n"); + fprintf(stderr, "--serialport=[serialport] Host's serial port to which serial receiver/proxy FC is connected, f.e. COM3, /dev/ttyACM3\n"); + fprintf(stderr, "--baudrate=[baudrate] Serial receiver baudrate (default: 115200).\n"); + fprintf(stderr, "--stopbits=[None|One|Two] Serial receiver stopbits (default: One).\n"); + fprintf(stderr, "--parity=[Even|None|Odd] Serial receiver parity (default: None).\n"); + fprintf(stderr, "--fcproxy Use inav/betaflight FC as a proxy for serial receiver.\n"); + fprintf(stderr, "--chanmap=[mapstring] Channel mapping. Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); + fprintf(stderr, " The mapstring has the following format: M(otor)|S(servo)-,... All numbers must have two digits\n"); + fprintf(stderr, " For example: Map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); + fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); } void parseArguments(int argc, char *argv[]) @@ -202,7 +232,13 @@ void parseArguments(int argc, char *argv[]) {"simport", required_argument, 0, 'p'}, {"help", no_argument, 0, 'h'}, {"path", required_argument, 0, 'e'}, - {"version", no_argument, 0, 'v'}, + {"version", no_argument, 0, 'v'}, + {"serialuart", required_argument, 0, '0'}, + {"serialport", required_argument, 0, '1'}, + {"baudrate", required_argument, 0, '2'}, + {"stopbits", required_argument, 0, '3'}, + {"parity", required_argument, 0, '4'}, + {"fcproxy", no_argument, 0, '5'}, {NULL, 0, NULL, 0} }; @@ -242,10 +278,54 @@ void parseArguments(int argc, char *argv[]) fprintf(stderr, "[EEPROM] Invalid path, using eeprom file in program directory\n."); } break; - case 'v': - printVersion(); - exit(0); - default: + case 'v': + printVersion(); + exit(0); + case '0': + serialUartIndex = atoi(optarg); + if ( (serialUartIndex<1) || (serialUartIndex>8) ) { + fprintf(stderr, "[serialuart] Invalid argument\n."); + exit(0); + } + break; + case '1': + if ( (strlen(optarg)<1) || (strlen(optarg)>63) ) { + fprintf(stderr, "[serialport] Invalid argument\n."); + exit(0); + } else { + strcpy( serialPort, optarg ); + } + break; + case '2': + serialBaudRate = atoi(optarg); + if ( serialBaudRate < 1200 ) + { + fprintf(stderr, "[baudrate] Invalid argument\n."); + exit(0); + } + break; + case '3': + serialStopBits = parseStopBits(optarg); + if ( serialStopBits == OPT_SERIAL_STOP_BITS_INVALID ) + { + fprintf(stderr, "[stopbits] Invalid argument\n."); + exit(0); + } + break; + + case '4': + serialParity = parseParity(optarg); + if ( serialParity== OPT_SERIAL_PARITY_INVALID ) + { + fprintf(stderr, "[parity] Invalid argument\n."); + exit(0); + } + break; + case '5': + serialFCProxy = true; + break; + + default: printCmdLineOptions(); exit(0); } @@ -304,6 +384,7 @@ void systemReset(void) #else closefrom(3); #endif + serialProxyClose(); execvp(c_argv[0], c_argv); // restart } diff --git a/src/main/target/ZEEZF7/target.c b/src/main/target/ZEEZF7/target.c index f1f5356dcb2..79bfc08d2cb 100755 --- a/src/main/target/ZEEZF7/target.c +++ b/src/main/target/ZEEZF7/target.c @@ -32,9 +32,9 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 #endif #ifdef ZEEZF7V2 @@ -42,10 +42,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 #endif #ifdef ZEEZF7 diff --git a/src/utils/declination.py b/src/utils/declination.py old mode 100644 new mode 100755 index 8608ffda95f..44f5c9f21db --- a/src/utils/declination.py +++ b/src/utils/declination.py @@ -14,7 +14,7 @@ import pathlib import sys -import igrf12 +import igrf import numpy as np SAMPLING_RES = 10 @@ -73,7 +73,7 @@ def declination_tables(query): for i, lat in enumerate(lats): for j, lon in enumerate(lons): - mag = igrf12.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1) + mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1) intensity[i][j] = mag.total / 1e5 inclination[i][j] = mag.incl declination[i][j] = mag.decl