Merge branch 'master' into esp32wip

This commit is contained in:
Bayu Laksono 2024-12-14 13:14:26 +07:00 committed by GitHub
commit 779c405132
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
629 changed files with 37916 additions and 3589 deletions

View File

@ -156,7 +156,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -177,7 +177,7 @@ jobs:
source ~/ccache.conf &&
ccache -s
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: D:/a/ardupilot/ardupilot/ccache
key: ${{ steps.ccache_cache_timestamp.outputs.cache-key }}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -169,7 +169,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -182,7 +182,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{ matrix.gcc }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -48,7 +48,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -161,7 +161,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.config }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -32,8 +32,6 @@ jobs:
name: focal
- os: ubuntu
name: jammy
- os: ubuntu
name: mantic
- os: ubuntu
name: noble
- os: archlinux

View File

@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -170,7 +170,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -19,6 +19,7 @@ jobs:
python-cleanliness,
astyle-cleanliness,
validate_board_list,
logger_metadata,
]
steps:
# git checkout the PR

View File

@ -182,7 +182,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -229,7 +229,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -247,7 +247,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -302,7 +302,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -343,7 +343,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -172,7 +172,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -222,7 +222,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -230,7 +230,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -180,7 +180,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -244,7 +244,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -184,7 +184,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -244,7 +244,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -183,7 +183,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -230,7 +230,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache/restore@v3
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}

View File

@ -97,7 +97,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
@ -268,7 +268,7 @@ jobs:
shell: bash
run: |
cd pr/
Tools/scripts/pretty_diff_size.py -m $GITHUB_WORKSPACE/base_branch_bin -s $GITHUB_WORKSPACE/pr_bin
Tools/scripts/build_tests/pretty_diff_size.py -m $GITHUB_WORKSPACE/base_branch_bin -s $GITHUB_WORKSPACE/pr_bin
- name: Feature compare with ${{ github.event.pull_request.base.ref }}
shell: bash
@ -301,8 +301,26 @@ jobs:
Tools/scripts/extract_features.py "$EF_BASE_BRANCH_BINARY" -nm "${BIN_PREFIX}nm" >features-base_branch.txt
Tools/scripts/extract_features.py "$EF_PR_BRANCH_BINARY" -nm "${BIN_PREFIX}nm" >features-pr.txt
diff -u features-base_branch.txt features-pr.txt || true
diff_output=$(diff -u features-base_branch.txt features-pr.txt || true)
echo "### Features Diff Output" >> $GITHUB_STEP_SUMMARY
if [ -n "$diff_output" ]; then
echo '```diff' >> $GITHUB_STEP_SUMMARY
echo "$diff_output" >> $GITHUB_STEP_SUMMARY
echo '```' >> $GITHUB_STEP_SUMMARY
else
echo "No differences found." >> $GITHUB_STEP_SUMMARY
fi
- name: Checksum compare with ${{ github.event.pull_request.base.ref }}
shell: bash
run: |
diff -r $GITHUB_WORKSPACE/base_branch_bin_no_versions $GITHUB_WORKSPACE/pr_bin_no_versions --exclude=*.elf --exclude=*.apj || true
diff_output=$(diff -r $GITHUB_WORKSPACE/base_branch_bin_no_versions $GITHUB_WORKSPACE/pr_bin_no_versions --exclude=*.elf --exclude=*.apj || true || true)
echo "### Checksum Diff Output" >> $GITHUB_STEP_SUMMARY
if [ -n "$diff_output" ]; then
echo '```diff' >> $GITHUB_STEP_SUMMARY
echo "$diff_output" >> $GITHUB_STEP_SUMMARY
echo '```' >> $GITHUB_STEP_SUMMARY
else
echo "No differences found." >> $GITHUB_STEP_SUMMARY
fi

View File

@ -126,7 +126,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}

4
.gitignore vendored
View File

@ -171,7 +171,3 @@ ENV/
env.bak/
venv.bak/
autotest_result_*_junit.xml
# Ignore ESP-IDF SDK defines
/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig
/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig

View File

@ -276,10 +276,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_NAV_CONTROLLER_OUTPUT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
};
@ -315,7 +321,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
MSG_BATTERY_STATUS,
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
@ -643,3 +650,43 @@ void GCS_MAVLINK_Tracker::send_global_position_int()
0, // Z speed cm/s (+ve Down)
tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree
}
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&tracker.mode_manual,
&tracker.mode_stop,
&tracker.mode_scan,
&tracker.mode_guided,
&tracker.mode_servotest,
&tracker.mode_auto,
&tracker.mode_initialising,
};
const uint8_t mode_count = ARRAY_SIZE(modes);
// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}
// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);
return mode_count;
}

View File

@ -30,6 +30,10 @@ protected:
void send_nav_controller_output() const override;
void send_pid_tuning() override;
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;
private:
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;

View File

@ -1,5 +1,476 @@
Antenna Tracker Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta2 11 Dec 2024
Changes from 4.6.0-beta1
1) Board specfic changes
- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed
2) Copter specific enhancements and bug fixes
- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option
3) Plane related enhancements and bug fixes
- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes
4) Bug Fixes and minor enhancements
- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024
Changes from 4.5.7
1) Board specific changes
- AnyLeaf H7 supports compass and onboard logging
- Blitz743Pro supports CAN
- BlueRobotics Navigator supports BMP390 baro
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
- CB Unmanned Stamp H743 support
- ClearSky CSKY405 support
- CUAV-7-Nano default batt monitor fixed
- CubeRed bootloader fixes including disabling 2nd core by default
- CubeRed supports PPP networking between primary and secondary MCU
- CubeRedPrimary supports external compasses
- ESP32 main loop rate improvements
- ESP32 RC input fixes and wifi connection reliability improved
- ESP32 safety switch and GPIO pin support
- FlyingMoon no longer support MAX7456
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
- Flywoo H743 Pro support
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
- FlywooF745 supports DPS310 baro
- FPV boards lose SMBus battery support (to save flash)
- GEPRC F745BTHD support
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
- Holybro Kakute F4 Wing support
- iFlight 2RAW H743 supports onboard logging
- JFB110 supports measuring servo rail voltage
- JFB110 supports safety switch LED
- JHEM-JHEF405 bootloader supports firmware updates via serial
- JHEMCU GF30H743 HD support
- JHEMCU-GF16-F405 autopilot support
- JHEMCU-GSF405A becomes FPV board (to save flash)
- KakuteF7 only supports BMP280 baro (to save flash)
- KakuteH7Mini supports ICM42688 IMU
- Linux auto detection of GPS baud rate fixed
- Linux board scheduler jitter reduced
- Linux board shutdown fixes
- MakeFlyEasy PixPilot-V6Pro support
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
- MatekH7A3 support Bi-directional DShot
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
- MicoAir743 internal compass orientation fixed
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
- mRo Control Zero Classic supports servo rail analog input
- mRo KitCAN revC fixed
- Mugin MUPilot support
- OmnibusF7v2 loses quadplane support (to save flash)
- Pixhack-v3 board added (same as fmuv3)
- Pixhawk6C bootloader supports flashing firmware from SD card
- RadiolinkPIX6 imu orientation fixed
- RadiolinkPIX6 supports SPA06 baro
- ReaperF745 V4 FC supports MPU6000 IMU
- RPI5 support
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
- Solo serial ports default to MAVLink1
- SpeedyBeeF405Wing gets Bi-directional DShot
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
- Spektreworks boom board support
- TrueNavPro-G4 SPI does not share DMA
- X-MAV AP-H743v2 support
2) AHRS/EKF enhancements and fixes
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
- AHRS_OPTION to disable innovation check for airspeed sensor
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
- EK2 supports disabling external nav (see EK2_OPTIONS)
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
- EK3 uses filtered velocity corrections for IMU position
- EKF2, EKF3, ExternalAHRS all use common origin
- EKF3 accepts set origin even when using GPS
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
- EKF3 copes better with GPS jamming
- EKF3 logs mag fusion selection to XKFS
- EKF3 wind estimation when using GPS-for-yaw fixed
- External AHRS improvements including handling variances, pre-arm origin check
- Inertial Labs External AHRS fixes
- VectorNav driver fix for handling of error from sensor
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
- VectorNav support for sensors outside VN-100 and VN-300
3) Driver enhancements and bug fixes
- ADSB fix to display last character in status text sent to GCS
- Ainstein LR-D1 radar support
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
- AIRSPEED message sent to GCS
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
- ARSPD_OPTIONS to report calibration offset to GCS
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
- Baro provides improved atmospheric model for high altitude flight
- BARO_ALT_OFFSET slew slowed to keep EKF happy
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
- BATTx_OPTION to not send battery voltage, current, etc to GCS
- Benewake RDS02U radar support
- Bi-directional DShot on IOMCU supports reversible mask
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
- BMM350 compass support
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
- CRSF baro and vertical speeed fixed
- CRSF RX bind command support
- DroneCAN battery monitor check to avoid memory corruption when type changed
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
- DroneCAN EFI health check fix
- DroneCAN ESC battery monitors calculate consumed mah
- DroneCAN ESCs forced to zero when disarmed
- DroneCAN RPM message support
- DroneCAN timeout fix for auxiliary frames
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
- FuelLevel battery monitor fix to report capacity
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
- Hirth EFI logging includes modified throttle
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
- Hott and LTM telemetry deprecated (still available through custom build server)
- i-BUS telemetry support
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
- ICE_START_CHAN replaced with RC aux function (Plane only)
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
- IE 2400 generator error message severity to GCS improved
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
- MCP9600 temperature sensor I2C address fixed
- MLX90614 temperature sensor support
- MSP GPS ground course scaling fixed
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
- Networking supports reconnection to TCP server or client
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
- Relay inverted output support (see RELAYx_INVERTED parameter)
- ROMFS efficiency improvements
- RS-485 driver enable RTS flow control
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
- Septentrio GPS sat count correctly drops to zero when 255 received
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
- Single LED for user notification supported
- SPA06 baro supported
- Sum battery monitor optionally reports minimum voltage instead of average
- Sum battery monitor reports average temp
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
- UBlox GPS time ignored until at least 2D fix
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
- Volz logs desired and actual position, voltage, current, motor and PCB temp
- Volz server feedback and logging fixed
- Volz servo output in its own thread resulting in smoother movements
- W25N02KV flash support
4) Networking enhancements and fixes
- Allow multiple UDP clients to connect/disconnect/reconnect
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
5) Camera and gimbal enhancements
- Alexmos precision improved slightly
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
- Dual serial camera gimbal mounts fixed
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
- Retract Mount2 aux function added (see RCx_OPTION = 113)
- Servo gimbal reported angles respect roll, pitch and yaw limits
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
- Siyi picture and video download scripts
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
- Siyi ZT6 hardware id and set-lens fixed
- Topotek gimbal support
- Trigger distance ignores GPS status and only uses EKF reported location
6) Harmonic notch enhancements
- Harmonic notch is active in forward flight on quadplanes
- Harmonic notch filter freq clamping and disabling reworked
- Harmonic notch handles negative ESC RPMs
- Harmonic notch supports per-motor throttle-based harmonic notch
7) Copter specific enhancements and bug fixes
- Attitude control fix to dt update order (reduces rate controller noise)
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
- Auto mode small target position jump when takeoff completes removed
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
- AutoTune fix to prevent spool up after landing
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
- Config error avoided if auto mode is paused very soon after poweron
- FLIGHT_OPTIONS bit added to require position estimate before arming
- Follow mode slowdown calcs fixed when target is moving
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
- Landing detector logging added to ease support (see LDET message)
- Loiter unlimited command accepts NaNs (QGC sends these)
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
- Payload place bug fix when aborted because gripper is already released
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
- RTL_ALT minimum reduced to 30cm
- SystemID position controller support (Copter and Heli)
- TriCopter motor test and slew-up fixed
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
8) TradHeli specific enhancements
- Autorotation yaw behaviour fix
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
- Blade pitch angle logging added (see SWSH log message)
- Constrain cyclic roll for intermeshing
- ICE / turbine cool down fix
- Inverted flight extended to non manual throttle modes
- Inverted flight transitions smoothed and restricted to only Stabilize mode
- SWSH logging fix for reversed collectives
9) Plane specific enhancements and bug fixes
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
- Allow for different orientations of landing rangefinder
- Assistance requirements evaluted on mode change
- FBWB/CRUISE climb/sink rate limited by TECS limits
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
- Glider pullup support (available only through custom build server)
- Loiter breakout improved to better handle destinations inside loiter circle
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
- Quadplane assistance check enhancements
- Quadplane Deca frame support
- Quadplane gets smoother takeoff by input shaping target accel and velocity
- Servo wiggles in altitude wait staged to be one after another
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
- Takeoff fixes for fence autoenable
- Takeoff improvements including less overshoot of TKOFF_ALT
- TECS reset along with other controllers (important if plane dropped from balloon)
- Tilt quadplane ramp of motors on back transition fixed
- Tiltrotor tilt angles logged
- TKOFF_THR_MIN applied to SLT transitions
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
10) Rover specific enhancements and bug fixes
- Auto mode reversed state maintained if momentarily switched to Hold mode
- Circle mode tracks better and avoids getting stuck at circle edge
- Flight time stats fixed
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
- Omni3Mecanum frame support
- Stopping point uses max deceleration (was incorrectly using acceleration)
- Wheel rate controller slew rate fix
11) Antenna Tracker specific enhancements and bug fixes
- Never track lat,lon of 0,0
12) Scripting enhancements
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
- battery_internal_resistance_check.lua monitors battery resistance
- CAN:get_device returns nil for unconfigured CAN device
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
- Copter:get_target_location, update_target_location support
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
- Display text on OLED display supported
- Docs improved for many bindings
- EFI get_last_update_ms binding
- EFI_SkyPower.lua driver accepts 2nd supply voltage
- ESC_slew_rate.lua example script supports testing ESCs
- Filesystem CRC32 check to allow scripts to check module versions
- forced arming support
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
- Halo6000 EFI driver can log all CAN packets for easier debugging
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
- I2C:transfer support
- IMU gyros_consistent and accels_consistent bindings added
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
- INS bindings for is calibrating, gyro and accel sensor values
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
- Logging of booleans supported
- Lua language checks improved (finds more errors)
- MAVLink commands can be called from scripting
- MCU voltage binding (see analog:mcu_voltage)
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
- "open directory failed" false warning when scripts in ROMFS fixed
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
- Pass by reference values are always initialized
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
- plane_aerobatics.lua minor enhancements
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
- "require" function failures in rare circumstances fixed
- "require" function works for modules in ROMFS (e.g. not on SD card)
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
- SD card formatting supported
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
- Temperature sensor bindings added
- uint64 support
- Various performance and memory usage optimizations
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
13) GCS / mavlink related changes and fixes
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
- Deny attempts to upload two missions simultaneously
- Fence and Rally points may be uploaded using FTP
- GPS_INPUT and HIL_GPS handles multiple GPSs
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
- MAV_CMD_SET_HAGL support (Plane only)
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
- Message interval supports TERRAIN_REPORT msg
- Mission upload may be cancelled using MISSION_CLEAR_ALL
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
- RC_CHANNELS_RAW deprecated
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
14) Logging enhancements and fixes
- AC_PID resets and I-term sets logged
- ANG provides attitude at high rate (equivalent to ATT)
- ATT logs angles as floats (better resolution than ints)
- CAND message gets driver index
- DCM log message includes roll/pitch and yaw error
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
- FMT messages written as required instead of all at beginning
- Logging restarted after download completes when LOG_DISARMED = 1
- MISE msg logs active mission command (CMD logged when commands are uploaded)
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
- RPM sensor logging gets instance field, quality and health fields
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
- UART data rates logged at 1hz (see UART message)
15) ROS2 / DDS support
- Airspeed published
- Battery topic reports all available batteries
- Compile-time configurable rates for each publisher
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
- GPS global origin published at 1 Hz
- High frequency raw imu data transmission
- Joystick support
- Support sending waypoints to Copter and Rover
- Remove the XML refs file in favor of binary entity creation
16) Safety related enhancements and fixes
- Accel/Gyro inconsistent message fixed for using with only single IMU
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
- Far from EKF origin pre-arm check removed (Copter only)
- Fence breach warning message slightly improved
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
- LEDs flash green lights based on EKF location not GPS
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
- Pre-arm check if OpenDroneID is compiled in but disabled
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
- Pre-arm checks alert user more quickly on failure
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
- Warning of duplicate SERIALx_PROTOCOL = RCIN
17) Other bug fixes and minor enhancements
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
- Bootloader rejects allocation of broadcast node ID
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
- Dijkstras fix to correct use of uninitialised variable
- DShot rates are not limited by NeoPixel rates
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
- Filesystem does not show entries for empty @ files
- Filesystem efficiency improvements when reading files
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
- Internal error thrown if we lose parameters due to saving queue being too small
- MAVLink via DroneCAN baud rate fix
- SPI pins may also be used as GPIOs
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
18) Developer focused fixes and enhancements
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
- Cygwin build fix for non-SITL builds
- Cygwin build fixed with malloc wrap
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
- EKF3 code generator documentation and cleanup
- GPS jamming simulator added
- MacOS compiler warnings reduced
- SFML joystick support
- SITL support for OpenBSD
- Text warning if older Fence or Rally point protocols are used
------------------------------------------------------------------
Release 4.5.7 08 Oct 2024
Changes from 4.5.7-beta1

View File

@ -82,7 +82,7 @@ void Tracker::one_second_loop()
mavlink_system.sysid = g.sysid_this_mav;
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
// updated armed/disarmed status LEDs
update_armed_disarmed();

View File

@ -22,6 +22,7 @@ public:
// returns a unique number specific to this mode
virtual Mode::Number number() const = 0;
virtual const char* name() const = 0;
virtual bool requires_armed_servos() const = 0;
@ -41,6 +42,7 @@ protected:
class ModeAuto : public Mode {
public:
Mode::Number number() const override { return Mode::Number::AUTO; }
const char* name() const override { return "Auto"; }
bool requires_armed_servos() const override { return true; }
void update() override;
};
@ -48,6 +50,7 @@ public:
class ModeGuided : public Mode {
public:
Mode::Number number() const override { return Mode::Number::GUIDED; }
const char* name() const override { return "Guided"; }
bool requires_armed_servos() const override { return true; }
void update() override;
@ -66,6 +69,7 @@ private:
class ModeInitialising : public Mode {
public:
Mode::Number number() const override { return Mode::Number::INITIALISING; }
const char* name() const override { return "Initialising"; }
bool requires_armed_servos() const override { return false; }
void update() override {};
};
@ -73,6 +77,7 @@ public:
class ModeManual : public Mode {
public:
Mode::Number number() const override { return Mode::Number::MANUAL; }
const char* name() const override { return "Manual"; }
bool requires_armed_servos() const override { return true; }
void update() override;
};
@ -80,6 +85,7 @@ public:
class ModeScan : public Mode {
public:
Mode::Number number() const override { return Mode::Number::SCAN; }
const char* name() const override { return "Scan"; }
bool requires_armed_servos() const override { return true; }
void update() override;
};
@ -87,6 +93,7 @@ public:
class ModeServoTest : public Mode {
public:
Mode::Number number() const override { return Mode::Number::SERVOTEST; }
const char* name() const override { return "ServoTest"; }
bool requires_armed_servos() const override { return true; }
void update() override {};
@ -96,6 +103,7 @@ public:
class ModeStop : public Mode {
public:
Mode::Number number() const override { return Mode::Number::STOP; }
const char* name() const override { return "Stop"; }
bool requires_armed_servos() const override { return false; }
void update() override {};
};

View File

@ -8,7 +8,7 @@
void Tracker::init_servos()
{
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw);
SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch);

View File

@ -6,13 +6,13 @@
#include "ap_version.h"
#define THISFIRMWARE "AntennaTracker V4.6.0-dev"
#define THISFIRMWARE "AntennaTracker V4.7.0-dev"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV
#define FW_MAJOR 4
#define FW_MINOR 6
#define FW_MINOR 7
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

View File

@ -27,7 +27,7 @@
// features below are disabled by default on all boards
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
//#define ADVANCED_FAILSAFE 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events
//#define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events
// other settings
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)

View File

@ -1,7 +1,7 @@
#include "Copter.h"
#pragma GCC diagnostic push
#if defined(__clang__)
#if defined(__clang_major__) && __clang_major__ >= 14
#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"
#endif

View File

@ -4,18 +4,21 @@
* Attitude Rate controllers and timing
****************************************************************/
// update rate controllers and output to roll, pitch and yaw actuators
// called at 400hz by default
void Copter::run_rate_controller()
/*
update rate controller when run from main thread (normal operation)
*/
void Copter::run_rate_controller_main()
{
// set attitude and position controller loop time
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
motors->set_dt(last_loop_time_s);
attitude_control->set_dt(last_loop_time_s);
pos_control->set_dt(last_loop_time_s);
attitude_control->set_dt(last_loop_time_s);
// run low level rate controllers that only require IMU data
attitude_control->rate_controller_run();
if (!using_rate_thread) {
motors->set_dt(last_loop_time_s);
// only run the rate controller if we are not using the rate thread
attitude_control->rate_controller_run();
}
// reset sysid and other temporary inputs
attitude_control->rate_controller_target_reset();
}

View File

@ -75,6 +75,7 @@
*/
#include "Copter.h"
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
#define FORCE_VERSION_H_INCLUDE
#include "version.h"
@ -113,7 +114,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
// update INS immediately to get current gyro data populated
FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),
// run low level rate controllers that only require IMU data
FAST_TASK(run_rate_controller),
FAST_TASK(run_rate_controller_main),
#if AC_CUSTOMCONTROL_MULTI_ENABLED
FAST_TASK(run_custom_controller),
#endif
@ -121,7 +122,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
FAST_TASK(heli_update_autorotation),
#endif //HELI_FRAME
// send outputs to the motors library immediately
FAST_TASK(motors_output),
FAST_TASK(motors_output_main),
// run EKF state estimator (expensive)
FAST_TASK(read_AHRS),
#if FRAME_CONFIG == HELI_FRAME
@ -232,7 +233,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if HAL_ADSB_ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100, 138),
#endif
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
SCHED_TASK(afs_fs_check, 10, 100, 141),
#endif
#if AP_TERRAIN_AVAILABLE
@ -259,6 +260,10 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if HAL_BUTTON_ENABLED
SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168),
#endif
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
// don't delete this, there is an equivalent (virtual) in AP_Vehicle for the non-rate loop case
SCHED_TASK(update_dynamic_notch_at_specified_rate_main, LOOP_RATE, 200, 215),
#endif
};
void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
@ -285,13 +290,9 @@ bool Copter::set_target_location(const Location& target_loc)
return mode_guided.set_destination(target_loc);
}
#endif //MODE_GUIDED_ENABLED
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
bool Copter::start_takeoff(const float alt)
{
// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!flightmode->in_guided_mode()) {
@ -304,7 +305,11 @@ bool Copter::start_takeoff(float alt)
}
return false;
}
#endif //MODE_GUIDED_ENABLED
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED
// set target position (for use by scripting)
bool Copter::set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt)
{
@ -411,7 +416,55 @@ bool Copter::set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_
mode_guided.set_angle(q, ang_vel_body, throttle, true);
return true;
}
#endif
// Register a custom mode with given number and names
AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, const char* full_name, const char* short_name)
{
const Mode::Number number = (Mode::Number)num;
// See if this mode has been registered already, if it has return the state for it
// This allows scripting restarts
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
if (mode_guided_custom[i] == nullptr) {
break;
}
if ((mode_guided_custom[i]->mode_number() == number) &&
(strcmp(mode_guided_custom[i]->name(), full_name) == 0) &&
(strncmp(mode_guided_custom[i]->name4(), short_name, 4) == 0)) {
return &mode_guided_custom[i]->state;
}
}
// Number already registered to existing mode
if (mode_from_mode_num(number) != nullptr) {
return nullptr;
}
// Find free slot
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
if (mode_guided_custom[i] == nullptr) {
// Duplicate strings so were not pointing to unknown memory
const char* full_name_copy = strdup(full_name);
const char* short_name_copy = strndup(short_name, 4);
if ((full_name_copy != nullptr) && (short_name_copy != nullptr)) {
mode_guided_custom[i] = NEW_NOTHROW ModeGuidedCustom(number, full_name_copy, short_name_copy);
}
if (mode_guided_custom[i] == nullptr) {
// Allocation failure
return nullptr;
}
// Registration sucsessful, notify the GCS that it should re-request the avalable modes
gcs().available_modes_changed();
return &mode_guided_custom[i]->state;
}
}
// No free slots
return nullptr;
}
#endif // MODE_GUIDED_ENABLED
#if MODE_CIRCLE_ENABLED
// circle mode controls
@ -570,12 +623,15 @@ void Copter::update_batt_compass(void)
// should be run at loop rate
void Copter::loop_rate_logging()
{
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
Log_Write_Attitude();
Log_Write_PIDS(); // only logs if PIDS bitmask is set
if (!using_rate_thread) {
Log_Write_Rate();
Log_Write_PIDS(); // only logs if PIDS bitmask is set
}
}
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
if (should_log(MASK_LOG_FTN_FAST)) {
if (should_log(MASK_LOG_FTN_FAST) && !using_rate_thread) {
AP::ins().write_notch_log_messages();
}
#endif
@ -593,10 +649,15 @@ void Copter::ten_hz_logging_loop()
// log attitude controller data if we're not already logging at the higher rate
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
Log_Write_Attitude();
if (!using_rate_thread) {
Log_Write_Rate();
}
}
if (!should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set
Log_Write_PIDS();
if (!using_rate_thread) {
Log_Write_PIDS();
}
}
// log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
@ -688,12 +749,29 @@ void Copter::three_hz_loop()
low_alt_avoidance();
}
// ap_value calculates a 32-bit bitmask representing various pieces of
// state about the Copter. It replaces a global variable which was
// used to track this state.
uint32_t Copter::ap_value() const
{
uint32_t ret = 0;
const bool *b = (const bool *)&ap;
for (uint8_t i=0; i<sizeof(ap); i++) {
if (b[i]) {
ret |= 1U<<i;
}
}
return ret;
}
// one_hz_loop - runs at 1Hz
void Copter::one_hz_loop()
{
#if HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_ANY)) {
Log_Write_Data(LogDataID::AP_STATE, ap.value);
Log_Write_Data(LogDataID::AP_STATE, ap_value());
}
#endif
@ -710,7 +788,7 @@ void Copter::one_hz_loop()
}
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
#if HAL_LOGGING_ENABLED
// log terrain data
@ -724,11 +802,26 @@ void Copter::one_hz_loop()
AP_Notify::flags.flying = !ap.land_complete;
// slowly update the PID notches with the average loop rate
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
if (!using_rate_thread) {
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
}
pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#if AC_CUSTOMCONTROL_MULTI_ENABLED
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#endif
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
// see if we should have a separate rate thread
if (!started_rate_thread && get_fast_rate_type() != FastRateType::FAST_RATE_DISABLED) {
if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),
"rate",
1536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {
started_rate_thread = true;
} else {
AP_BoardConfig::allocation_error("rate thread");
}
}
#endif
}
void Copter::init_simple_bearing()

View File

@ -137,7 +137,7 @@
#include <AP_OSD/AP_OSD.h>
#endif
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
# include "afs_copter.h"
#endif
#if TOY_MODE_ENABLED
@ -183,7 +183,7 @@ public:
friend class ParametersG2;
friend class AP_Avoidance_Copter;
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
friend class AP_AdvancedFailsafe_Copter;
#endif
friend class AP_Arming_Copter;
@ -347,46 +347,48 @@ private:
# include USERHOOK_VARIABLES
#endif
// Documentation of GLobals:
typedef union {
struct {
uint8_t unused1 : 1; // 0
uint8_t unused_was_simple_mode : 2; // 1,2
uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully
uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised
uint8_t logging_started : 1; // 6 // true if logging has started
uint8_t land_complete : 1; // 7 // true if we have detected a landing
uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio
uint8_t usb_connected_unused : 1; // 9 // UNUSED
uint8_t rc_receiver_present_unused : 1; // 10 // UNUSED
uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test
uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 14 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
uint8_t system_time_set_unused : 1; // 16 // true if the system time has been set from the GPS
uint8_t gps_glitching : 1; // 17 // true if GPS glitching is affecting navigation accuracy
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
uint8_t land_repo_active : 1; // 21 // true if the pilot is overriding the landing position
uint8_t motor_interlock_switch : 1; // 22 // true if pilot is requesting motor interlock enable
uint8_t in_arming_delay : 1; // 23 // true while we are armed but waiting to spin motors
uint8_t initialised_params : 1; // 24 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
uint8_t unused3 : 1; // 25 // was compass_init_location; true when the compass's initial location has been set
uint8_t unused2 : 1; // 26 // aux switch rc_override is allowed
uint8_t armed_with_airmode_switch : 1; // 27 // we armed using a arming switch
uint8_t prec_land_active : 1; // 28 // true if precland is active
};
uint32_t value;
} ap_t;
// ap_value calculates a 32-bit bitmask representing various pieces of
// state about the Copter. It replaces a global variable which was
// used to track this state.
uint32_t ap_value() const;
ap_t ap;
// These variables are essentially global variables. These should
// be removed over time. It is critical that the offsets of these
// variables remain unchanged - the logging is dependent on this
// ordering!
struct PACKED {
bool unused1; // 0
bool unused_was_simple_mode_byte1; // 1
bool unused_was_simple_mode_byte2; // 2
bool pre_arm_rc_check; // 3 true if rc input pre-arm checks have been completed successfully
bool pre_arm_check; // 4 true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
bool auto_armed; // 5 stops auto missions from beginning until throttle is raised
bool unused_log_started; // 6
bool land_complete; // 7 true if we have detected a landing
bool new_radio_frame; // 8 Set true if we have new PWM data to act on from the Radio
bool unused_usb_connected; // 9
bool unused_receiver_present; // 10
bool compass_mot; // 11 true if we are currently performing compassmot calibration
bool motor_test; // 12 true if we are currently performing the motors test
bool initialised; // 13 true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
bool land_complete_maybe; // 14 true if we may have landed (less strict version of land_complete)
bool throttle_zero; // 15 true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
bool system_time_set_unused; // 16 true if the system time has been set from the GPS
bool gps_glitching; // 17 true if GPS glitching is affecting navigation accuracy
bool using_interlock; // 18 aux switch motor interlock function is in use
bool land_repo_active; // 19 true if the pilot is overriding the landing position
bool motor_interlock_switch; // 20 true if pilot is requesting motor interlock enable
bool in_arming_delay; // 21 true while we are armed but waiting to spin motors
bool initialised_params; // 22 true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
bool unused_compass_init_location; // 23
bool unused2_aux_switch_rc_override_allowed; // 24
bool armed_with_airmode_switch; // 25 we armed using a arming switch
bool prec_land_active; // 26 true if precland is active
} ap;
AirMode air_mode; // air mode is 0 = not-configured ; 1 = disabled; 2 = enabled;
bool force_flying; // force flying is enabled when true;
static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t");
// This is the state of the flight control system
// There are multiple states defined such as STABILIZE, ACRO,
Mode *flightmode;
@ -629,6 +631,17 @@ private:
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};
// type of fast rate attitude controller in operation
enum class FastRateType : uint8_t {
FAST_RATE_DISABLED = 0,
FAST_RATE_DYNAMIC = 1,
FAST_RATE_FIXED_ARMED = 2,
FAST_RATE_FIXED = 3,
};
FastRateType get_fast_rate_type() const { return FastRateType(g2.att_enable.get()); }
// returns true if option is enabled for this vehicle
bool option_is_enabled(FlightOption option) const {
return (g2.flight_options & uint32_t(option)) != 0;
@ -666,12 +679,12 @@ private:
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED
bool set_target_location(const Location& target_loc) override;
bool start_takeoff(const float alt) override;
#endif // MODE_GUIDED_ENABLED
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED
bool start_takeoff(float alt) override;
bool get_target_location(Location& target_loc) override;
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override;
@ -682,6 +695,8 @@ private:
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
bool set_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) override;
// Register a custom mode with given number and names
AP_Vehicle::custom_mode_state* register_custom_mode(const uint8_t number, const char* full_name, const char* short_name) override;
#endif
#if MODE_CIRCLE_ENABLED
bool get_circle_radius(float &radius_m) override;
@ -724,7 +739,25 @@ private:
void set_accel_throttle_I_from_pilot_throttle();
void rotate_body_frame_to_NE(float &x, float &y);
uint16_t get_pilot_speed_dn() const;
void run_rate_controller();
void run_rate_controller_main();
// if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
struct RateControllerRates {
uint8_t fast_logging_rate;
uint8_t medium_logging_rate;
uint8_t filter_rate;
uint8_t main_loop_rate;
};
uint8_t calc_gyro_decimation(uint8_t gyro_decimation, uint16_t rate_hz);
void rate_controller_thread();
void rate_controller_filter_update();
void rate_controller_log_update();
void rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high);
void enable_fast_rate_loop(uint8_t rate_decimation, RateControllerRates& rates);
void disable_fast_rate_loop(RateControllerRates& rates);
void update_dynamic_notch_at_specified_rate_main();
// endif AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
#if AC_CUSTOMCONTROL_MULTI_ENABLED
void run_custom_controller() { custom_control.update(); }
@ -802,7 +835,7 @@ private:
// failsafe.cpp
void failsafe_enable();
void failsafe_disable();
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
void afs_fs_check(void);
#endif
@ -874,6 +907,7 @@ private:
// Log.cpp
void Log_Write_Control_Tuning();
void Log_Write_Attitude();
void Log_Write_Rate();
void Log_Write_EKF_POS();
void Log_Write_PIDS();
void Log_Write_Data(LogDataID id, int32_t value);
@ -888,6 +922,7 @@ private:
void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out);
void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z);
void Log_Write_Vehicle_Startup_Messages();
void Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin);
#endif // HAL_LOGGING_ENABLED
// mode.cpp
@ -917,7 +952,8 @@ private:
// motors.cpp
void arm_motors_check();
void auto_disarm_check();
void motors_output();
void motors_output(bool full_push = true);
void motors_output_main();
void lost_vehicle_check();
// navigation.cpp
@ -1027,6 +1063,10 @@ private:
#endif
#if MODE_GUIDED_ENABLED
ModeGuided mode_guided;
#if AP_SCRIPTING_ENABLED
// Custom modes registered at runtime
ModeGuidedCustom *mode_guided_custom[5];
#endif
#endif
ModeLand mode_land;
#if MODE_LOITER_ENABLED
@ -1078,6 +1118,9 @@ private:
Mode *mode_from_mode_num(const Mode::Number mode);
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
bool started_rate_thread;
bool using_rate_thread;
public:
void failsafe_check(); // failsafe.cpp
};

View File

@ -505,10 +505,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
@ -583,7 +589,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
static const ap_message STREAM_ADSB_msgs[] = {
MSG_ADSB_VEHICLE,
@ -1519,7 +1526,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
}
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {
return MAV_RESULT_ACCEPTED;
}
@ -1657,3 +1664,148 @@ uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
#if MODE_AUTO_ENABLED
&copter.mode_auto, // This auto is actually auto RTL!
&copter.mode_auto, // This one is really is auto!
#endif
#if MODE_ACRO_ENABLED
&copter.mode_acro,
#endif
&copter.mode_stabilize,
&copter.mode_althold,
#if MODE_CIRCLE_ENABLED
&copter.mode_circle,
#endif
#if MODE_LOITER_ENABLED
&copter.mode_loiter,
#endif
#if MODE_GUIDED_ENABLED
&copter.mode_guided,
#endif
&copter.mode_land,
#if MODE_RTL_ENABLED
&copter.mode_rtl,
#endif
#if MODE_DRIFT_ENABLED
&copter.mode_drift,
#endif
#if MODE_SPORT_ENABLED
&copter.mode_sport,
#endif
#if MODE_FLIP_ENABLED
&copter.mode_flip,
#endif
#if AUTOTUNE_ENABLED
&copter.mode_autotune,
#endif
#if MODE_POSHOLD_ENABLED
&copter.mode_poshold,
#endif
#if MODE_BRAKE_ENABLED
&copter.mode_brake,
#endif
#if MODE_THROW_ENABLED
&copter.mode_throw,
#endif
#if HAL_ADSB_ENABLED
&copter.mode_avoid_adsb,
#endif
#if MODE_GUIDED_NOGPS_ENABLED
&copter.mode_guided_nogps,
#endif
#if MODE_SMARTRTL_ENABLED
&copter.mode_smartrtl,
#endif
#if MODE_FLOWHOLD_ENABLED
(Mode*)copter.g2.mode_flowhold_ptr,
#endif
#if MODE_FOLLOW_ENABLED
&copter.mode_follow,
#endif
#if MODE_ZIGZAG_ENABLED
&copter.mode_zigzag,
#endif
#if MODE_SYSTEMID_ENABLED
(Mode *)copter.g2.mode_systemid_ptr,
#endif
#if MODE_AUTOROTATE_ENABLED
&copter.mode_autorotate,
#endif
#if MODE_TURTLE_ENABLED
&copter.mode_turtle,
#endif
};
const uint8_t base_mode_count = ARRAY_SIZE(modes);
uint8_t mode_count = base_mode_count;
#if AP_SCRIPTING_ENABLED
for (uint8_t i = 0; i < ARRAY_SIZE(copter.mode_guided_custom); i++) {
if (copter.mode_guided_custom[i] != nullptr) {
mode_count += 1;
}
}
#endif
// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}
// Ask the mode for its name and number
const char* name;
uint8_t mode_number;
if (index_zero < base_mode_count) {
name = modes[index_zero]->name();
mode_number = (uint8_t)modes[index_zero]->mode_number();
} else {
#if AP_SCRIPTING_ENABLED
const uint8_t custom_index = index_zero - base_mode_count;
if (copter.mode_guided_custom[custom_index] == nullptr) {
// Invalid index, should not happen
return mode_count;
}
name = copter.mode_guided_custom[custom_index]->name();
mode_number = (uint8_t)copter.mode_guided_custom[custom_index]->mode_number();
#else
// Should not endup here
return mode_count;
#endif
}
#if MODE_AUTO_ENABLED
// Auto RTL is odd
// Have to deal with is separately becase its number and name can change depending on if were in it or not
if (index_zero == 0) {
mode_number = (uint8_t)Mode::Number::AUTO_RTL;
name = "AUTO RTL";
} else if (index_zero == 1) {
mode_number = (uint8_t)Mode::Number::AUTO;
name = "AUTO";
}
#endif
mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);
return mode_count;
}

View File

@ -64,6 +64,10 @@ protected:
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
#endif
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;
private:
// sanity check velocity or acceleration vector components are numbers

View File

@ -1,4 +1,5 @@
#include "Copter.h"
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
#if HAL_LOGGING_ENABLED
@ -76,6 +77,10 @@ void Copter::Log_Write_Control_Tuning()
void Copter::Log_Write_Attitude()
{
attitude_control->Write_ANG();
}
void Copter::Log_Write_Rate()
{
attitude_control->Write_Rate(*pos_control);
}
@ -339,6 +344,16 @@ struct PACKED log_Guided_Attitude_Target {
float climb_rate;
};
// rate thread dt stats
struct PACKED log_Rate_Thread_Dt {
LOG_PACKET_HEADER;
uint64_t time_us;
float dt;
float dtAvg;
float dtMax;
float dtMin;
};
// Write a Guided mode position target
// pos_target is lat, lon, alt OR offset from ekf origin in cm
// terrain should be 0 if pos_target.z is alt-above-ekf-origin, 1 if alt-above-terrain
@ -386,6 +401,21 @@ void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, f
logger.WriteBlock(&pkt, sizeof(pkt));
}
void Copter::Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin)
{
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
const log_Rate_Thread_Dt pkt {
LOG_PACKET_HEADER_INIT(LOG_RATE_THREAD_DT_MSG),
time_us : AP_HAL::micros64(),
dt : dt,
dtAvg : dtAvg,
dtMax : dtMax,
dtMin : dtMin
};
logger.WriteBlock(&pkt, sizeof(pkt));
#endif
}
// type and unit information can be found in
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
// units and "Format characters" for field type information
@ -527,6 +557,18 @@ const struct LogStructure Copter::log_structure[] = {
{ LOG_GUIDED_ATTITUDE_TARGET_MSG, sizeof(log_Guided_Attitude_Target),
"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },
// @LoggerMessage: RTDT
// @Description: Attitude controller time deltas
// @Field: TimeUS: Time since system startup
// @Field: dt: current time delta
// @Field: dtAvg: current time delta average
// @Field: dtMax: Max time delta since last log output
// @Field: dtMin: Min time delta since last log output
{ LOG_RATE_THREAD_DT_MSG, sizeof(log_Rate_Thread_Dt),
"RTDT", "Qffff", "TimeUS,dt,dtAvg,dtMax,dtMin", "sssss", "F----" , true },
};
uint8_t Copter::get_num_log_structures() const

View File

@ -1,6 +1,7 @@
#include "Copter.h"
#include <AP_Gripper/AP_Gripper.h>
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
/*
This program is free software: you can redistribute it and/or modify
@ -771,7 +772,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 1),
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// @Group: AFS_
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
AP_SUBGROUPINFO(afs, "AFS_", 6, ParametersG2, AP_AdvancedFailsafe),
@ -1232,6 +1233,22 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
// @User: Advanced
AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT),
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
// @Param: FSTRATE_ENABLE
// @DisplayName: Enable the fast Rate thread
// @Description: Enable the fast Rate thread. In the default case the fast rate divisor, which controls the update frequency of the thread, is dynamically scaled from FSTRATE_DIV to avoid overrun in the gyro sample buffer and main loop slow-downs. Other values can be selected to fix the divisor to FSTRATE_DIV on arming or always.
// @User: Advanced
// @Values: 0:Disabled,1:Enabled-Dynamic,2:Enabled-FixedWhenArmed,3:Enabled-Fixed
AP_GROUPINFO("FSTRATE_ENABLE", 9, ParametersG2, att_enable, 0),
// @Param: FSTRATE_DIV
// @DisplayName: Fast rate thread divisor
// @Description: Fast rate thread divisor used to control the maximum fast rate update rate. The actual rate is the gyro rate in Hz divided by this value. This value is scaled depending on the configuration of FSTRATE_ENABLE.
// @User: Advanced
// @Range: 1 10
AP_GROUPINFO("FSTRATE_DIV", 10, ParametersG2, att_decimation, 1),
#endif
// ID 62 is reserved for the AP_SUBGROUPEXTENSION
AP_GROUPEND
@ -1240,8 +1257,11 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
/*
constructor for g2 object
*/
ParametersG2::ParametersG2(void)
: command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)
ParametersG2::ParametersG2(void) :
unused_integer{17}
#if HAL_BUTTON_ENABLED
,button_ptr(&copter.button)
#endif
#if AP_TEMPCALIBRATION_ENABLED
, temp_calibration()
#endif
@ -1251,21 +1271,21 @@ ParametersG2::ParametersG2(void)
#if HAL_PROXIMITY_ENABLED
, proximity()
#endif
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
,afs()
#endif
#if MODE_SMARTRTL_ENABLED
,smart_rtl()
#endif
#if USER_PARAMS_ENABLED
,user_parameters()
#endif
#if MODE_FLOWHOLD_ENABLED
,mode_flowhold_ptr(&copter.mode_flowhold)
#endif
#if MODE_FOLLOW_ENABLED
,follow()
#endif
#if USER_PARAMS_ENABLED
,user_parameters()
#endif
#if AUTOTUNE_ENABLED
,autotune_ptr(&copter.mode_autotune.autotune)
#endif
@ -1275,13 +1295,9 @@ ParametersG2::ParametersG2(void)
#if MODE_AUTOROTATE_ENABLED
,arot()
#endif
#if HAL_BUTTON_ENABLED
,button_ptr(&copter.button)
#endif
#if MODE_ZIGZAG_ENABLED
,mode_zigzag_ptr(&copter.mode_zigzag)
#endif
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)
#endif
@ -1290,6 +1306,8 @@ ParametersG2::ParametersG2(void)
,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)
#endif
,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)
#if WEATHERVANE_ENABLED
,weathervane()
#endif

View File

@ -499,6 +499,11 @@ public:
// altitude at which nav control can start in takeoff
AP_Float wp_navalt_min;
// unused_integer simply exists so that the constructor for
// ParametersG2 can be created with a relatively easy syntax in
// the face of many #ifs:
uint8_t unused_integer;
// button checking
#if HAL_BUTTON_ENABLED
AP_Button *button_ptr;
@ -530,8 +535,8 @@ public:
// whether to enforce acceptance of packets only from sysid_my_gcs
AP_Int8 sysid_enforce;
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// advanced failsafe library
AP_AdvancedFailsafe_Copter afs;
#endif
@ -685,6 +690,9 @@ public:
AP_Float pldp_range_finder_maximum_m;
AP_Float pldp_delay_s;
AP_Float pldp_descent_speed_ms;
AP_Int8 att_enable;
AP_Int8 att_decimation;
};
extern const AP_Param::Info var_info[];

View File

@ -1,5 +1,476 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta2 11 Dec 2024
Changes from 4.6.0-beta1
1) Board specfic changes
- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed
2) Copter specific enhancements and bug fixes
- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option
3) Plane related enhancements and bug fixes
- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes
4) Bug Fixes and minor enhancements
- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024
Changes from 4.5.7
1) Board specific changes
- AnyLeaf H7 supports compass and onboard logging
- Blitz743Pro supports CAN
- BlueRobotics Navigator supports BMP390 baro
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
- CB Unmanned Stamp H743 support
- ClearSky CSKY405 support
- CUAV-7-Nano default batt monitor fixed
- CubeRed bootloader fixes including disabling 2nd core by default
- CubeRed supports PPP networking between primary and secondary MCU
- CubeRedPrimary supports external compasses
- ESP32 main loop rate improvements
- ESP32 RC input fixes and wifi connection reliability improved
- ESP32 safety switch and GPIO pin support
- FlyingMoon no longer support MAX7456
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
- Flywoo H743 Pro support
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
- FlywooF745 supports DPS310 baro
- FPV boards lose SMBus battery support (to save flash)
- GEPRC F745BTHD support
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
- Holybro Kakute F4 Wing support
- iFlight 2RAW H743 supports onboard logging
- JFB110 supports measuring servo rail voltage
- JFB110 supports safety switch LED
- JHEM-JHEF405 bootloader supports firmware updates via serial
- JHEMCU GF30H743 HD support
- JHEMCU-GF16-F405 autopilot support
- JHEMCU-GSF405A becomes FPV board (to save flash)
- KakuteF7 only supports BMP280 baro (to save flash)
- KakuteH7Mini supports ICM42688 IMU
- Linux auto detection of GPS baud rate fixed
- Linux board scheduler jitter reduced
- Linux board shutdown fixes
- MakeFlyEasy PixPilot-V6Pro support
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
- MatekH7A3 support Bi-directional DShot
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
- MicoAir743 internal compass orientation fixed
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
- mRo Control Zero Classic supports servo rail analog input
- mRo KitCAN revC fixed
- Mugin MUPilot support
- OmnibusF7v2 loses quadplane support (to save flash)
- Pixhack-v3 board added (same as fmuv3)
- Pixhawk6C bootloader supports flashing firmware from SD card
- RadiolinkPIX6 imu orientation fixed
- RadiolinkPIX6 supports SPA06 baro
- ReaperF745 V4 FC supports MPU6000 IMU
- RPI5 support
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
- Solo serial ports default to MAVLink1
- SpeedyBeeF405Wing gets Bi-directional DShot
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
- Spektreworks boom board support
- TrueNavPro-G4 SPI does not share DMA
- X-MAV AP-H743v2 support
2) AHRS/EKF enhancements and fixes
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
- AHRS_OPTION to disable innovation check for airspeed sensor
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
- EK2 supports disabling external nav (see EK2_OPTIONS)
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
- EK3 uses filtered velocity corrections for IMU position
- EKF2, EKF3, ExternalAHRS all use common origin
- EKF3 accepts set origin even when using GPS
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
- EKF3 copes better with GPS jamming
- EKF3 logs mag fusion selection to XKFS
- EKF3 wind estimation when using GPS-for-yaw fixed
- External AHRS improvements including handling variances, pre-arm origin check
- Inertial Labs External AHRS fixes
- VectorNav driver fix for handling of error from sensor
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
- VectorNav support for sensors outside VN-100 and VN-300
3) Driver enhancements and bug fixes
- ADSB fix to display last character in status text sent to GCS
- Ainstein LR-D1 radar support
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
- AIRSPEED message sent to GCS
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
- ARSPD_OPTIONS to report calibration offset to GCS
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
- Baro provides improved atmospheric model for high altitude flight
- BARO_ALT_OFFSET slew slowed to keep EKF happy
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
- BATTx_OPTION to not send battery voltage, current, etc to GCS
- Benewake RDS02U radar support
- Bi-directional DShot on IOMCU supports reversible mask
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
- BMM350 compass support
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
- CRSF baro and vertical speeed fixed
- CRSF RX bind command support
- DroneCAN battery monitor check to avoid memory corruption when type changed
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
- DroneCAN EFI health check fix
- DroneCAN ESC battery monitors calculate consumed mah
- DroneCAN ESCs forced to zero when disarmed
- DroneCAN RPM message support
- DroneCAN timeout fix for auxiliary frames
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
- FuelLevel battery monitor fix to report capacity
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
- Hirth EFI logging includes modified throttle
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
- Hott and LTM telemetry deprecated (still available through custom build server)
- i-BUS telemetry support
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
- ICE_START_CHAN replaced with RC aux function (Plane only)
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
- IE 2400 generator error message severity to GCS improved
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
- MCP9600 temperature sensor I2C address fixed
- MLX90614 temperature sensor support
- MSP GPS ground course scaling fixed
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
- Networking supports reconnection to TCP server or client
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
- Relay inverted output support (see RELAYx_INVERTED parameter)
- ROMFS efficiency improvements
- RS-485 driver enable RTS flow control
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
- Septentrio GPS sat count correctly drops to zero when 255 received
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
- Single LED for user notification supported
- SPA06 baro supported
- Sum battery monitor optionally reports minimum voltage instead of average
- Sum battery monitor reports average temp
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
- UBlox GPS time ignored until at least 2D fix
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
- Volz logs desired and actual position, voltage, current, motor and PCB temp
- Volz server feedback and logging fixed
- Volz servo output in its own thread resulting in smoother movements
- W25N02KV flash support
4) Networking enhancements and fixes
- Allow multiple UDP clients to connect/disconnect/reconnect
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
5) Camera and gimbal enhancements
- Alexmos precision improved slightly
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
- Dual serial camera gimbal mounts fixed
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
- Retract Mount2 aux function added (see RCx_OPTION = 113)
- Servo gimbal reported angles respect roll, pitch and yaw limits
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
- Siyi picture and video download scripts
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
- Siyi ZT6 hardware id and set-lens fixed
- Topotek gimbal support
- Trigger distance ignores GPS status and only uses EKF reported location
6) Harmonic notch enhancements
- Harmonic notch is active in forward flight on quadplanes
- Harmonic notch filter freq clamping and disabling reworked
- Harmonic notch handles negative ESC RPMs
- Harmonic notch supports per-motor throttle-based harmonic notch
7) Copter specific enhancements and bug fixes
- Attitude control fix to dt update order (reduces rate controller noise)
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
- Auto mode small target position jump when takeoff completes removed
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
- AutoTune fix to prevent spool up after landing
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
- Config error avoided if auto mode is paused very soon after poweron
- FLIGHT_OPTIONS bit added to require position estimate before arming
- Follow mode slowdown calcs fixed when target is moving
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
- Landing detector logging added to ease support (see LDET message)
- Loiter unlimited command accepts NaNs (QGC sends these)
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
- Payload place bug fix when aborted because gripper is already released
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
- RTL_ALT minimum reduced to 30cm
- SystemID position controller support (Copter and Heli)
- TriCopter motor test and slew-up fixed
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
8) TradHeli specific enhancements
- Autorotation yaw behaviour fix
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
- Blade pitch angle logging added (see SWSH log message)
- Constrain cyclic roll for intermeshing
- ICE / turbine cool down fix
- Inverted flight extended to non manual throttle modes
- Inverted flight transitions smoothed and restricted to only Stabilize mode
- SWSH logging fix for reversed collectives
9) Plane specific enhancements and bug fixes
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
- Allow for different orientations of landing rangefinder
- Assistance requirements evaluted on mode change
- FBWB/CRUISE climb/sink rate limited by TECS limits
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
- Glider pullup support (available only through custom build server)
- Loiter breakout improved to better handle destinations inside loiter circle
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
- Quadplane assistance check enhancements
- Quadplane Deca frame support
- Quadplane gets smoother takeoff by input shaping target accel and velocity
- Servo wiggles in altitude wait staged to be one after another
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
- Takeoff fixes for fence autoenable
- Takeoff improvements including less overshoot of TKOFF_ALT
- TECS reset along with other controllers (important if plane dropped from balloon)
- Tilt quadplane ramp of motors on back transition fixed
- Tiltrotor tilt angles logged
- TKOFF_THR_MIN applied to SLT transitions
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
10) Rover specific enhancements and bug fixes
- Auto mode reversed state maintained if momentarily switched to Hold mode
- Circle mode tracks better and avoids getting stuck at circle edge
- Flight time stats fixed
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
- Omni3Mecanum frame support
- Stopping point uses max deceleration (was incorrectly using acceleration)
- Wheel rate controller slew rate fix
11) Antenna Tracker specific enhancements and bug fixes
- Never track lat,lon of 0,0
12) Scripting enhancements
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
- battery_internal_resistance_check.lua monitors battery resistance
- CAN:get_device returns nil for unconfigured CAN device
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
- Copter:get_target_location, update_target_location support
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
- Display text on OLED display supported
- Docs improved for many bindings
- EFI get_last_update_ms binding
- EFI_SkyPower.lua driver accepts 2nd supply voltage
- ESC_slew_rate.lua example script supports testing ESCs
- Filesystem CRC32 check to allow scripts to check module versions
- forced arming support
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
- Halo6000 EFI driver can log all CAN packets for easier debugging
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
- I2C:transfer support
- IMU gyros_consistent and accels_consistent bindings added
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
- INS bindings for is calibrating, gyro and accel sensor values
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
- Logging of booleans supported
- Lua language checks improved (finds more errors)
- MAVLink commands can be called from scripting
- MCU voltage binding (see analog:mcu_voltage)
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
- "open directory failed" false warning when scripts in ROMFS fixed
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
- Pass by reference values are always initialized
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
- plane_aerobatics.lua minor enhancements
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
- "require" function failures in rare circumstances fixed
- "require" function works for modules in ROMFS (e.g. not on SD card)
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
- SD card formatting supported
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
- Temperature sensor bindings added
- uint64 support
- Various performance and memory usage optimizations
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
13) GCS / mavlink related changes and fixes
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
- Deny attempts to upload two missions simultaneously
- Fence and Rally points may be uploaded using FTP
- GPS_INPUT and HIL_GPS handles multiple GPSs
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
- MAV_CMD_SET_HAGL support (Plane only)
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
- Message interval supports TERRAIN_REPORT msg
- Mission upload may be cancelled using MISSION_CLEAR_ALL
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
- RC_CHANNELS_RAW deprecated
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
14) Logging enhancements and fixes
- AC_PID resets and I-term sets logged
- ANG provides attitude at high rate (equivalent to ATT)
- ATT logs angles as floats (better resolution than ints)
- CAND message gets driver index
- DCM log message includes roll/pitch and yaw error
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
- FMT messages written as required instead of all at beginning
- Logging restarted after download completes when LOG_DISARMED = 1
- MISE msg logs active mission command (CMD logged when commands are uploaded)
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
- RPM sensor logging gets instance field, quality and health fields
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
- UART data rates logged at 1hz (see UART message)
15) ROS2 / DDS support
- Airspeed published
- Battery topic reports all available batteries
- Compile-time configurable rates for each publisher
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
- GPS global origin published at 1 Hz
- High frequency raw imu data transmission
- Joystick support
- Support sending waypoints to Copter and Rover
- Remove the XML refs file in favor of binary entity creation
16) Safety related enhancements and fixes
- Accel/Gyro inconsistent message fixed for using with only single IMU
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
- Far from EKF origin pre-arm check removed (Copter only)
- Fence breach warning message slightly improved
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
- LEDs flash green lights based on EKF location not GPS
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
- Pre-arm check if OpenDroneID is compiled in but disabled
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
- Pre-arm checks alert user more quickly on failure
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
- Warning of duplicate SERIALx_PROTOCOL = RCIN
17) Other bug fixes and minor enhancements
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
- Bootloader rejects allocation of broadcast node ID
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
- Dijkstras fix to correct use of uninitialised variable
- DShot rates are not limited by NeoPixel rates
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
- Filesystem does not show entries for empty @ files
- Filesystem efficiency improvements when reading files
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
- Internal error thrown if we lose parameters due to saving queue being too small
- MAVLink via DroneCAN baud rate fix
- SPI pins may also be used as GPIOs
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
18) Developer focused fixes and enhancements
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
- Cygwin build fix for non-SITL builds
- Cygwin build fixed with malloc wrap
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
- EKF3 code generator documentation and cleanup
- GPS jamming simulator added
- MacOS compiler warnings reduced
- SFML joystick support
- SITL support for OpenBSD
- Text warning if older Fence or Rally point protocols are used
------------------------------------------------------------------
Release 4.5.7 08 Oct 2024
Changes from 4.5.7-beta1
@ -305,7 +776,7 @@ Changes from 4.5.0-beta1:
- broaden acceptance criteria for GPS yaw measurement for moving baseline yaw
------------------------------------------------------------------
Copter 4.5.0-beta1 30-Jan-2025
Copter 4.5.0-beta1 30-Jan-2024
Changes from 4.4.4
1) New autopilots supported
- ACNS-F405AIO
@ -989,7 +1460,7 @@ Changes from 4.3.6
e) Memory corruption bug in the STM32H757 (very rare)
f) RC input on IOMCU bug fix (RC might not be regained if lost)
------------------------------------------------------------------
Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6--beta2 27-Mar-2023
Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6-beta2 27-Mar-2023
Changes from 4.3.5
1) Bi-directional DShot fix for possible motor stop approx 72min after startup
------------------------------------------------------------------

View File

@ -4,7 +4,7 @@
#include "Copter.h"
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
/*
setup radio_out values for all channels to termination values
@ -63,4 +63,4 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void)
{
copter.set_mode(Mode::Number::AUTO,ModeReason::GCS_FAILSAFE);
}
#endif // ADVANCED_FAILSAFE
#endif // AP_COPTER_ADVANCED_FAILSAFE_ENABLED

View File

@ -18,7 +18,9 @@
advanced failsafe support for copter
*/
#if ADVANCED_FAILSAFE
#include "config.h"
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
/*
@ -44,5 +46,5 @@ protected:
void set_mode_auto(void) override;
};
#endif // ADVANCED_FAILSAFE
#endif // AP_COPTER_ADVANCED_FAILSAFE_ENABLED

View File

@ -146,9 +146,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
read_radio();
// pass through throttle to motors
SRV_Channels::cork();
auto &srv = AP::srv();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
SRV_Channels::push();
srv.push();
// read some compass values
compass.read();

View File

@ -574,8 +574,8 @@
// Developer Items
//
#ifndef ADVANCED_FAILSAFE
# define ADVANCED_FAILSAFE 0
#ifndef AP_COPTER_ADVANCED_FAILSAFE_ENABLED
# define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 0
#endif
#ifndef CH_MODE_DEFAULT

View File

@ -87,7 +87,8 @@ enum LoggingParameters {
LOG_GUIDED_POSITION_TARGET_MSG,
LOG_SYSIDD_MSG,
LOG_SYSIDS_MSG,
LOG_GUIDED_ATTITUDE_TARGET_MSG
LOG_GUIDED_ATTITUDE_TARGET_MSG,
LOG_RATE_THREAD_DT_MSG
};
#define MASK_LOG_ATTITUDE_FAST (1<<0)

View File

@ -95,9 +95,10 @@ void Copter::esc_calibration_passthrough()
hal.scheduler->delay(3);
// pass through to motors
SRV_Channels::cork();
auto &srv = AP::srv();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
SRV_Channels::push();
srv.push();
}
#endif // FRAME_CONFIG != HELI_FRAME
}
@ -112,25 +113,26 @@ void Copter::esc_calibration_auto()
esc_calibration_setup();
// raise throttle to maximum
SRV_Channels::cork();
auto &srv = AP::srv();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
SRV_Channels::push();
srv.push();
// delay for 5 seconds while outputting pulses
uint32_t tstart = millis();
while (millis() - tstart < 5000) {
SRV_Channels::cork();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
SRV_Channels::push();
srv.push();
esc_calibration_notify();
hal.scheduler->delay(3);
}
// block until we restart
while(1) {
SRV_Channels::cork();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
SRV_Channels::push();
srv.push();
esc_calibration_notify();
hal.scheduler->delay(3);
}

View File

@ -492,7 +492,7 @@ void Copter::do_failsafe_action(FailsafeAction action, ModeReason reason){
set_mode_SmartRTL_or_land_with_pause(reason);
break;
case FailsafeAction::TERMINATE: {
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
g2.afs.gcs_terminate(true, "Failsafe");
#else
arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);

View File

@ -72,7 +72,7 @@ void Copter::failsafe_check()
}
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
/*
check for AFS failsafe check
*/

View File

@ -32,158 +32,141 @@ PayloadPlace Mode::payload_place;
// return the static controller object corresponding to supplied mode
Mode *Copter::mode_from_mode_num(const Mode::Number mode)
{
Mode *ret = nullptr;
switch (mode) {
#if MODE_ACRO_ENABLED
case Mode::Number::ACRO:
ret = &mode_acro;
break;
return &mode_acro;
#endif
case Mode::Number::STABILIZE:
ret = &mode_stabilize;
break;
return &mode_stabilize;
case Mode::Number::ALT_HOLD:
ret = &mode_althold;
break;
return &mode_althold;
#if MODE_AUTO_ENABLED
case Mode::Number::AUTO:
ret = &mode_auto;
break;
return &mode_auto;
#endif
#if MODE_CIRCLE_ENABLED
case Mode::Number::CIRCLE:
ret = &mode_circle;
break;
return &mode_circle;
#endif
#if MODE_LOITER_ENABLED
case Mode::Number::LOITER:
ret = &mode_loiter;
break;
return &mode_loiter;
#endif
#if MODE_GUIDED_ENABLED
case Mode::Number::GUIDED:
ret = &mode_guided;
break;
return &mode_guided;
#endif
case Mode::Number::LAND:
ret = &mode_land;
break;
return &mode_land;
#if MODE_RTL_ENABLED
case Mode::Number::RTL:
ret = &mode_rtl;
break;
return &mode_rtl;
#endif
#if MODE_DRIFT_ENABLED
case Mode::Number::DRIFT:
ret = &mode_drift;
break;
return &mode_drift;
#endif
#if MODE_SPORT_ENABLED
case Mode::Number::SPORT:
ret = &mode_sport;
break;
return &mode_sport;
#endif
#if MODE_FLIP_ENABLED
case Mode::Number::FLIP:
ret = &mode_flip;
break;
return &mode_flip;
#endif
#if AUTOTUNE_ENABLED
case Mode::Number::AUTOTUNE:
ret = &mode_autotune;
break;
return &mode_autotune;
#endif
#if MODE_POSHOLD_ENABLED
case Mode::Number::POSHOLD:
ret = &mode_poshold;
break;
return &mode_poshold;
#endif
#if MODE_BRAKE_ENABLED
case Mode::Number::BRAKE:
ret = &mode_brake;
break;
return &mode_brake;
#endif
#if MODE_THROW_ENABLED
case Mode::Number::THROW:
ret = &mode_throw;
break;
return &mode_throw;
#endif
#if HAL_ADSB_ENABLED
case Mode::Number::AVOID_ADSB:
ret = &mode_avoid_adsb;
break;
return &mode_avoid_adsb;
#endif
#if MODE_GUIDED_NOGPS_ENABLED
case Mode::Number::GUIDED_NOGPS:
ret = &mode_guided_nogps;
break;
return &mode_guided_nogps;
#endif
#if MODE_SMARTRTL_ENABLED
case Mode::Number::SMART_RTL:
ret = &mode_smartrtl;
break;
return &mode_smartrtl;
#endif
#if MODE_FLOWHOLD_ENABLED
case Mode::Number::FLOWHOLD:
ret = (Mode *)g2.mode_flowhold_ptr;
break;
return (Mode *)g2.mode_flowhold_ptr;
#endif
#if MODE_FOLLOW_ENABLED
case Mode::Number::FOLLOW:
ret = &mode_follow;
break;
return &mode_follow;
#endif
#if MODE_ZIGZAG_ENABLED
case Mode::Number::ZIGZAG:
ret = &mode_zigzag;
break;
return &mode_zigzag;
#endif
#if MODE_SYSTEMID_ENABLED
case Mode::Number::SYSTEMID:
ret = (Mode *)g2.mode_systemid_ptr;
break;
return (Mode *)g2.mode_systemid_ptr;
#endif
#if MODE_AUTOROTATE_ENABLED
case Mode::Number::AUTOROTATE:
ret = &mode_autorotate;
break;
return &mode_autorotate;
#endif
#if MODE_TURTLE_ENABLED
case Mode::Number::TURTLE:
ret = &mode_turtle;
break;
return &mode_turtle;
#endif
default:
break;
}
return ret;
#if MODE_GUIDED_ENABLED && AP_SCRIPTING_ENABLED
// Check registered custom modes
for (uint8_t i = 0; i < ARRAY_SIZE(mode_guided_custom); i++) {
if ((mode_guided_custom[i] != nullptr) && (mode_guided_custom[i]->mode_number() == mode)) {
return mode_guided_custom[i];
}
}
#endif
return nullptr;
}

View File

@ -4,7 +4,7 @@
#include <AP_Math/chirp.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h> // TODO why is this needed if Copter.h includes this
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
#include "afs_copter.h"
#endif
@ -134,7 +134,7 @@ public:
virtual bool allows_flip() const { return false; }
virtual bool crash_check_enabled() const { return true; }
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// Return the type of this mode for use by advanced failsafe
virtual AP_AdvancedFailsafe_Copter::control_mode afs_mode() const { return AP_AdvancedFailsafe_Copter::control_mode::AFS_STABILIZED; }
#endif
@ -517,7 +517,7 @@ public:
bool allows_inverted() const override { return true; };
#endif
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// Return the type of this mode for use by advanced failsafe
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
#endif
@ -1068,7 +1068,7 @@ public:
bool requires_terrain_failsafe() const override { return true; }
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// Return the type of this mode for use by advanced failsafe
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
#endif
@ -1193,14 +1193,37 @@ private:
void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle);
// controls which controller is run (pos or vel):
SubMode guided_mode = SubMode::TakeOff;
bool send_notification; // used to send one time notification to ground station
bool takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear)
static SubMode guided_mode;
static bool send_notification; // used to send one time notification to ground station
static bool takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear)
// guided mode is paused or not
bool _paused;
static bool _paused;
};
#if AP_SCRIPTING_ENABLED
// Mode which behaves as guided with custom mode number and name
class ModeGuidedCustom : public ModeGuided {
public:
// constructor registers custom number and names
ModeGuidedCustom(const Number _number, const char* _full_name, const char* _short_name);
bool init(bool ignore_checks) override;
Number mode_number() const override { return number; }
const char *name() const override { return full_name; }
const char *name4() const override { return short_name; }
// State object which can be edited by scripting
AP_Vehicle::custom_mode_state state;
private:
const Number number;
const char* full_name;
const char* short_name;
};
#endif
class ModeGuidedNoGPS : public ModeGuided {
@ -1243,7 +1266,7 @@ public:
bool is_landing() const override { return true; };
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// Return the type of this mode for use by advanced failsafe
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
#endif
@ -1425,7 +1448,7 @@ public:
bool requires_terrain_failsafe() const override { return true; }
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// Return the type of this mode for use by advanced failsafe
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
#endif

View File

@ -824,7 +824,7 @@ void ModeAuto::exit_mission()
bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd)
{
// only process guided waypoint if we are in guided mode
if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && _mode == SubMode::NAVGUIDED)) {
if (!copter.flightmode->in_guided_mode()) {
return false;
}

View File

@ -7,7 +7,7 @@
*/
static Vector3p guided_pos_target_cm; // position target (used by posvel controller only)
bool guided_pos_terrain_alt; // true if guided_pos_target_cm.z is an alt above terrain
static bool guided_pos_terrain_alt; // true if guided_pos_target_cm.z is an alt above terrain
static Vector3f guided_vel_target_cms; // velocity target (used by pos_vel_accel controller and vel_accel controller)
static Vector3f guided_accel_target_cmss; // acceleration target (used by pos_vel_accel controller vel_accel controller and accel controller)
static uint32_t update_time_ms; // system time of last target update to pos_vel_accel, vel_accel or accel controller
@ -30,7 +30,15 @@ struct Guided_Limit {
float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit)
uint32_t start_time;// system time in milliseconds that control was handed to the external computer
Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit
} guided_limit;
} static guided_limit;
// controls which controller is run (pos or vel):
ModeGuided::SubMode ModeGuided::guided_mode = SubMode::TakeOff;
bool ModeGuided::send_notification; // used to send one time notification to ground station
bool ModeGuided::takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear)
// guided mode is paused or not
bool ModeGuided::_paused;
// init - initialise guided controller
bool ModeGuided::init(bool ignore_checks)

View File

@ -0,0 +1,23 @@
#include "Copter.h"
#if MODE_GUIDED_ENABLED && AP_SCRIPTING_ENABLED
// constructor registers custom number and names
ModeGuidedCustom::ModeGuidedCustom(const Number _number, const char* _full_name, const char* _short_name):
number(_number),
full_name(_full_name),
short_name(_short_name)
{
}
bool ModeGuidedCustom::init(bool ignore_checks)
{
// Stript can block entry
if (!state.allow_entry) {
return false;
}
// Guided entry checks must also pass
return ModeGuided::init(ignore_checks);
}
#endif

View File

@ -535,11 +535,7 @@ void ModePosHold::update_brake_angle_from_velocity(float &brake_angle, float vel
}
// calculate velocity-only based lean angle
if (velocity >= 0) {
lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (velocity + 60.0f));
} else {
lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (-velocity + 60.0f));
}
lean_angle = -brake.gain * velocity * (1.0f + 500.0f / (fabsf(velocity) + 60.0f));
// do not let lean_angle be too far from brake_angle
brake_angle = constrain_float(lean_angle, brake_angle - brake_rate, brake_angle + brake_rate);
@ -592,7 +588,7 @@ void ModePosHold::update_wind_comp_estimate()
}
// limit acceleration
const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * 981.0f;
const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * (GRAVITY_MSS*100);
const float wind_comp_ef_len = wind_comp_ef.length();
if (!is_zero(accel_lim_cmss) && (wind_comp_ef_len > accel_lim_cmss)) {
wind_comp_ef *= accel_lim_cmss / wind_comp_ef_len;

View File

@ -414,6 +414,7 @@ void ModeSystemId::log_data() const
// Full rate logging of attitude, rate and pid loops
copter.Log_Write_Attitude();
copter.Log_Write_Rate();
copter.Log_Write_PIDS();
if (is_poscontrol_axis_type()) {

View File

@ -158,6 +158,12 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
ap.motor_test = true;
EXPECT_DELAY_MS(3000);
// wait for rate thread to stop running due to motor test
while (using_rate_thread) {
hal.scheduler->delay(1);
}
// enable and arm motors
if (!motors->armed()) {
motors->output_min(); // output lowest possible value to motors

View File

@ -133,9 +133,10 @@ void Copter::auto_disarm_check()
}
// motors_output - send output to motors library which will adjust and send to ESCs and servos
void Copter::motors_output()
// full_push is true when slower rate updates (e.g. servo output) need to be performed at the main loop rate.
void Copter::motors_output(bool full_push)
{
#if ADVANCED_FAILSAFE
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
// this is to allow the failsafe module to deliberately crash
// the vehicle. Only used in extreme circumstances to meet the
// OBC rules
@ -156,8 +157,10 @@ void Copter::motors_output()
// output any servo channels
SRV_Channels::calc_pwm();
auto &srv = AP::srv();
// cork now, so that all channel outputs happen at once
SRV_Channels::cork();
srv.cork();
// update output on any aux channels, for manual passthru
SRV_Channels::output_ch_all();
@ -181,7 +184,21 @@ void Copter::motors_output()
}
// push all channels
SRV_Channels::push();
if (full_push) {
// motor output including servos and other updates that need to run at the main loop rate
srv.push();
} else {
// motor output only at main loop rate or faster
hal.rcout->push();
}
}
// motors_output from main thread at main loop rate
void Copter::motors_output_main()
{
if (!using_rate_thread) {
motors_output();
}
}
// check for pilot stick input to trigger lost vehicle alarm

View File

@ -45,7 +45,7 @@ void Copter::init_rc_out()
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
// enable aux servos to cope with multiple output channels per motor
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
// update rate must be set after motors->init() to allow for motor mapping
motors->set_update_rate(g.rc_speed);

490
ArduCopter/rate_thread.cpp Normal file
View File

@ -0,0 +1,490 @@
/*
This program 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.
This program 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 "Copter.h"
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
#pragma GCC optimize("O2")
/*
Attitude Rate controller thread design.
Rationale: running rate outputs linked to fast gyro outputs achieves two goals:
1. High frequency gyro processing allows filters to be applied with high sample rates
which is advantageous in removing high frequency noise and associated aliasing
2. High frequency rate control reduces the latency between control and action leading to
better disturbance rejection and faster responses which generally means higher
PIDs can be used without introducing control oscillation
(1) is already mostly achieved through the higher gyro rates that are available via
INS_GYRO_RATE. (2) requires running the rate controller at higher rates via a separate thread
Goal: the ideal scenario is to run in a single cycle:
gyro read->filter->publish->rate control->motor output
This ensures the minimum latency between gyro sample and motor output. Other functions need
to also run faster than they would normally most notably logging and filter frequencies - most
notably the harmonic notch frequency.
Design assumptions:
1. The sample rate of the IMUs is consistent and accurate.
This is the most basic underlying assumption. An alternative approach would be to rely on
the timing of when samples are received but this proves to not work in practice due to
scheduling delays. Thus the dt used by the attitude controller is the delta between IMU
measurements, not the delta between processing cycles in the rate thread.
2. Every IMU reading must be processed or consistently sub-sampled.
This is an assumption that follows from (1) - so it means that attitude control should
process every sample or every other sample or every third sample etc. Note that these are
filtered samples - all incoming samples are processed for filtering purposes, it is only
for the purposes of rate control that we are sub-sampling.
3. The data that the rate loop requires is timely, consistent and accurate.
Rate control essentially requires two components - the target and the actuals. The actuals
come from the incoming gyro sample combined with the state of the PIDs. The target comes
from attitude controller which is running at a slower rate in the main loop. Since the rate
thread can read the attitude target at any time it is important that this is always available
consistently and is updated consistently.
4. The data that the rest of the vehicle uses is the same data that the rate thread uses.
Put another way any gyro value that the vehicle uses (e.g. in the EKF etc), must have already
been processed by the rate thread. Where this becomes important is with sub-sampling - if
rate gyro values are sub-sampled we need to make sure that the vehicle is also only using
the sub-sampled values.
Design:
1. Filtered gyro samples are (sub-sampled and) pushed into an ObjectBuffer from the INS backend.
2. The pushed sample is published to the INS front-end so that the rest of the vehicle only
sees published values that have been used by the rate controller. When the rate thread is not
in use the filtered samples are effectively sub-sampled at the main loop rate. The EKF is unaffected
as it uses delta angles calculated from the raw gyro values. (It might be possible to avoid publishing
from the rate thread by only updating _gyro_filtered when a value is pushed).
3. A notification is sent that a sample is available
4. The rate thread is blocked waiting for a sample. When it receives a notification it:
4a. Runs the rate controller
4b. Pushes the new pwm values. Periodically at the main loop rate all of the SRV_Channels::push()
functionality is run as well.
5. The rcout dshot thread is blocked waiting for a new pwm value. When it is signalled by the
rate thread it wakes up and runs the dshot motor output logic.
6. Periodically the rate thread:
6a. Logs the rate outputs (1Khz)
6b. Updates the notch filter centers (Gyro rate/2)
6c. Checks the ObjectBuffer length and main loop delay (10Hz)
If the ObjectBuffer length has been longer than 2 for the last 5 cycles or the main loop has
been slowed down then the rate thread is slowed down by telling the INS to sub-sample. This
mechanism is continued until the rate thread is able to keep up with the sub-sample rate.
The inverse of this mechanism is run if the rate thread is able to keep up but is running slower
than the gyro sample rate.
6d. Updates the PID notch centers (1Hz)
7. When the rate rate changes through sub-sampling the following values are updated:
7a. The PID notch sample rate
7b. The dshot rate is constrained to be never greater than the gyro rate or rate rate
7c. The motors dt
8. Independently of the rate thread the attitude control target is updated in the main loop. In order
for target values to be consistent all updates are processed using local variables and the final
target is only written at the end of the update as a vector. Direct control of the target (e.g. in
autotune) is also constrained to be on all axes simultaneously using the new desired value. The
target makes use of the current PIDs and the "latest" gyro, it might be possible to use a loop
delayed gyro value, but that is currently out-of-scope.
Performance considerations:
On an H754 using ICM42688 and gyro sampling at 4KHz and rate thread at 4Khz the main CPU users are:
ArduCopter PRI=182 sp=0x30000600 STACK=4392/7168 LOAD=18.6%
idle PRI= 1 sp=0x300217B0 STACK= 296/ 504 LOAD= 4.3%
rcout PRI=181 sp=0x3001DAF0 STACK= 504/ 952 LOAD=10.7%
SPI1 PRI=181 sp=0x3002DAB8 STACK= 856/1464 LOAD=17.5%
SPI4 PRI=181 sp=0x3002D4A0 STACK= 888/1464 LOAD=18.3%
rate PRI=182 sp=0x3002B1D0 STACK=1272/1976 LOAD=22.4%
There is a direct correlation between the rate rate and CPU load, so if the rate rate is half the gyro
rate (i.e. 2Khz) we observe the following:
ArduCopter PRI=182 sp=0x30000600 STACK=4392/7168 LOAD=16.7%
idle PRI= 1 sp=0x300217B0 STACK= 296/ 504 LOAD=21.3%
rcout PRI=181 sp=0x3001DAF0 STACK= 504/ 952 LOAD= 6.2%
SPI1 PRI=181 sp=0x3002DAB8 STACK= 856/1464 LOAD=16.7%
SPI4 PRI=181 sp=0x3002D4A0 STACK= 888/1464 LOAD=17.8%
rate PRI=182 sp=0x3002B1D0 STACK=1272/1976 LOAD=11.5%
So we get almost a halving of CPU load in the rate and rcout threads. This is the main way that CPU
load can be handled on lower-performance boards, with the other mechanism being lowering the gyro rate.
So at a very respectable gyro rate and rate rate both of 2Khz (still 5x standard main loop rate) we see:
ArduCopter PRI=182 sp=0x30000600 STACK=4440/7168 LOAD=15.6%
idle PRI= 1 sp=0x300217B0 STACK= 296/ 504 LOAD=39.4%
rcout PRI=181 sp=0x3001DAF0 STACK= 504/ 952 LOAD= 5.9%
SPI1 PRI=181 sp=0x3002DAB8 STACK= 856/1464 LOAD= 8.9%
SPI4 PRI=181 sp=0x3002D4A0 STACK= 896/1464 LOAD= 9.1%
rate PRI=182 sp=0x30029FB0 STACK=1296/1976 LOAD=11.8%
This essentially means that its possible to run this scheme successfully on all MCUs by careful setting of
the maximum rates.
Enabling rate thread timing debug for 4Khz reads with fast logging and armed we get the following data:
Rate loop timing: gyro=178us, rate=13us, motors=45us, log=7us, ctrl=1us
Rate loop timing: gyro=178us, rate=13us, motors=45us, log=7us, ctrl=1us
Rate loop timing: gyro=177us, rate=13us, motors=46us, log=7us, ctrl=1us
The log output is an average since it only runs at 1Khz, so roughly 28us elapsed. So the majority of the time
is spent waiting for a gyro sample (higher is better here since it represents the idle time) updating the PIDs
and outputting to the motors. Everything else is relatively cheap. Since the total cycle time is 250us the duty
cycle is thus 29%
*/
#define DIV_ROUND_INT(x, d) ((x + d/2) / d)
uint8_t Copter::calc_gyro_decimation(uint8_t gyro_decimation, uint16_t rate_hz)
{
return MAX(uint8_t(DIV_ROUND_INT(ins.get_raw_gyro_rate_hz() / gyro_decimation, rate_hz)), 1U);
}
static inline bool run_decimated_callback(uint8_t decimation_rate, uint8_t& decimation_count)
{
return decimation_rate > 0 && ++decimation_count >= decimation_rate;
}
//#define RATE_LOOP_TIMING_DEBUG
/*
thread for rate control
*/
void Copter::rate_controller_thread()
{
uint8_t target_rate_decimation = constrain_int16(g2.att_decimation.get(), 1, DIV_ROUND_INT(ins.get_raw_gyro_rate_hz(), 400));
uint8_t rate_decimation = target_rate_decimation;
// set up the decimation rates
RateControllerRates rates;
rate_controller_set_rates(rate_decimation, rates, false);
uint32_t rate_loop_count = 0;
uint32_t prev_loop_count = 0;
uint32_t last_run_us = AP_HAL::micros();
float max_dt = 0.0;
float min_dt = 1.0;
uint32_t now_ms = AP_HAL::millis();
uint32_t last_rate_check_ms = 0;
uint32_t last_rate_increase_ms = 0;
#if HAL_LOGGING_ENABLED
uint32_t last_rtdt_log_ms = now_ms;
#endif
uint32_t last_notch_sample_ms = now_ms;
bool was_using_rate_thread = false;
bool notify_fixed_rate_active = true;
bool was_armed = false;
uint32_t running_slow = 0;
#ifdef RATE_LOOP_TIMING_DEBUG
uint32_t gyro_sample_time_us = 0;
uint32_t rate_controller_time_us = 0;
uint32_t motor_output_us = 0;
uint32_t log_output_us = 0;
uint32_t ctrl_output_us = 0;
uint32_t timing_count = 0;
uint32_t last_timing_msg_us = 0;
#endif
// run the filters at half the gyro rate
#if HAL_LOGGING_ENABLED
uint8_t log_loop_count = 0;
#endif
uint8_t main_loop_count = 0;
uint8_t filter_loop_count = 0;
while (true) {
#ifdef RATE_LOOP_TIMING_DEBUG
uint32_t rate_now_us = AP_HAL::micros();
#endif
// allow changing option at runtime
if (get_fast_rate_type() == FastRateType::FAST_RATE_DISABLED || ap.motor_test) {
if (was_using_rate_thread) {
disable_fast_rate_loop(rates);
was_using_rate_thread = false;
}
hal.scheduler->delay_microseconds(500);
last_run_us = AP_HAL::micros();
continue;
}
// set up rate thread requirements
if (!using_rate_thread) {
enable_fast_rate_loop(rate_decimation, rates);
}
ins.set_rate_decimation(rate_decimation);
// wait for an IMU sample
Vector3f gyro;
if (!ins.get_next_gyro_sample(gyro)) {
continue; // go around again
}
#ifdef RATE_LOOP_TIMING_DEBUG
gyro_sample_time_us += AP_HAL::micros() - rate_now_us;
rate_now_us = AP_HAL::micros();
#endif
// we must use multiples of the actual sensor rate
const float sensor_dt = 1.0f * rate_decimation / ins.get_raw_gyro_rate_hz();
const uint32_t now_us = AP_HAL::micros();
const uint32_t dt_us = now_us - last_run_us;
const float dt = dt_us * 1.0e-6;
last_run_us = now_us;
// check if we are falling behind
if (ins.get_num_gyro_samples() > 2) {
running_slow++;
} else if (running_slow > 0) {
running_slow--;
}
if (AP::scheduler().get_extra_loop_us() == 0) {
rate_loop_count++;
}
// run the rate controller on all available samples
// it is important not to drop samples otherwise the filtering will be fubar
// there is no need to output to the motors more than once for every batch of samples
attitude_control->rate_controller_run_dt(gyro + ahrs.get_gyro_drift(), sensor_dt);
#ifdef RATE_LOOP_TIMING_DEBUG
rate_controller_time_us += AP_HAL::micros() - rate_now_us;
rate_now_us = AP_HAL::micros();
#endif
// immediately output the new motor values
if (run_decimated_callback(rates.main_loop_rate, main_loop_count)) {
main_loop_count = 0;
}
motors_output(main_loop_count == 0);
// process filter updates
if (run_decimated_callback(rates.filter_rate, filter_loop_count)) {
filter_loop_count = 0;
rate_controller_filter_update();
}
max_dt = MAX(dt, max_dt);
min_dt = MIN(dt, min_dt);
#if HAL_LOGGING_ENABLED
if (now_ms - last_rtdt_log_ms >= 100) { // 10 Hz
Log_Write_Rate_Thread_Dt(dt, sensor_dt, max_dt, min_dt);
max_dt = sensor_dt;
min_dt = sensor_dt;
last_rtdt_log_ms = now_ms;
}
#endif
#ifdef RATE_LOOP_TIMING_DEBUG
motor_output_us += AP_HAL::micros() - rate_now_us;
rate_now_us = AP_HAL::micros();
#endif
#if HAL_LOGGING_ENABLED
// fast logging output
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
if (run_decimated_callback(rates.fast_logging_rate, log_loop_count)) {
log_loop_count = 0;
rate_controller_log_update();
}
} else if (should_log(MASK_LOG_ATTITUDE_MED)) {
if (run_decimated_callback(rates.medium_logging_rate, log_loop_count)) {
log_loop_count = 0;
rate_controller_log_update();
}
}
#endif
#ifdef RATE_LOOP_TIMING_DEBUG
log_output_us += AP_HAL::micros() - rate_now_us;
rate_now_us = AP_HAL::micros();
#endif
now_ms = AP_HAL::millis();
// make sure we have the latest target rate
target_rate_decimation = constrain_int16(g2.att_decimation.get(), 1, DIV_ROUND_INT(ins.get_raw_gyro_rate_hz(), 400));
if (now_ms - last_notch_sample_ms >= 1000 || !was_using_rate_thread) {
// update the PID notch sample rate at 1Hz if we are
// enabled at runtime
last_notch_sample_ms = now_ms;
attitude_control->set_notch_sample_rate(1.0 / sensor_dt);
#ifdef RATE_LOOP_TIMING_DEBUG
hal.console->printf("Sample rate %.1f, main loop %u, fast rate %u, med rate %u\n", 1.0 / sensor_dt,
rates.main_loop_rate, rates.fast_logging_rate, rates.medium_logging_rate);
#endif
}
// interlock for printing fixed rate active
if (was_armed != motors->armed()) {
notify_fixed_rate_active = !was_armed;
was_armed = motors->armed();
}
// Once armed, switch to the fast rate if configured to do so
if ((rate_decimation != target_rate_decimation || notify_fixed_rate_active)
&& ((get_fast_rate_type() == FastRateType::FAST_RATE_FIXED_ARMED && motors->armed())
|| get_fast_rate_type() == FastRateType::FAST_RATE_FIXED)) {
rate_decimation = target_rate_decimation;
rate_controller_set_rates(rate_decimation, rates, false);
notify_fixed_rate_active = false;
}
// check that the CPU is not pegged, if it is drop the attitude rate
if (now_ms - last_rate_check_ms >= 100
&& (get_fast_rate_type() == FastRateType::FAST_RATE_DYNAMIC
|| (get_fast_rate_type() == FastRateType::FAST_RATE_FIXED_ARMED && !motors->armed())
|| target_rate_decimation > rate_decimation)) {
last_rate_check_ms = now_ms;
const uint32_t att_rate = ins.get_raw_gyro_rate_hz()/rate_decimation;
if (running_slow > 5 || AP::scheduler().get_extra_loop_us() > 0
#if HAL_LOGGING_ENABLED
|| AP::logger().in_log_download()
#endif
|| target_rate_decimation > rate_decimation) {
const uint8_t new_rate_decimation = MAX(rate_decimation + 1, target_rate_decimation);
const uint32_t new_attitude_rate = ins.get_raw_gyro_rate_hz() / new_rate_decimation;
if (new_attitude_rate > AP::scheduler().get_filtered_loop_rate_hz()) {
rate_decimation = new_rate_decimation;
rate_controller_set_rates(rate_decimation, rates, true);
prev_loop_count = rate_loop_count;
rate_loop_count = 0;
running_slow = 0;
}
} else if (rate_decimation > target_rate_decimation && rate_loop_count > att_rate/10 // ensure 100ms worth of good readings
&& (prev_loop_count > att_rate/10 // ensure there was 100ms worth of good readings at the higher rate
|| prev_loop_count == 0 // last rate was actually a lower rate so keep going quickly
|| now_ms - last_rate_increase_ms >= 10000)) { // every 10s retry
rate_decimation = rate_decimation - 1;
rate_controller_set_rates(rate_decimation, rates, false);
prev_loop_count = 0;
rate_loop_count = 0;
last_rate_increase_ms = now_ms;
}
}
#ifdef RATE_LOOP_TIMING_DEBUG
timing_count++;
ctrl_output_us += AP_HAL::micros() - rate_now_us;
rate_now_us = AP_HAL::micros();
if (rate_now_us - last_timing_msg_us > 1e6) {
hal.console->printf("Rate loop timing: gyro=%uus, rate=%uus, motors=%uus, log=%uus, ctrl=%uus\n",
unsigned(gyro_sample_time_us/timing_count), unsigned(rate_controller_time_us/timing_count),
unsigned(motor_output_us/timing_count), unsigned(log_output_us/timing_count), unsigned(ctrl_output_us/timing_count));
last_timing_msg_us = rate_now_us;
timing_count = 0;
gyro_sample_time_us = rate_controller_time_us = motor_output_us = log_output_us = ctrl_output_us = 0;
}
#endif
was_using_rate_thread = true;
}
}
/*
update rate controller filters. on an H7 this is about 30us
*/
void Copter::rate_controller_filter_update()
{
// update the frontend center frequencies of notch filters
for (auto &notch : ins.harmonic_notches) {
update_dynamic_notch(notch);
}
// this copies backend data to the frontend and updates the notches
ins.update_backend_filters();
}
/*
update rate controller rates and return the logging rate
*/
void Copter::rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high)
{
const uint32_t attitude_rate = ins.get_raw_gyro_rate_hz() / rate_decimation;
attitude_control->set_notch_sample_rate(attitude_rate);
hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), attitude_rate);
motors->set_dt(1.0f / attitude_rate);
gcs().send_text(warn_cpu_high ? MAV_SEVERITY_WARNING : MAV_SEVERITY_INFO,
"Rate CPU %s, rate set to %uHz",
warn_cpu_high ? "high" : "normal", (unsigned) attitude_rate);
#if HAL_LOGGING_ENABLED
if (attitude_rate > 1000) {
rates.fast_logging_rate = calc_gyro_decimation(rate_decimation, 1000); // 1Khz
} else {
rates.fast_logging_rate = calc_gyro_decimation(rate_decimation, AP::scheduler().get_filtered_loop_rate_hz());
}
rates.medium_logging_rate = calc_gyro_decimation(rate_decimation, 10); // 10Hz
#endif
rates.main_loop_rate = calc_gyro_decimation(rate_decimation, AP::scheduler().get_filtered_loop_rate_hz());
rates.filter_rate = calc_gyro_decimation(rate_decimation, ins.get_raw_gyro_rate_hz() / 2);
}
// enable the fast rate thread using the provided decimation rate and record the new output rates
void Copter::enable_fast_rate_loop(uint8_t rate_decimation, RateControllerRates& rates)
{
ins.enable_fast_rate_buffer();
rate_controller_set_rates(rate_decimation, rates, false);
hal.rcout->force_trigger_groups(true);
using_rate_thread = true;
}
// disable the fast rate thread and record the new output rates
void Copter::disable_fast_rate_loop(RateControllerRates& rates)
{
using_rate_thread = false;
uint8_t rate_decimation = calc_gyro_decimation(1, AP::scheduler().get_filtered_loop_rate_hz());
rate_controller_set_rates(rate_decimation, rates, false);
hal.rcout->force_trigger_groups(false);
ins.disable_fast_rate_buffer();
}
/*
log only those items that are updated at the rate loop rate
*/
void Copter::rate_controller_log_update()
{
#if HAL_LOGGING_ENABLED
if (!copter.flightmode->logs_attitude()) {
Log_Write_Rate();
Log_Write_PIDS(); // only logs if PIDS bitmask is set
}
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
if (should_log(MASK_LOG_FTN_FAST)) {
AP::ins().write_notch_log_messages();
}
#endif
#endif
}
// run notch update at either loop rate or 200Hz
void Copter::update_dynamic_notch_at_specified_rate_main()
{
if (using_rate_thread) {
return;
}
update_dynamic_notch_at_specified_rate();
}
#endif // AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED

View File

@ -347,7 +347,6 @@ void Copter::update_auto_armed()
*/
bool Copter::should_log(uint32_t mask)
{
ap.logging_started = logger.logging_started();
return logger.should_log(mask);
}
#endif

View File

@ -6,13 +6,13 @@
#include "ap_version.h"
#define THISFIRMWARE "ArduCopter V4.6.0-dev"
#define THISFIRMWARE "ArduCopter V4.7.0-dev"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV
#define FW_MAJOR 4
#define FW_MINOR 6
#define FW_MINOR 7
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

View File

@ -433,9 +433,15 @@ bool AP_Arming_Plane::mission_checks(bool report)
{
// base checks
bool ret = AP_Arming::mission_checks(report);
if (plane.mission.contains_item(MAV_CMD_DO_LAND_START) && plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {
ret = false;
check_failed(ARMING_CHECK_MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled");
if (plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {
if (plane.mission.contains_item(MAV_CMD_DO_LAND_START)) {
ret = false;
check_failed(ARMING_CHECK_MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled");
}
if (plane.mission.contains_item(MAV_CMD_DO_RETURN_PATH_START)) {
ret = false;
check_failed(ARMING_CHECK_MISSION, report, "DO_RETURN_PATH_START set and RTL_AUTOLAND disabled");
}
}
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.available()) {

View File

@ -139,6 +139,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if AC_PRECLAND_ENABLED
SCHED_TASK(precland_update, 400, 50, 160),
#endif
#if AP_QUICKTUNE_ENABLED
SCHED_TASK(update_quicktune, 40, 100, 163),
#endif
};
void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
@ -329,7 +332,7 @@ void Plane::one_second_loop()
set_control_channels();
#if HAL_WITH_IO_MCU
iomcu.setup_mixing(&rcmap, g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);
iomcu.setup_mixing(g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);
#endif
#if HAL_ADSB_ENABLED
@ -346,7 +349,7 @@ void Plane::one_second_loop()
// sync MAVLink system ID
mavlink_system.sysid = g.sysid_this_mav;
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
// update notify flags
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
@ -1025,4 +1028,16 @@ void Plane::precland_update(void)
}
#endif
#if AP_QUICKTUNE_ENABLED
/*
update AP_Quicktune object. We pass the supports_quicktune() method
in so that quicktune can detect if the user changes to a
non-quicktune capable mode while tuning and the gains can be reverted
*/
void Plane::update_quicktune(void)
{
quicktune.update(control_mode->supports_quicktune());
}
#endif
AP_HAL_MAIN_CALLBACKS(&plane);

View File

@ -630,10 +630,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
@ -710,7 +716,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
MSG_VIBRATION,
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
static const ap_message STREAM_ADSB_msgs[] = {
MSG_ADSB_VEHICLE,
@ -863,6 +870,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com
if (((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) ||
(plane.control_mode == &plane.mode_guided)) {
plane.set_mode(plane.mode_guided, ModeReason::GCS_COMMAND);
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
#endif
// add home alt if needed
if (requested_position.relative_alt) {
@ -973,14 +983,20 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl
float new_target_heading = radians(wrap_180(packet.param2));
// course over ground
if ( int(packet.param1) == HEADING_TYPE_COURSE_OVER_GROUND) { // compare as nearest int
switch(HEADING_TYPE(packet.param1)) {
case HEADING_TYPE_COURSE_OVER_GROUND:
// course over ground
plane.guided_state.target_heading_type = GUIDED_HEADING_COG;
plane.prev_WP_loc = plane.current_loc;
// normal vehicle heading
} else if (int(packet.param1) == HEADING_TYPE_HEADING) { // compare as nearest int
break;
case HEADING_TYPE_HEADING:
// normal vehicle heading
plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING;
} else {
break;
case HEADING_TYPE_DEFAULT:
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
return MAV_RESULT_ACCEPTED;
default:
// MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters).
return MAV_RESULT_DENIED;
}
@ -1056,11 +1072,27 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
case MAV_CMD_DO_GO_AROUND:
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
case MAV_CMD_DO_RETURN_PATH_START:
// attempt to rejoin after the next DO_RETURN_PATH_START command in the mission
if (plane.have_position && plane.mission.jump_to_closest_mission_leg(plane.current_loc)) {
plane.mission.set_force_resume(true);
if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
// mode change failed, revert force resume flag
plane.mission.set_force_resume(false);
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_LAND_START:
// attempt to switch to next DO_LAND_START command in the mission
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
return MAV_RESULT_ACCEPTED;
plane.mission.set_force_resume(true);
if (plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
// mode change failed, revert force resume flag
plane.mission.set_force_resume(false);
}
return MAV_RESULT_FAILED;
@ -1372,43 +1404,27 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess
mavlink_set_position_target_global_int_t pos_target;
mavlink_msg_set_position_target_global_int_decode(&msg, &pos_target);
Location::AltFrame frame;
if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)pos_target.coordinate_frame, frame)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
// Even though other parts of the command may be valid, reject the whole thing.
return;
}
// Unexpectedly, the mask is expecting "ones" for dimensions that should
// be IGNORNED rather than INCLUDED. See mavlink documentation of the
// SET_POSITION_TARGET_GLOBAL_INT message, type_mask field.
const uint16_t alt_mask = 0b1111111111111011; // (z mask at bit 3)
bool msg_valid = true;
AP_Mission::Mission_Command cmd = {0};
if (pos_target.type_mask & alt_mask)
{
cmd.content.location.alt = pos_target.alt * 100;
cmd.content.location.relative_alt = false;
cmd.content.location.terrain_alt = false;
switch (pos_target.coordinate_frame)
{
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
break; //default to MSL altitude
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
cmd.content.location.relative_alt = true;
break;
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
cmd.content.location.relative_alt = true;
cmd.content.location.terrain_alt = true;
break;
default:
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
msg_valid = false;
break;
}
if (msg_valid) {
handle_change_alt_request(cmd);
}
} // end if alt_mask
const int32_t alt_cm = pos_target.alt * 100;
cmd.content.location.set_alt_cm(alt_cm, frame);
handle_change_alt_request(cmd);
}
}
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
@ -1546,3 +1562,99 @@ MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const
return MAV_LANDED_STATE_ON_GROUND;
}
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Plane::send_available_mode(uint8_t index) const
{
// Fixed wing modes
const Mode* fw_modes[] {
&plane.mode_manual,
&plane.mode_circle,
&plane.mode_stabilize,
&plane.mode_training,
&plane.mode_acro,
&plane.mode_fbwa,
&plane.mode_fbwb,
&plane.mode_cruise,
&plane.mode_autotune,
&plane.mode_auto,
&plane.mode_rtl,
&plane.mode_loiter,
#if HAL_ADSB_ENABLED
&plane.mode_avoidADSB,
#endif
&plane.mode_guided,
&plane.mode_initializing,
&plane.mode_takeoff,
#if HAL_SOARING_ENABLED
&plane.mode_thermal,
#endif
};
const uint8_t fw_mode_count = ARRAY_SIZE(fw_modes);
// Fixedwing modes are always present
uint8_t mode_count = fw_mode_count;
#if HAL_QUADPLANE_ENABLED
// Quadplane modes
const Mode* q_modes[] {
&plane.mode_qstabilize,
&plane.mode_qhover,
&plane.mode_qloiter,
&plane.mode_qland,
&plane.mode_qrtl,
&plane.mode_qacro,
&plane.mode_loiter_qland,
#if QAUTOTUNE_ENABLED
&plane.mode_qautotune,
#endif
};
// Quadplane modes must be enabled
if (plane.quadplane.available()) {
mode_count += ARRAY_SIZE(q_modes);
}
#endif // HAL_QUADPLANE_ENABLED
// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}
// Ask the mode for its name and number
const char* name;
uint8_t mode_number;
if (index_zero < fw_mode_count) {
// A fixedwing mode
name = fw_modes[index_zero]->name();
mode_number = (uint8_t)fw_modes[index_zero]->mode_number();
} else {
#if HAL_QUADPLANE_ENABLED
// A Quadplane mode
const uint8_t q_index = index_zero - fw_mode_count;
name = q_modes[q_index]->name();
mode_number = (uint8_t)q_modes[q_index]->mode_number();
#else
// Should not endup here
return mode_count;
#endif
}
mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);
return mode_count;
}

View File

@ -50,6 +50,10 @@ protected:
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;
private:
void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved);
@ -83,8 +87,6 @@ private:
MAV_MODE base_mode() const override;
MAV_STATE vehicle_system_status() const override;
uint8_t radio_in_rssi() const;
float vfr_hud_airspeed() const override;
int16_t vfr_hud_throttle() const override;
float vfr_hud_climbrate() const override;

View File

@ -60,7 +60,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
// @Param: KFF_RDDRMIX
@ -158,6 +158,15 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Standard
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),
// @Param: TKOFF_THR_IDLE
// @DisplayName: Takeoff idle throttle
// @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes.
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Standard
ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0),
// @Param: TKOFF_OPTIONS
// @DisplayName: Takeoff options
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.
@ -737,7 +746,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: RTL_AUTOLAND
// @DisplayName: RTL auto land
// @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location. If this is set to 0 and there is a DO_LAND_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around without it changing RTL behaviour. For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation).
// @Values: 0:Disable,1:Fly HOME then land,2:Go directly to landing sequence, 3:OnlyForGoAround
// @Values: 0:Disable,1:Fly HOME then land via DO_LAND_START mission item, 2:Go directly to landing sequence via DO_LAND_START mission item, 3:OnlyForGoAround, 4:Go directly to landing sequence via DO_RETURN_PATH_START mission item
// @User: Standard
GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)),
@ -1029,6 +1038,12 @@ const AP_Param::Info Plane::var_info[] = {
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
PARAM_VEHICLE_INFO,
#if AP_QUICKTUNE_ENABLED
// @Group: QWIK_
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
GOBJECT(quicktune, "QWIK_", AP_Quicktune),
#endif
AP_VAREND
};

View File

@ -359,8 +359,10 @@ public:
k_param_autotune_options,
k_param_takeoff_throttle_min,
k_param_takeoff_options,
k_param_takeoff_throttle_idle,
k_param_pullup = 270,
k_param_quicktune,
};
AP_Int16 format_version;
@ -483,6 +485,9 @@ public:
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
// just to make compilation easier when all things are compiled out...
uint8_t unused_integer;
// button reporting library
#if HAL_BUTTON_ENABLED
AP_Button *button_ptr;
@ -579,9 +584,6 @@ public:
AP_Int8 axis_bitmask; // axes to be autotuned
// just to make compilation easier when all things are compiled out...
uint8_t unused_integer;
#if AP_RANGEFINDER_ENABLED
// orientation of rangefinder to use for landing
AP_Int8 rangefinder_land_orient;

View File

@ -330,6 +330,10 @@ private:
ModeThermal mode_thermal;
#endif
#if AP_QUICKTUNE_ENABLED
AP_Quicktune quicktune;
#endif
// This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO
Mode *control_mode = &mode_initializing;
@ -449,7 +453,7 @@ private:
float throttle_lim_max;
float throttle_lim_min;
uint32_t throttle_max_timer_ms;
// Good candidate for keeping the initial time for TKOFF_THR_MAX_T.
uint32_t level_off_start_time_ms;
} takeoff_state;
// ground steering controller state
@ -875,6 +879,10 @@ private:
static const TerrainLookupTable Terrain_lookup[];
#endif
#if AP_QUICKTUNE_ENABLED
void update_quicktune(void);
#endif
// Attitude.cpp
void adjust_nav_pitch_throttle(void);
void update_load_factor(void);
@ -1139,6 +1147,7 @@ private:
int16_t get_takeoff_pitch_min_cd(void);
void landing_gear_update(void);
bool check_takeoff_timeout(void);
bool check_takeoff_timeout_level_off(void);
// avoidance_adsb.cpp
void avoidance_adsb_update(void);
@ -1159,7 +1168,7 @@ private:
void servos_twin_engine_mix();
void force_flare();
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func);
void throttle_slew_limit();
bool suppress_throttle(void);
void update_throttle_hover();
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,

View File

@ -1,6 +1,7 @@
#include "Plane.h"
#include "RC_Channel.h"
#include "qautotune.h"
// defining these two macros and including the RC_Channels_VarInfo
// header defines the parameter information common to all vehicle
@ -176,6 +177,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
#endif
#if QAUTOTUNE_ENABLED
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
#endif
#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
#endif
break;
@ -458,6 +462,12 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break;
#endif
#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
plane.quicktune.update_switch_pos(ch_flag);
break;
#endif
default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
}

View File

@ -30,7 +30,6 @@ private:
void do_aux_function_soaring_3pos(AuxSwitchPos ch_flag);
void do_aux_function_flare(AuxSwitchPos ch_flag);
};
class RC_Channels_Plane : public RC_Channels

View File

@ -1,5 +1,476 @@
ArduPilot Plane Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta2 11 Dec 2024
Changes from 4.6.0-beta1
1) Board specfic changes
- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed
2) Copter specific enhancements and bug fixes
- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option
3) Plane related enhancements and bug fixes
- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes
4) Bug Fixes and minor enhancements
- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024
Changes from 4.5.7
1) Board specific changes
- AnyLeaf H7 supports compass and onboard logging
- Blitz743Pro supports CAN
- BlueRobotics Navigator supports BMP390 baro
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
- CB Unmanned Stamp H743 support
- ClearSky CSKY405 support
- CUAV-7-Nano default batt monitor fixed
- CubeRed bootloader fixes including disabling 2nd core by default
- CubeRed supports PPP networking between primary and secondary MCU
- CubeRedPrimary supports external compasses
- ESP32 main loop rate improvements
- ESP32 RC input fixes and wifi connection reliability improved
- ESP32 safety switch and GPIO pin support
- FlyingMoon no longer support MAX7456
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
- Flywoo H743 Pro support
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
- FlywooF745 supports DPS310 baro
- FPV boards lose SMBus battery support (to save flash)
- GEPRC F745BTHD support
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
- Holybro Kakute F4 Wing support
- iFlight 2RAW H743 supports onboard logging
- JFB110 supports measuring servo rail voltage
- JFB110 supports safety switch LED
- JHEM-JHEF405 bootloader supports firmware updates via serial
- JHEMCU GF30H743 HD support
- JHEMCU-GF16-F405 autopilot support
- JHEMCU-GSF405A becomes FPV board (to save flash)
- KakuteF7 only supports BMP280 baro (to save flash)
- KakuteH7Mini supports ICM42688 IMU
- Linux auto detection of GPS baud rate fixed
- Linux board scheduler jitter reduced
- Linux board shutdown fixes
- MakeFlyEasy PixPilot-V6Pro support
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
- MatekH7A3 support Bi-directional DShot
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
- MicoAir743 internal compass orientation fixed
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
- mRo Control Zero Classic supports servo rail analog input
- mRo KitCAN revC fixed
- Mugin MUPilot support
- OmnibusF7v2 loses quadplane support (to save flash)
- Pixhack-v3 board added (same as fmuv3)
- Pixhawk6C bootloader supports flashing firmware from SD card
- RadiolinkPIX6 imu orientation fixed
- RadiolinkPIX6 supports SPA06 baro
- ReaperF745 V4 FC supports MPU6000 IMU
- RPI5 support
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
- Solo serial ports default to MAVLink1
- SpeedyBeeF405Wing gets Bi-directional DShot
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
- Spektreworks boom board support
- TrueNavPro-G4 SPI does not share DMA
- X-MAV AP-H743v2 support
2) AHRS/EKF enhancements and fixes
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
- AHRS_OPTION to disable innovation check for airspeed sensor
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
- EK2 supports disabling external nav (see EK2_OPTIONS)
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
- EK3 uses filtered velocity corrections for IMU position
- EKF2, EKF3, ExternalAHRS all use common origin
- EKF3 accepts set origin even when using GPS
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
- EKF3 copes better with GPS jamming
- EKF3 logs mag fusion selection to XKFS
- EKF3 wind estimation when using GPS-for-yaw fixed
- External AHRS improvements including handling variances, pre-arm origin check
- Inertial Labs External AHRS fixes
- VectorNav driver fix for handling of error from sensor
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
- VectorNav support for sensors outside VN-100 and VN-300
3) Driver enhancements and bug fixes
- ADSB fix to display last character in status text sent to GCS
- Ainstein LR-D1 radar support
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
- AIRSPEED message sent to GCS
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
- ARSPD_OPTIONS to report calibration offset to GCS
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
- Baro provides improved atmospheric model for high altitude flight
- BARO_ALT_OFFSET slew slowed to keep EKF happy
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
- BATTx_OPTION to not send battery voltage, current, etc to GCS
- Benewake RDS02U radar support
- Bi-directional DShot on IOMCU supports reversible mask
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
- BMM350 compass support
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
- CRSF baro and vertical speeed fixed
- CRSF RX bind command support
- DroneCAN battery monitor check to avoid memory corruption when type changed
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
- DroneCAN EFI health check fix
- DroneCAN ESC battery monitors calculate consumed mah
- DroneCAN ESCs forced to zero when disarmed
- DroneCAN RPM message support
- DroneCAN timeout fix for auxiliary frames
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
- FuelLevel battery monitor fix to report capacity
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
- Hirth EFI logging includes modified throttle
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
- Hott and LTM telemetry deprecated (still available through custom build server)
- i-BUS telemetry support
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
- ICE_START_CHAN replaced with RC aux function (Plane only)
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
- IE 2400 generator error message severity to GCS improved
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
- MCP9600 temperature sensor I2C address fixed
- MLX90614 temperature sensor support
- MSP GPS ground course scaling fixed
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
- Networking supports reconnection to TCP server or client
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
- Relay inverted output support (see RELAYx_INVERTED parameter)
- ROMFS efficiency improvements
- RS-485 driver enable RTS flow control
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
- Septentrio GPS sat count correctly drops to zero when 255 received
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
- Single LED for user notification supported
- SPA06 baro supported
- Sum battery monitor optionally reports minimum voltage instead of average
- Sum battery monitor reports average temp
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
- UBlox GPS time ignored until at least 2D fix
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
- Volz logs desired and actual position, voltage, current, motor and PCB temp
- Volz server feedback and logging fixed
- Volz servo output in its own thread resulting in smoother movements
- W25N02KV flash support
4) Networking enhancements and fixes
- Allow multiple UDP clients to connect/disconnect/reconnect
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
5) Camera and gimbal enhancements
- Alexmos precision improved slightly
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
- Dual serial camera gimbal mounts fixed
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
- Retract Mount2 aux function added (see RCx_OPTION = 113)
- Servo gimbal reported angles respect roll, pitch and yaw limits
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
- Siyi picture and video download scripts
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
- Siyi ZT6 hardware id and set-lens fixed
- Topotek gimbal support
- Trigger distance ignores GPS status and only uses EKF reported location
6) Harmonic notch enhancements
- Harmonic notch is active in forward flight on quadplanes
- Harmonic notch filter freq clamping and disabling reworked
- Harmonic notch handles negative ESC RPMs
- Harmonic notch supports per-motor throttle-based harmonic notch
7) Copter specific enhancements and bug fixes
- Attitude control fix to dt update order (reduces rate controller noise)
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
- Auto mode small target position jump when takeoff completes removed
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
- AutoTune fix to prevent spool up after landing
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
- Config error avoided if auto mode is paused very soon after poweron
- FLIGHT_OPTIONS bit added to require position estimate before arming
- Follow mode slowdown calcs fixed when target is moving
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
- Landing detector logging added to ease support (see LDET message)
- Loiter unlimited command accepts NaNs (QGC sends these)
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
- Payload place bug fix when aborted because gripper is already released
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
- RTL_ALT minimum reduced to 30cm
- SystemID position controller support (Copter and Heli)
- TriCopter motor test and slew-up fixed
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
8) TradHeli specific enhancements
- Autorotation yaw behaviour fix
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
- Blade pitch angle logging added (see SWSH log message)
- Constrain cyclic roll for intermeshing
- ICE / turbine cool down fix
- Inverted flight extended to non manual throttle modes
- Inverted flight transitions smoothed and restricted to only Stabilize mode
- SWSH logging fix for reversed collectives
9) Plane specific enhancements and bug fixes
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
- Allow for different orientations of landing rangefinder
- Assistance requirements evaluted on mode change
- FBWB/CRUISE climb/sink rate limited by TECS limits
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
- Glider pullup support (available only through custom build server)
- Loiter breakout improved to better handle destinations inside loiter circle
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
- Quadplane assistance check enhancements
- Quadplane Deca frame support
- Quadplane gets smoother takeoff by input shaping target accel and velocity
- Servo wiggles in altitude wait staged to be one after another
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
- Takeoff fixes for fence autoenable
- Takeoff improvements including less overshoot of TKOFF_ALT
- TECS reset along with other controllers (important if plane dropped from balloon)
- Tilt quadplane ramp of motors on back transition fixed
- Tiltrotor tilt angles logged
- TKOFF_THR_MIN applied to SLT transitions
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
10) Rover specific enhancements and bug fixes
- Auto mode reversed state maintained if momentarily switched to Hold mode
- Circle mode tracks better and avoids getting stuck at circle edge
- Flight time stats fixed
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
- Omni3Mecanum frame support
- Stopping point uses max deceleration (was incorrectly using acceleration)
- Wheel rate controller slew rate fix
11) Antenna Tracker specific enhancements and bug fixes
- Never track lat,lon of 0,0
12) Scripting enhancements
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
- battery_internal_resistance_check.lua monitors battery resistance
- CAN:get_device returns nil for unconfigured CAN device
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
- Copter:get_target_location, update_target_location support
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
- Display text on OLED display supported
- Docs improved for many bindings
- EFI get_last_update_ms binding
- EFI_SkyPower.lua driver accepts 2nd supply voltage
- ESC_slew_rate.lua example script supports testing ESCs
- Filesystem CRC32 check to allow scripts to check module versions
- forced arming support
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
- Halo6000 EFI driver can log all CAN packets for easier debugging
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
- I2C:transfer support
- IMU gyros_consistent and accels_consistent bindings added
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
- INS bindings for is calibrating, gyro and accel sensor values
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
- Logging of booleans supported
- Lua language checks improved (finds more errors)
- MAVLink commands can be called from scripting
- MCU voltage binding (see analog:mcu_voltage)
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
- "open directory failed" false warning when scripts in ROMFS fixed
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
- Pass by reference values are always initialized
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
- plane_aerobatics.lua minor enhancements
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
- "require" function failures in rare circumstances fixed
- "require" function works for modules in ROMFS (e.g. not on SD card)
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
- SD card formatting supported
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
- Temperature sensor bindings added
- uint64 support
- Various performance and memory usage optimizations
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
13) GCS / mavlink related changes and fixes
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
- Deny attempts to upload two missions simultaneously
- Fence and Rally points may be uploaded using FTP
- GPS_INPUT and HIL_GPS handles multiple GPSs
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
- MAV_CMD_SET_HAGL support (Plane only)
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
- Message interval supports TERRAIN_REPORT msg
- Mission upload may be cancelled using MISSION_CLEAR_ALL
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
- RC_CHANNELS_RAW deprecated
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
14) Logging enhancements and fixes
- AC_PID resets and I-term sets logged
- ANG provides attitude at high rate (equivalent to ATT)
- ATT logs angles as floats (better resolution than ints)
- CAND message gets driver index
- DCM log message includes roll/pitch and yaw error
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
- FMT messages written as required instead of all at beginning
- Logging restarted after download completes when LOG_DISARMED = 1
- MISE msg logs active mission command (CMD logged when commands are uploaded)
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
- RPM sensor logging gets instance field, quality and health fields
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
- UART data rates logged at 1hz (see UART message)
15) ROS2 / DDS support
- Airspeed published
- Battery topic reports all available batteries
- Compile-time configurable rates for each publisher
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
- GPS global origin published at 1 Hz
- High frequency raw imu data transmission
- Joystick support
- Support sending waypoints to Copter and Rover
- Remove the XML refs file in favor of binary entity creation
16) Safety related enhancements and fixes
- Accel/Gyro inconsistent message fixed for using with only single IMU
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
- Far from EKF origin pre-arm check removed (Copter only)
- Fence breach warning message slightly improved
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
- LEDs flash green lights based on EKF location not GPS
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
- Pre-arm check if OpenDroneID is compiled in but disabled
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
- Pre-arm checks alert user more quickly on failure
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
- Warning of duplicate SERIALx_PROTOCOL = RCIN
17) Other bug fixes and minor enhancements
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
- Bootloader rejects allocation of broadcast node ID
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
- Dijkstras fix to correct use of uninitialised variable
- DShot rates are not limited by NeoPixel rates
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
- Filesystem does not show entries for empty @ files
- Filesystem efficiency improvements when reading files
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
- Internal error thrown if we lose parameters due to saving queue being too small
- MAVLink via DroneCAN baud rate fix
- SPI pins may also be used as GPIOs
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
18) Developer focused fixes and enhancements
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
- Cygwin build fix for non-SITL builds
- Cygwin build fixed with malloc wrap
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
- EKF3 code generator documentation and cleanup
- GPS jamming simulator added
- MacOS compiler warnings reduced
- SFML joystick support
- SITL support for OpenBSD
- Text warning if older Fence or Rally point protocols are used
------------------------------------------------------------------
Release 4.5.7 08 Oct 2024
Changes from 4.5.7-beta1

View File

@ -44,7 +44,7 @@ void Plane::check_home_alt_change(void)
next_WP_loc.alt += alt_change_cm;
}
// reset TECS to force the field elevation estimate to reset
TECS_controller.reset();
TECS_controller.offset_altitude(alt_change_cm * 0.01f);
}
auto_state.last_home_alt_cm = home_alt_cm;
}

View File

@ -138,6 +138,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
}
break;
case MAV_CMD_DO_RETURN_PATH_START:
case MAV_CMD_DO_LAND_START:
break;
@ -304,6 +305,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_INVERTED_FLIGHT:
case MAV_CMD_DO_RETURN_PATH_START:
case MAV_CMD_DO_LAND_START:
case MAV_CMD_DO_FENCE_ENABLE:
case MAV_CMD_DO_AUTOTUNE_ENABLE:
@ -587,7 +589,10 @@ bool Plane::verify_takeoff()
// see if we have reached takeoff altitude
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
if (relative_alt_cm > auto_state.takeoff_altitude_rel_cm) {
if (
relative_alt_cm > auto_state.takeoff_altitude_rel_cm || // altitude reached
plane.check_takeoff_timeout_level_off() // pitch level-off maneuver has timed out
) {
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",
(double)(relative_alt_cm*0.01f));
steer_state.hold_course_cd = -1;

View File

@ -61,19 +61,7 @@ enum class RtlAutoland {
RTL_THEN_DO_LAND_START = 1,
RTL_IMMEDIATE_DO_LAND_START = 2,
NO_RTL_GO_AROUND = 3,
};
enum ChannelMixing {
MIXING_DISABLED = 0,
MIXING_UPUP = 1,
MIXING_UPDN = 2,
MIXING_DNUP = 3,
MIXING_DNDN = 4,
MIXING_UPUP_SWP = 5,
MIXING_UPDN_SWP = 6,
MIXING_DNUP_SWP = 7,
MIXING_DNDN_SWP = 8,
DO_RETURN_PATH_START = 4,
};
// PID broadcast bitmask

View File

@ -1,14 +1,15 @@
#include "Plane.h"
Mode::Mode() :
ahrs(plane.ahrs)
unused_integer{17},
#if HAL_QUADPLANE_ENABLED
, quadplane(plane.quadplane),
pos_control(plane.quadplane.pos_control),
attitude_control(plane.quadplane.attitude_control),
loiter_nav(plane.quadplane.loiter_nav),
poscontrol(plane.quadplane.poscontrol)
quadplane(plane.quadplane),
poscontrol(plane.quadplane.poscontrol),
#endif
ahrs(plane.ahrs)
{
}

View File

@ -11,6 +11,12 @@
#include <AP_Mission/AP_Mission.h>
#include "pullup.h"
#ifndef AP_QUICKTUNE_ENABLED
#define AP_QUICKTUNE_ENABLED HAL_QUADPLANE_ENABLED
#endif
#include <AP_Quicktune/AP_Quicktune.h>
class AC_PosControl;
class AC_AttitudeControl_Multi;
class AC_Loiter;
@ -142,6 +148,11 @@ public:
// true if voltage correction should be applied to throttle
virtual bool use_battery_compensation() const;
#if AP_QUICKTUNE_ENABLED
// does this mode support VTOL quicktune?
virtual bool supports_quicktune() const { return false; }
#endif
protected:
// subclasses override this to perform checks before entering the mode
@ -159,6 +170,9 @@ protected:
// Output pilot throttle, this is used in stabilized modes without auto throttle control
void output_pilot_throttle();
// makes the initialiser list in the constructor manageable
uint8_t unused_integer;
#if HAL_QUADPLANE_ENABLED
// References for convenience, used by QModes
AC_PosControl*& pos_control;
@ -322,6 +336,9 @@ protected:
bool _enter() override;
bool _pre_arm_checks(size_t buflen, char *buffer) const override { return true; }
#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif
private:
float active_radius_m;
@ -659,6 +676,9 @@ public:
protected:
bool _enter() override;
#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif
};
class ModeQLoiter : public Mode
@ -685,6 +705,10 @@ protected:
bool _enter() override;
uint32_t last_target_loc_set_ms;
#if AP_QUICKTUNE_ENABLED
bool supports_quicktune() const override { return true; }
#endif
};
class ModeQLand : public Mode

View File

@ -43,12 +43,12 @@ bool ModeLoiterAltQLand::handle_guided_request(Location target_loc)
// setup altitude
#if AP_TERRAIN_AVAILABLE
if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) {
target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN);
target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_TERRAIN);
} else {
target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME);
target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME);
}
#else
target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME);
target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME);
#endif
plane.set_guided_WP(target_loc);

View File

@ -9,7 +9,6 @@ bool ModeQLand::_enter()
quadplane.throttle_wait = false;
quadplane.setup_target_position();
poscontrol.set_state(QuadPlane::QPOS_LAND_DESCEND);
poscontrol.pilot_correction_done = false;
quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
quadplane.landing_detect.lower_limit_start_ms = 0;
quadplane.landing_detect.land_start_ms = 0;

View File

@ -106,8 +106,7 @@ void ModeRTL::navigate()
if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) ||
(plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START &&
plane.reached_loiter_target() &&
labs(plane.calc_altitude_error_cm()) < 1000))
{
labs(plane.calc_altitude_error_cm()) < 1000)) {
// we've reached the RTL point, see if we have a landing sequence
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
// switch from RTL -> AUTO
@ -116,12 +115,26 @@ void ModeRTL::navigate()
// return here so we don't change the radius and don't run the rtl update_loiter()
return;
}
// mode change failed, revert force resume flag
plane.mission.set_force_resume(false);
}
// prevent running the expensive jump_to_landing_sequence
// on every loop
plane.auto_state.checked_for_autoland = true;
} else if (plane.g.rtl_autoland == RtlAutoland::DO_RETURN_PATH_START) {
if (plane.have_position && plane.mission.jump_to_closest_mission_leg(plane.current_loc)) {
plane.mission.set_force_resume(true);
if (plane.set_mode(plane.mode_auto, ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND)) {
// return here so we don't change the radius and don't run the rtl update_loiter()
return;
}
// mode change failed, revert force resume flag
plane.mission.set_force_resume(false);
}
plane.auto_state.checked_for_autoland = true;
}
}
}

View File

@ -83,9 +83,12 @@ void ModeTakeoff::update()
if (!takeoff_mode_setup) {
plane.auto_state.takeoff_altitude_rel_cm = alt * 100;
const uint16_t altitude = plane.relative_ground_altitude(false,true);
const float direction = degrees(ahrs.get_yaw());
const Vector2f &groundspeed2d = ahrs.groundspeed_vector();
const float direction = wrap_360(degrees(groundspeed2d.angle()));
const float groundspeed = groundspeed2d.length();
// see if we will skip takeoff as already flying
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && groundspeed > 3) {
if (altitude >= alt) {
gcs().send_text(MAV_SEVERITY_INFO, "Above TKOFF alt - loitering");
plane.next_WP_loc = plane.current_loc;
@ -115,10 +118,19 @@ void ModeTakeoff::update()
plane.set_flight_stage(AP_FixedWing::FlightStage::TAKEOFF);
if (!plane.throttle_suppressed) {
/*
don't lock in the takeoff loiter location until we reach
a ground speed of AIRSPEED_MIN*0.3 to cope with aircraft
with no compass or poor compass. If flying in a very
strong headwind then the is_flying() check above will
eventually trigger
*/
if (!plane.throttle_suppressed &&
groundspeed > plane.aparm.airspeed_min*0.3) {
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff to %.0fm for %.1fm heading %.1f deg",
alt, dist, direction);
plane.takeoff_state.start_time_ms = millis();
plane.takeoff_state.level_off_start_time_ms = 0;
plane.takeoff_state.throttle_max_timer_ms = millis();
takeoff_mode_setup = true;
plane.steer_state.hold_course_cd = wrap_360_cd(direction*100); // Necessary to allow Plane::takeoff_calc_roll() to function.
@ -157,6 +169,12 @@ void ModeTakeoff::update()
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
}
// If we have timed-out on the attempt to close the final few meters
// during pitch level-off, continue to NORMAL flight stage.
if (plane.check_takeoff_timeout_level_off()) {
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
}
if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) {
//below TKOFF_ALT
plane.takeoff_calc_roll();

View File

@ -8,7 +8,7 @@
#include "quadplane.h"
#ifndef QAUTOTUNE_ENABLED
#define QAUTOTUNE_ENABLED HAL_QUADPLANE_ENABLED
#define QAUTOTUNE_ENABLED (HAL_QUADPLANE_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif
#if QAUTOTUNE_ENABLED

View File

@ -2905,7 +2905,8 @@ QuadPlane::ActiveFwdThr QuadPlane::get_vfwd_method(void) const
/*
map from pitch tilt to fwd throttle when enabled
*/
void QuadPlane::assign_tilt_to_fwd_thr(void) {
void QuadPlane::assign_tilt_to_fwd_thr(void)
{
const auto fwd_thr_active = get_vfwd_method();
if (fwd_thr_active != ActiveFwdThr::NEW) {
@ -4201,7 +4202,7 @@ uint16_t QuadPlane::get_pilot_velocity_z_max_dn() const
{
if (is_zero(pilot_speed_z_max_dn)) {
return abs(pilot_speed_z_max_up*100);
}
}
return abs(pilot_speed_z_max_dn*100);
}
@ -4499,8 +4500,9 @@ void SLT_Transition::set_last_fw_pitch()
last_fw_nav_pitch_cd = plane.nav_pitch_cd;
}
void SLT_Transition::force_transition_complete() {
transition_state = TRANSITION_DONE;
void SLT_Transition::force_transition_complete()
{
transition_state = TRANSITION_DONE;
in_forced_transition = false;
transition_start_ms = 0;
transition_low_airspeed_ms = 0;
@ -4594,6 +4596,11 @@ void QuadPlane::mode_enter(void)
poscontrol.last_velocity_match_ms = 0;
poscontrol.set_state(QuadPlane::QPOS_NONE);
// Clear any pilot corrections
poscontrol.pilot_correction_done = false;
poscontrol.pilot_correction_active = false;
poscontrol.target_vel_cms.zero();
// clear guided takeoff wait on any mode change, but remember the
// state for special behaviour
guided_wait_takeoff_on_mode_enter = guided_wait_takeoff;

View File

@ -107,7 +107,7 @@ void Plane::init_rc_out_main()
*/
void Plane::init_rc_out_aux()
{
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
servos_output();

View File

@ -22,7 +22,7 @@
/*****************************************
* Throttle slew limit
*****************************************/
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
void Plane::throttle_slew_limit()
{
#if HAL_QUADPLANE_ENABLED
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
@ -32,7 +32,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
if (!do_throttle_slew) {
// only do throttle slew limiting in modes where throttle control is automatic
SRV_Channels::set_slew_rate(func, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, 0.0, 100, G_Dt);
return;
}
@ -55,7 +57,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
slewrate = g.takeoff_throttle_slewrate;
}
#endif
SRV_Channels::set_slew_rate(func, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, slewrate, 100, G_Dt);
}
/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
@ -619,6 +623,11 @@ void Plane::set_throttle(void)
// throttle is suppressed (above) to zero in final flare in auto mode, but we allow instead thr_min if user prefers, eg turbines:
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.throttle_min.get());
} else if ((flight_stage == AP_FixedWing::FlightStage::TAKEOFF)
&& (aparm.takeoff_throttle_idle.get() > 0)
) {
// we want to spin at idle throttle before the takeoff conditions are met
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.takeoff_throttle_idle.get());
} else {
// default
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
@ -788,8 +797,6 @@ void Plane::servos_twin_engine_mix(void)
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right);
throttle_slew_limit(SRV_Channel::k_throttleLeft);
throttle_slew_limit(SRV_Channel::k_throttleRight);
}
}
@ -853,8 +860,8 @@ void Plane::set_servos(void)
// start with output corked. the cork is released when we run
// servos_output(), which is run from all code paths in this
// function
SRV_Channels::cork();
AP::srv().cork();
// this is to allow the failsafe module to deliberately crash
// the plane. Only used in extreme circumstances to meet the
// OBC rules
@ -908,7 +915,7 @@ void Plane::set_servos(void)
airbrake_update();
// slew rate limit throttle
throttle_slew_limit(SRV_Channel::k_throttle);
throttle_slew_limit();
int8_t min_throttle = 0;
#if AP_ICENGINE_ENABLED
@ -1012,7 +1019,8 @@ void Plane::indicate_waiting_for_rud_neutral_to_takeoff(void)
*/
void Plane::servos_output(void)
{
SRV_Channels::cork();
auto &srv = AP::srv();
srv.cork();
// support twin-engine aircraft
servos_twin_engine_mix();
@ -1050,7 +1058,7 @@ void Plane::servos_output(void)
SRV_Channels::output_ch_all();
SRV_Channels::push();
srv.push();
if (g2.servo_channels.auto_trim_enabled()) {
servos_auto_trim();

View File

@ -289,9 +289,6 @@ void Tailsitter::output(void)
return;
}
float tilt_left = 0.0f;
float tilt_right = 0.0f;
// throttle 0 to 1
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01;
@ -341,6 +338,10 @@ void Tailsitter::output(void)
// set AP_MotorsMatrix throttles for forward flight
motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt);
// No tilt output unless forward gain is set
float tilt_left = 0.0;
float tilt_right = 0.0;
// in forward flight: set motor tilt servos and throttles using FW controller
if (vectored_forward_gain > 0) {
// remove scaling from surface speed scaling and apply throttle scaling
@ -398,8 +399,11 @@ void Tailsitter::output(void)
}
// output tilt motors
tilt_left = 0.0f;
tilt_right = 0.0f;
// No output unless hover gain is set
float tilt_left = 0.0;
float tilt_right = 0.0;
if (vectored_hover_gain > 0) {
const float hover_throttle = motors->get_throttle_hover();
const float output_throttle = motors->get_throttle();
@ -438,8 +442,10 @@ void Tailsitter::output(void)
tailsitter_motors->set_min_throttle(0.0);
}
tilt_left = 0.0f;
tilt_right = 0.0f;
// No tilt output unless hover gain is set
float tilt_left = 0.0;
float tilt_right = 0.0;
if (vectored_hover_gain > 0) {
// thrust vectoring VTOL modes
tilt_left = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft);

View File

@ -121,6 +121,7 @@ bool Plane::auto_takeoff_check(void)
takeoff_state.launchTimerStarted = false;
takeoff_state.last_tkoff_arm_time = 0;
takeoff_state.start_time_ms = now;
takeoff_state.level_off_start_time_ms = 0;
takeoff_state.throttle_max_timer_ms = now;
steer_state.locked_course_err = 0; // use current heading without any error offset
return true;
@ -316,6 +317,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void)
// make a note of that altitude to use it as a start height for scaling
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff level-off starting at %dm", int(remaining_height_to_target_cm/100));
auto_state.height_below_takeoff_to_level_off_cm = remaining_height_to_target_cm;
takeoff_state.level_off_start_time_ms = AP_HAL::millis();
}
}
}
@ -376,9 +378,8 @@ void Plane::landing_gear_update(void)
#endif
/*
check takeoff_timeout; checks time after the takeoff start time; returns true if timeout has occurred and disarms on timeout
check takeoff_timeout; checks time after the takeoff start time; returns true if timeout has occurred
*/
bool Plane::check_takeoff_timeout(void)
{
if (takeoff_state.start_time_ms != 0 && g2.takeoff_timeout > 0) {
@ -400,3 +401,17 @@ bool Plane::check_takeoff_timeout(void)
return false;
}
/*
check if the pitch level-off time has expired; returns true if timeout has occurred
*/
bool Plane::check_takeoff_timeout_level_off(void)
{
if (takeoff_state.level_off_start_time_ms > 0) {
// A takeoff is in progress.
uint32_t now = AP_HAL::millis();
if ((now - takeoff_state.level_off_start_time_ms) > (uint32_t)(1000U * g.takeoff_pitch_limit_reduction_sec)) {
return true;
}
}
return false;
}

View File

@ -6,13 +6,13 @@
#include "ap_version.h"
#define THISFIRMWARE "ArduPlane V4.6.0-dev"
#define THISFIRMWARE "ArduPlane V4.7.0-dev"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV
#define FW_MAJOR 4
#define FW_MINOR 6
#define FW_MINOR 7
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

View File

@ -27,6 +27,7 @@ def build(bld):
'AP_Follow',
'AC_PrecLand',
'AP_IRLock',
'AP_Quicktune',
],
)

View File

@ -290,7 +290,7 @@ void Sub::one_hz_loop()
}
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
#if HAL_LOGGING_ENABLED
// log terrain data

View File

@ -369,10 +369,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
@ -437,7 +443,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
@ -962,3 +969,47 @@ uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&sub.mode_manual,
&sub.mode_stabilize,
&sub.mode_acro,
&sub.mode_althold,
&sub.mode_surftrak,
&sub.mode_poshold,
&sub.mode_auto,
&sub.mode_guided,
&sub.mode_circle,
&sub.mode_surface,
&sub.mode_motordetect,
};
const uint8_t mode_count = ARRAY_SIZE(modes);
// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}
// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);
return mode_count;
}

View File

@ -37,6 +37,10 @@ protected:
uint64_t capabilities() const override;
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;
private:
void handle_message(const mavlink_message_t &msg) override;

View File

@ -72,6 +72,9 @@ public:
virtual const char *name() const = 0;
virtual const char *name4() const = 0;
// returns a unique number specific to this mode
virtual Mode::Number number() const = 0;
// functions for reporting to GCS
virtual bool get_wp(Location &loc) { return false; }
virtual int32_t wp_bearing() const { return 0; }
@ -202,6 +205,7 @@ protected:
const char *name() const override { return "MANUAL"; }
const char *name4() const override { return "MANU"; }
Mode::Number number() const override { return Mode::Number::MANUAL; }
};
@ -224,6 +228,7 @@ protected:
const char *name() const override { return "ACRO"; }
const char *name4() const override { return "ACRO"; }
Mode::Number number() const override { return Mode::Number::ACRO; }
};
@ -246,6 +251,7 @@ protected:
const char *name() const override { return "STABILIZE"; }
const char *name4() const override { return "STAB"; }
Mode::Number number() const override { return Mode::Number::STABILIZE; }
};
@ -272,6 +278,7 @@ protected:
const char *name() const override { return "ALT_HOLD"; }
const char *name4() const override { return "ALTH"; }
Mode::Number number() const override { return Mode::Number::ALT_HOLD; }
};
@ -293,6 +300,7 @@ protected:
const char *name() const override { return "SURFTRAK"; }
const char *name4() const override { return "STRK"; }
Mode::Number number() const override { return Mode::Number::SURFTRAK; }
private:
@ -342,6 +350,8 @@ protected:
const char *name() const override { return "GUIDED"; }
const char *name4() const override { return "GUID"; }
Mode::Number number() const override { return Mode::Number::GUIDED; }
autopilot_yaw_mode get_default_auto_yaw_mode(bool rtl) const;
private:
@ -387,6 +397,7 @@ protected:
const char *name() const override { return "AUTO"; }
const char *name4() const override { return "AUTO"; }
Mode::Number number() const override { return Mode::Number::AUTO; }
private:
void auto_wp_run();
@ -417,6 +428,7 @@ protected:
const char *name() const override { return "POSHOLD"; }
const char *name4() const override { return "POSH"; }
Mode::Number number() const override { return Mode::Number::POSHOLD; }
};
@ -439,6 +451,7 @@ protected:
const char *name() const override { return "CIRCLE"; }
const char *name4() const override { return "CIRC"; }
Mode::Number number() const override { return Mode::Number::CIRCLE; }
};
class ModeSurface : public Mode
@ -460,6 +473,7 @@ protected:
const char *name() const override { return "SURFACE"; }
const char *name4() const override { return "SURF"; }
Mode::Number number() const override { return Mode::Number::CIRCLE; }
};
@ -482,4 +496,5 @@ protected:
const char *name() const override { return "MOTORDETECT"; }
const char *name4() const override { return "DETE"; }
Mode::Number number() const override { return Mode::Number::MOTOR_DETECT; }
};

View File

@ -18,11 +18,12 @@ void Sub::motors_output()
verify_motor_test();
} else {
motors.set_interlock(true);
SRV_Channels::cork();
auto &srv = AP::srv();
srv.cork();
SRV_Channels::calc_pwm();
SRV_Channels::output_ch_all();
motors.output();
SRV_Channels::push();
srv.push();
}
}

View File

@ -210,7 +210,7 @@ void Blimp::one_hz_loop()
#endif
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
AP_Notify::flags.flying = !ap.land_complete;

View File

@ -327,10 +327,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
@ -395,7 +401,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
static const ap_message STREAM_ADSB_msgs[] = {
MSG_ADSB_VEHICLE,
@ -608,3 +615,41 @@ uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Blimp::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&blimp.mode_land,
&blimp.mode_manual,
&blimp.mode_velocity,
&blimp.mode_loiter,
&blimp.mode_rtl,
};
const uint8_t mode_count = ARRAY_SIZE(modes);
// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}
// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);
return mode_count;
}

View File

@ -48,6 +48,10 @@ protected:
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
#endif
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;
private:
void handle_message(const mavlink_message_t &msg) override;

View File

@ -52,6 +52,9 @@ public:
virtual const char *name() const = 0;
virtual const char *name4() const = 0;
// returns a unique number specific to this mode
virtual Mode::Number number() const = 0;
virtual bool is_landing() const
{
return false;
@ -159,6 +162,8 @@ protected:
return "MANU";
}
Mode::Number number() const override { return Mode::Number::MANUAL; }
private:
};
@ -201,6 +206,8 @@ protected:
return "VELY";
}
Mode::Number number() const override { return Mode::Number::VELOCITY; }
private:
};
@ -244,6 +251,8 @@ protected:
return "LOIT";
}
Mode::Number number() const override { return Mode::Number::LOITER; }
private:
Vector3f target_pos;
float target_yaw;
@ -286,6 +295,8 @@ protected:
return "LAND";
}
Mode::Number number() const override { return Mode::Number::LAND; }
private:
};
@ -328,4 +339,7 @@ protected:
{
return "RTL";
}
Mode::Number number() const override { return Mode::Number::RTL; }
};

View File

@ -78,8 +78,10 @@ void Blimp::motors_output()
// output any servo channels
SRV_Channels::calc_pwm();
auto &srv = AP::srv();
// cork now, so that all channel outputs happen at once
SRV_Channels::cork();
srv.cork();
// update output on any aux channels, for manual passthru
SRV_Channels::output_ch_all();
@ -88,5 +90,5 @@ void Blimp::motors_output()
motors->output();
// push all channels
SRV_Channels::push();
}
srv.push();
}

View File

@ -38,7 +38,7 @@ void Blimp::init_rc_in()
void Blimp::init_rc_out()
{
// enable aux servos to cope with multiple output channels per motor
SRV_Channels::enable_aux_servos();
AP::srv().enable_aux_servos();
// refresh auxiliary channel to function map
SRV_Channels::update_aux_servo_function();

View File

@ -6,13 +6,13 @@
#include "ap_version.h"
#define THISFIRMWARE "Blimp V4.5.0-dev"
#define THISFIRMWARE "Blimp V4.7.0-dev"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,7,0,FIRMWARE_VERSION_TYPE_DEV
#define FW_MAJOR 4
#define FW_MINOR 5
#define FW_MINOR 7
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

View File

@ -20,6 +20,8 @@ RUN apt-get update && apt-get install --no-install-recommends -y \
lsb-release \
sudo \
tzdata \
git \
default-jre \
bash-completion
COPY Tools/environment_install/install-prereqs-ubuntu.sh /ardupilot/Tools/environment_install/
@ -39,9 +41,19 @@ RUN SKIP_AP_EXT_ENV=$SKIP_AP_EXT_ENV SKIP_AP_GRAPHIC_ENV=$SKIP_AP_GRAPHIC_ENV SK
USER=${USER_NAME} \
Tools/environment_install/install-prereqs-ubuntu.sh -y
# Rectify git perms issue that seems to crop up only on OSX
RUN git config --global --add safe.directory $PWD
# Check that local/bin are in PATH for pip --user installed package
RUN echo "if [ -d \"\$HOME/.local/bin\" ] ; then\nPATH=\"\$HOME/.local/bin:\$PATH\"\nfi" >> ~/.ardupilot_env
# Clone & install Micro-XRCE-DDS-Gen dependancy
RUN git clone --recurse-submodules https://github.com/ardupilot/Micro-XRCE-DDS-Gen.git /home/${USER_NAME}/Micro-XRCE-DDS-Gen \
&& cd /home/${USER_NAME}/Micro-XRCE-DDS-Gen \
&& ./gradlew assemble \
&& export AP_ENV_LOC="/home/${USER_NAME}/.ardupilot_env" \
&& echo "export PATH=\$PATH:$PWD/scripts" >> $AP_ENV_LOC
# Create entrypoint as docker cannot do shell substitution correctly
RUN export ARDUPILOT_ENTRYPOINT="/home/${USER_NAME}/ardupilot_entrypoint.sh" \
&& echo "#!/bin/bash" > $ARDUPILOT_ENTRYPOINT \

View File

@ -541,10 +541,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_CURRENT_WAYPOINT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
@ -613,7 +619,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};
static const ap_message STREAM_ADSB_msgs[] = {
MSG_ADSB_VEHICLE,
@ -1148,3 +1155,54 @@ uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Rover::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&rover.mode_manual,
&rover.mode_acro,
&rover.mode_steering,
&rover.mode_hold,
&rover.mode_loiter,
#if MODE_FOLLOW_ENABLED
&rover.mode_follow,
#endif
&rover.mode_simple,
&rover.g2.mode_circle,
&rover.mode_auto,
&rover.mode_rtl,
&rover.mode_smartrtl,
&rover.mode_guided,
&rover.mode_initializing,
#if MODE_DOCK_ENABLED
(Mode *)rover.g2.mode_dock_ptr,
#endif
};
const uint8_t mode_count = ARRAY_SIZE(modes);
// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}
// Ask the mode for its name and number
const char* name = modes[index_zero]->name4();
const uint8_t mode_number = (uint8_t)modes[index_zero]->mode_number();
mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);
return mode_count;
}

Some files were not shown because too many files have changed in this diff Show More