Skip to content

Commit

Permalink
Merge branch 'master' into sys-id-table
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg authored Jan 20, 2025
2 parents f8e82cc + c5e8bce commit 3008d4c
Show file tree
Hide file tree
Showing 11 changed files with 76 additions and 17 deletions.
12 changes: 11 additions & 1 deletion .github/workflows/test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,17 @@ jobs:
./Sphinxsetup.sh
- name: Check image formats
run: |
find ./images/ -exec file {} + | grep RIFF -vzq
for i in $(find ./images/); do
BAD=false
if file "$i" | grep RIFF; then
echo "$i contains RIFF metadata; process file to remove"
BAD=true
fi
if $BAD; then
echo "Bad images found"
exit 1
fi
done
- name: Check python3 flake8 formatting
run : |
set -eux -o pipefail
Expand Down
35 changes: 26 additions & 9 deletions common/source/docs/common-flywoo-f745.rst
Original file line number Diff line number Diff line change
@@ -1,14 +1,19 @@
.. _common-flywoo-f745:

=========================================
Flywoo GOKU GN 745 AIO with 40A ESC/ Nano
=========================================
=================================================
Flywoo GOKU GN 745 AIO with 40A ESC/45A ESC/ Nano
=================================================

The Flywoo GOKU GN 745 AIO is an autopilot produced by [Flywoo](https://flywoo.net/).

.. image:: ../../../images/flywooF745AIO.jpg
:target: ../_images/flywooF745AIO.jpg

The Flywoo GOKU GN 745 45A AIO V3 is an updated version of the above, with 45A ESC.

.. image:: ../../../images/flywooF745AIOv3.jpg
:target: ../_images/flywooF745AIOv3.jpg

The Nano version is a smaller reduced feature set version

.. image:: ../../../images/flywoof745nano.jpg
Expand All @@ -25,7 +30,7 @@ Specifications
- **Processor**

- STM32F745VG ARM (216MHz), 1MB Flash
- Integrated 4 output, BLHeli-32 40A ESC (AIO version only)
- Integrated 4 output, BLHeli-32 40A ESC (AIO V1.2) or BLHeli-32 45A ESC (AIO V3)


- **Sensors**
Expand All @@ -39,7 +44,7 @@ Specifications

- 7.4V ~ 25V DC input power (4S MAX for Nano version)
- 5V 2A BEC for peripherals
- 9V 1.5A BEC for video
- 9V 1.5A BEC for video (no 9V rail on V3 AIO)


- **Interfaces**
Expand All @@ -55,7 +60,7 @@ Specifications
**Size and Dimensions AIO**

- 33.5mm x 33.5mm (25.6 x 25.6mm mount pattern)
- 8.5g
- 8.5g for V1.2, 9.4g for V3

**Size and Dimensions Nano**

Expand All @@ -64,11 +69,16 @@ Specifications

Pinouts
=======
AIO
AIO V1.2

.. image:: ../../../images/flywoo-f745AIO-wiring.jpg
:target: ../_images/flywoo-f745AIO-wiring.jpg

AIO V3

.. image:: ../../../images/flywooF745AIOv3Connections.jpg
:target: ../_images/flywooF745AIOv3Connections.jpg

Nano

.. image:: ../../../images/GOKUGN745AIO-nano_Pinout.jpg
Expand Down Expand Up @@ -103,6 +113,8 @@ RC input is configured on the RX3 (UART3_RX) pin. It supports all RC protocols e

Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See :ref:`common-rc-systems` for details.

.. note:: the V3 AIO moves this to UART2.

PWM Output
==========

Expand Down Expand Up @@ -138,15 +150,20 @@ The correct battery monitor parameters are:
- :ref:`BATT_VOLT_PIN<BATT_VOLT_PIN__AP_BattMonitor_Analog>` = 13
- :ref:`BATT_VOLT_MULT<BATT_VOLT_MULT__AP_BattMonitor_Analog>` ~ 10.9
- :ref:`BATT_CURR_PIN<BATT_CURR_PIN__AP_BattMonitor_Analog>` = 12
- :ref:`BATT_AMP_PERVLT<BATT_AMP_PERVLT__AP_BattMonitor_Analog>` ~ 28.5 (when using AIO version)
- :ref:`BATT_AMP_PERVLT<BATT_AMP_PERVLT__AP_BattMonitor_Analog>` ~ 28.5 (when using AIO version 1.2) (or approx 8.1 for AIO version 3)

These are set by default in the firmware and shouldn't need to be adjusted.
These are set by default in the firmware and shouldn't need to be adjusted (apart from for V3).

Compass
=======

The GOKU GN 745 AIO does not have a builtin compass but it does have an external I2C connector.

IMU
=======

The AIO V3 has its IMU at a different orientation to V1.2. This means :ref:`AHRS_ORIENTATION<AHRS_ORIENTATION>` = 5 (Yaw225) needs to be set for V3.

Loading ArduPilot onto the board
================================

Expand Down
20 changes: 17 additions & 3 deletions copter/source/docs/systemid-mode-operation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,6 @@ Parameters

:ref:`SID_AXIS<SID_AXIS>`: Controls which axis and control loop injection point are being excited


===== ===========
Value Description
===== ===========
Expand All @@ -85,8 +84,7 @@ Value Description
13 Mixer Thrust
===== ===========


:ref:`SID_MAGNITUDE<SID_MAGNITUDE>`: System identification Chirp Magnitude. Depending on the injection point, units will be in either deg, deg/s, or 0-1 for mixer outputs. The magnitude can be changed in flight easily using the :ref:`tuning knob<TUNE>` using the 58 option.
:ref:`SID_MAGNITUDE<SID_MAGNITUDE>`: System identification Chirp Magnitude. Depending on the injection point, units will be in either deg, deg/s, 0-1 for mixer outputs, m/s for velocity, and m for position. The magnitude can be changed in flight easily using the :ref:`tuning knob<TUNE>` using the 58 option.

:ref:`SID_F_START_HZ<SID_F_START_HZ>`: System identification Start Frequency. Range: 0.01-100 Hz

Expand Down Expand Up @@ -130,6 +128,22 @@ The next figure depicts the :ref:`SID_AXIS<SID_AXIS>` injection points in yellow

ArduCopter control loops with ATC_RATE_FF_ENAB=1

Position controller diagram showing the chirp being input at the desired velocity. Both the velocity and position feedback loops are being used. This input would be used to analyze data to determine position or tracking bandwidth.

.. figure:: ../images/Pos_Ctrl_Pos_BW.png

Position controller diagram showing the chirp being input at the desired velocity. Only the velocity feedback loop is being used. This input would be used to analyze data to determine the velocity bandwidth.

.. figure:: ../images/Pos_Ctrl_Vel_BW.png

Position controller diagram showing the chirp being input at the measured position. Both the velocity and position feedback loops are being used. This input would be used to analyze data to determine the position disturbance rejection bandwidth.

.. figure:: ../images/Pos_Ctrl_Pos_DRB.png

Position controller diagram showing the chirp being input at the measured velocity. Only the velocity feedback loop is being used. This input would be used to analyze data to determine the velocity disturbance rejection bandwidth.

.. figure:: ../images/Pos_Ctrl_Vel_DRB.png

Identification of a Multicopter
===============================

Expand Down
8 changes: 7 additions & 1 deletion copter/source/docs/systemid-mode.rst
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,13 @@
System Identification Mode
==========================

This mode is for advanced users and provides a means to generate mathematical models of the vehicles flight behavior for model generation. It places the vehicle into a STABILIZE like mode, and generates bursts of signals ("chirps") injected into the control loops at various points and logs the results for math analysis and model generation later.
This mode is for advanced users and provides a means to characterize the response of a vehicle in the frequency domain. The flight data collected from this mode can be used in several ways:

- generating mathematical models of the vehicles flight behavior for model generation
- investigating and predicting the quality of the vehicle tune
- calculating flying quality metrics

It injects an input signal, called a chirp, at various points in the control loops. The chirp is a constant amplitude oscillation that increases in frequency from a user defined minimum to maximum frequency, generally referred to as a frequency sweep. The injection points are defined by the :ref:`SID_AXIS<SID_AXIS>` parameter and there are points in the Attitude and Position Controller. For any injection points in the Attitude Controller, the user is required to fly the aircraft through an underlying STABILIZE like flight mode. For any injection points in the Position Controller, the user controls are locked out and will not be able to affect the control of the vehicle. The resulting flight data is logged for math analysis and model generation after the flight.


Enabling the Mode
Expand Down
18 changes: 15 additions & 3 deletions copter/source/docs/traditional-helicopter-autotune.rst
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,7 @@
========
AutoTune
========
The AutoTune for tradheli is completely different from multicopter AutoTune. It can tune any combination of feedforward (``ATC_RAT_xxx_FF``),
the rate gains (``ATC_RAT_xxx_P`` and ``ATC_RAT_xxx_D``), or angle P gain (``ATC_ANG_xxx_P``). The tuning for rate gains begins with finding the maximum allowable value for the rate gains and then tunes them. Knowing the maximum value enables the AutoTune feature to keep from creating an instability.
The AutoTune for tradheli is completely different from multicopter AutoTune. It can tune any combination of feedforward (``ATC_RAT_xxx_FF``), the rate gains (``ATC_RAT_xxx_P`` and ``ATC_RAT_xxx_D``), or angle P gain (``ATC_ANG_xxx_P``). The tuning for rate gains begins with finding the maximum allowable value for the rate gains and then tunes them. Knowing the maximum value enables the AutoTune feature to keep from creating an instability. In Copter 4.6, rate and acceleration limiting were added to allow users to protect aircraft that may not be able to handle the dynamic oscillations of the autotune maneuver.

Before you start AutoTune, you must:

Expand Down Expand Up @@ -105,6 +104,15 @@ The :ref:`AUTOTUNE_FRQ_MAX<AUTOTUNE_FRQ_MAX>` parameter specifies the maximum fr

The :ref:`AUTOTUNE_VELXY_P<AUTOTUNE_VELXY_P>` parameter specifies P gain for velocity feedback. This aids the AutoTune in maintaining aircraft position during the frequency sweeps and dwells. It does not apply to ``ATC_RAT_xxx_FF`` tuning. Keep this at 0.1 unless the aircraft is drifting more than 10 meters during the dwell and frequency sweeps. It only affects position holding while the aircraft is oscillating during these tests. If it does drift more than 10 meters during the dwell adn frequency sweep tests then increase this parameter but don't increase much beyond 0.2. In between the oscillations, it may drift if the aircraft wasn't properly trimmed for hover. This gain will not help with that.

:ref:`Maximum Allowable Angular Acceleration<AUTOTUNE_ACC_MAX>`
---------------------------------------------------------------

The :ref:`AUTOTUNE_ACC_MAX<AUTOTUNE_ACC_MAX>` parameter specifies maximum allowable angular acceleration in deg/s/s during autotune maneuvers. This is only available in version Copter-4.6 and subsequent. This parameter limits the requested acceleration. This does not guarantee the actual aircraft acceleration will be that which was requested. It is likely that the response will be less than the requested acceleration. If the response is too low, the resulting analysis may not be good enough for autotune to work well. If the actual response is much lower, consider increasing the acceleration parameter so that there is a larger response for analysis. The rate response can be used to estimate the actual acceleration by multiplying the magnitude in deg/s of the oscillatory response by the frequency in rad/s.

:ref:`Maximum Allowable Angular Rate<AUTOTUNE_RAT_MAX>`
-------------------------------------------------------

The :ref:`AUTOTUNE_RAT_MAX<AUTOTUNE_RAT_MAX>` parameter specifies maximum allowable angular rate in deg/s during autotune maneuvers. This is only available in version Copter-4.6 and subsequent. This parameter limits the requested rate. This does not guarantee the actual aircraft rate will be that which was requested. It is likely that the response will be less than the requested acceleration. If the response is too low, the resulting analysis may not be good enough for autotune to work well. If the actual response is much lower, consider increasing the rate parameter so that there is a larger response for analysis. The actual rate can be evaluated from the RATE log message.

Preparing for AutoTune
======================
Expand Down Expand Up @@ -193,7 +201,11 @@ Tuning Maneuver Descriptions
``ATC_RAT_xxx_FF`` Tuning
+++++++++++++++++++++++++

The ``ATC_RAT_xxx_FF`` tuning is accomplished by achieving a constant angular rate of 50 deg/s and determining the steady state command required to maintain the 50 deg/s. The maneuver to achieve the constant angular rate consists of changing attitude by 15 deg in one direction then reversing direction to achieve a constant rate of 50 deg/s before reaching 15 deg in the opposite direction. Finally it returns to the starting attitude. During ``ATC_RAT_xxx_FF`` tuning there is no position holding logic and the aircraft may drift, reposition the aircraft between maneuvers as needed to keep it from drifting. Making any inputs during this test will stop the tuning and won’t begin again unless the sticks are centered. The following video demonstrates the ``ATC_RAT_xxx_FF`` tuning.
In versions 4.6 and subsequent, the ``ATC_RAT_xxx_FF`` tuning is accomplished by performing low frequency oscillations targeting an amplitude of 5 deg. The test will conduct 5 to 6 oscillations which will take 15 to 20 seconds. This will be repeated to refine the feedforward gain. Although the requested amplitude is 5 deg, the actual amplitude may be larger. If the amplitude exceeds 10 to 15 deg or the oscillations are growing, the autotune testing should be stopped. The following video demonstrates the ``ATC_RAT_xxx_FF`` tuning. It shows the tuning in progress where approximately 6 oscillations are done to test the gain with a short pause and then another 6 oscillations. During the pause, the gains are being updated and the test is conducted again until the tuning is complete.

.. youtube:: mquYOOVxWTo

In versions prior to 4.6, the ``ATC_RAT_xxx_FF`` tuning is accomplished by achieving a constant angular rate of 50 deg/s and determining the steady state command required to maintain the 50 deg/s. The maneuver to achieve the constant angular rate consists of changing attitude by 15 deg in one direction then reversing direction to achieve a constant rate of 50 deg/s before reaching 15 deg in the opposite direction. Finally it returns to the starting attitude. During ``ATC_RAT_xxx_FF`` tuning there is no position holding logic and the aircraft may drift, reposition the aircraft between maneuvers as needed to keep it from drifting. Making any inputs during this test will stop the tuning and won’t begin again unless the sticks are centered. The following video demonstrates the ``ATC_RAT_xxx_FF`` tuning.

.. youtube:: 2XLBIycPiq0

Expand Down
Binary file added copter/source/images/Pos_Ctrl_Pos_BW.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added copter/source/images/Pos_Ctrl_Pos_DRB.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added copter/source/images/Pos_Ctrl_Vel_BW.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added copter/source/images/Pos_Ctrl_Vel_DRB.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added images/flywooF745AIOv3.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added images/flywooF745AIOv3Connections.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.

0 comments on commit 3008d4c

Please sign in to comment.