Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_HAL_ChibiOS: hwdef: ARK_FPV board support #28603

Open
wants to merge 10 commits into
base: master
Choose a base branch
from

Conversation

dakejahl
Copy link
Contributor

@dakejahl dakejahl commented Nov 13, 2024

Adds board support for the ARK FPV.
https://arkelectron.com/product/ark-fpv-flight-controller/

Testing Checklist

From https://ardupilot.org/dev/docs/porting.html

  • the board boots and connects to a GCS via USB (Mission Planner, QGC, MAVProxy,etc.)
  • the GPS and Compass is recognized.
  • the RC is recognized and RC input follows the TX
  • the pitch and roll reports (ie HUD horizon) follows autopilot movement correctly (ie IMU is oriented properly and working). test each IMU individually using the INSx_USE parameters.
  • the board arms with default arming checks (may need to force arm if GPS is indoors)
    • I get a warning about FS_THR_VALUE, due to FS_THR_ENABLE being default. Not entirely sure what these params do.
  • attach a battery either directly if onboard power sensors or via external power module and make sure voltage is correctly displayed and current indication present
  • attach a test servo to each output after setting the output to a normal function like elevator, and exercise each one with TX while in MANUAL mode to check output functionality. Bdshot capable outputs should be tested with a BLHeli32 esc for passthrough mode communication (non-IOMCU outputs).
  • move the GPS to each UART output after setting all other UART protocols to NONE and the tested UART to GPS to assure the UART is functioning.
  • UARTs with CTS/RTS lines should use a telemetry radio with those connected to be sure they function with BRD_SERx__CTSRTS=1

From my own notes

  • FW upload on USB
  • FW upload on serial port (GPS)
  • Flash based params functional
  • Telem port test (mavlink)
  • GPS port test (mavlink)
  • RCIN port test (SBUS)
  • PWM 1-4 test (Bidir-DSHOT)
  • ESC Telem test
  • Analog current measurement (ESC pin CURR_IN)
  • CAN port test (DroneCAN via MAVCAN over USB)
  • VTX OSD port test (UART5_RX/TX and UART2_RX)
  • PWM AUX (5 - 9) port test
    • Servo9 doesn't go back to 0 when disabled, it stays at the disarmed PWM value
  • SPI (external) port test
  • 12V ADC measurement

Questions

  • How do I configure the ADC for the 12V input?
    image

Requires

IIS2MDC compass driver PR
#28602

@dakejahl
Copy link
Contributor Author

dakejahl commented Nov 18, 2024

I want to reduce the clock speed to 320MHz to reduce heat but adding MCU_CLOCKRATE_MHZ 320 to the hwdef causes the build to fail. Any ideas?

From Andy

The only value supported is 480 on H7, its a way of raising the clockrate from the default of 400. bit of history the rev X&Y versions of the H7 had silicon bugs which meant they would only work at 400MHz, that's why its an option - and should only be used with rev V

@dakejahl dakejahl marked this pull request as draft November 21, 2024 20:27
@AlexKlimaj
Copy link
Contributor

Just built and flashed. Looks like it is working.

@dakejahl dakejahl force-pushed the pr-ark_fpv branch 2 times, most recently from cbfd219 to 20bfdc2 Compare December 10, 2024 18:51
@dakejahl dakejahl marked this pull request as ready for review December 10, 2024 18:56
@dakejahl dakejahl marked this pull request as draft December 12, 2024 00:44
@dakejahl dakejahl marked this pull request as ready for review December 12, 2024 03:12
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef-bl.dat Outdated Show resolved Hide resolved
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef-bl.dat Outdated Show resolved Hide resolved
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat Outdated Show resolved Hide resolved
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat Outdated Show resolved Hide resolved
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat Outdated Show resolved Hide resolved
PI5 TIM8_CH1 TIM8 PWM(5) GPIO(54) BIDIR
PI6 TIM8_CH2 TIM8 PWM(6) GPIO(55) BIDIR
PI7 TIM8_CH3 TIM8 PWM(7) GPIO(56) BIDIR
PI2 TIM8_CH4 TIM8 PWM(8) GPIO(57) BIDIR
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove bidir

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

how did you determine the correct ones to select for BIDIR? I was reading through some forum posts where you explained it, I thought as long as they didn't share DMA it was okay. I'm also surprised the group is split across two timers. I recently worked on bidir dshot in PX4 so I would love to hear the technical reasons and understand how it works in ardupilot.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should I set any new default params for bidir dshot? Or better to let the user configure these?

MOT_PWM_TYPE
SERVO_BLH_BDMASK
SERVO_BLH_OTYPE
SERVO_DSHOT_ESC
SERVO_DSHOT_RATE

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unless you know what ESC the user is going to use I would leave these alone

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just tested this and it works

PI0  TIM5_CH4 TIM5 PWM(1) GPIO(50) BIDIR
PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) BIDIR
PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) BIDIR
PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) BIDIR
PI5  TIM8_CH1 TIM8 PWM(5) GPIO(54)
PI6  TIM8_CH2 TIM8 PWM(6) GPIO(55)
PI7  TIM8_CH3 TIM8 PWM(7) GPIO(56)
PI2  TIM8_CH4 TIM8 PWM(8) GPIO(57)
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58)

libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat Outdated Show resolved Hide resolved
libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat Outdated Show resolved Hide resolved
PA0 SCALED1_V3V3 ADC1 SCALE(2)
PB1 VDD_5V_SENS ADC1 SCALE(2)
# TODO: 12V monitor
# PA4 SCALED2_V3V3 ADC1 SCALE(7.66)
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do non int values work here? Is this the right way to do it?
Screenshot from 2024-12-11 17-26-15

Comment on lines 103 to 112
# Motors, see STM32H743xx.py
PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50)
PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) BIDIR
PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52)
PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) BIDIR
PI5 TIM8_CH1 TIM8 PWM(5) GPIO(54) BIDIR
PI6 TIM8_CH2 TIM8 PWM(6) GPIO(55)
PI7 TIM8_CH3 TIM8 PWM(7) GPIO(56) BIDIR
PI2 TIM8_CH4 TIM8 PWM(8) GPIO(57)
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58)
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All 8 channels are DMA capable. Is it possible to allow usage of all of them, but only have 4 at a time configured for use? How does the user figure out which channels they need to use?

Comment on lines +125 to +131
# I2C2 (BMP390 baro, internal)
PF1 I2C2_SCL I2C2
PF0 I2C2_SDA I2C2

# I2C4 (IIS2MDC compass, internal)
PF14 I2C4_SCL I2C4
PF15 I2C4_SDA I2C4
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Both of these busses are "internal". I noticed most other boards only have 1 internal bus, is this okay to have 2 internal busses? I assume so since the I2C_INTERNAL_MASK bitmask exists, but wanted to double check.

define HAL_IMUHEAT_P_DEFAULT 50
define HAL_IMUHEAT_I_DEFAULT 0.07
# TODO: should we use this?
# define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good practice to set an IMU temp low margin? Or just pre-arm annoyance?


# SPI6 external bus
# SPIDEV adis16507 SPI6 DEVID1 EXT1_CS MODE3 1*MHZ 2*MHZ
# IMU ADIS1647x SPI:adis16507 ROTATION_NONE ADIS_DRDY_PIN
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should I have this driver active by default? Along with any other IMU drivers we want to support on external SPI?

@@ -57,6 +58,7 @@ Reserved "PX4 [BL] FMU v6X.x" 53
Reserved "PX4 [BL] FMU v6C.x" 56

Reserved "ARK [BL] FMU v6X.x" 57
Reserved "ARK [BL] FPV" 59
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this causes CI to fail

@dakejahl
Copy link
Contributor Author

ESC Bidir DShot passthrough works using BIDIR on Channels 1 - 4
image

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants