mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ea7c7f9d19
Co-authored-by: Dr.-Ing. Amilcar do Carmo Lucas <amilcar.lucas@iav.de> tidy message sending using templates Calculate and enforce the minimum update period. Disable unused features to save flash forced time gaps between all transmits correct ESC reset functionality Avoid re-initialization repeatition Make sure we stop FETtec if safety is on (ignore reverse) this reduces duplicated code Error count calculation changed as the telemetry error count is absolute only the overflow status can be safed and used for the percentage calculation Update the README to add autotests information FETtec needs a time gap between frames This allows running at high fast_loop_rates do not send fast_throttle data if a configuration command just got sent Example parameter configuration file is for a Quadcopter with ESCs connected to Telem2 remove two FIXME fix compilation in master Fix the ESC not re-initializing issue. Now we re-init whenever we loose connection RVMASK parameter changes only take effect when not armed Improve documentation Always use the same wording when referring to fast-throttle commands fix pre-arm check message assure the length of the memmove is positive Set HAL_AP_FETTEC_CONFIGURE_ESCS to 0 when no ESC hardware is available and you want to test the UART send function
32 lines
736 B
Plaintext
32 lines
736 B
Plaintext
# Example parameter configuration file is for a Quadcopter with ESCs connected to Telem2
|
|
|
|
# FETtec OneWire ESCs are connected on Telem2 port
|
|
SERIAL2_PROTOCOL 38
|
|
SERIAL2_OPTIONS 0
|
|
|
|
# Use the full digital range supported by the ESCs
|
|
MOT_PWM_MAX 2000
|
|
MOT_PWM_MIN 1000
|
|
|
|
# Make sure the correct functions get routed out
|
|
SERVO1_FUNCTION 33
|
|
SERVO2_FUNCTION 34
|
|
SERVO3_FUNCTION 35
|
|
SERVO4_FUNCTION 36
|
|
|
|
# Activate FETtec OneWire support
|
|
SERVO_FTW_MASK 15
|
|
SERVO_FTW_RVMASK 0
|
|
SERVO_FTW_POLES 14
|
|
|
|
# Use RPM telemetry data to dynamically configure one notch filter per motor
|
|
INS_HNTCH_ENABLE 1
|
|
INS_HNTCH_MODE 3
|
|
INS_HNTCH_OPTS 2
|
|
INS_HNTCH_REF 1
|
|
INS_HNTCH_FREQ 60
|
|
INS_HNTCH_BW 30
|
|
|
|
# Use ESC telemetry data as a "virtual" battery monitor
|
|
BATT2_MONITOR 9
|