Skip to content

Latest commit

 

History

History
121 lines (93 loc) · 4.17 KB

common-stellarh7v2.rst

File metadata and controls

121 lines (93 loc) · 4.17 KB

[copywiki destination="plane,copter,blimp,rover"]

StellarH7V2

An autopilot sold by StingBee

Features

  • Processor
    • STM32H743VIH6 480 MHz, 2MB flash
  • Sensors
    • ICM-42688p Acc/Gyro with external clock feature
    • DPS310/BMP280 barometer
    • AT7456E OSD
    • SD Card
  • Power
    • 2S-8S Lipo input voltage with voltage monitoring
    • 12V, 3A BEC for powering Video Transmitter
    • 5V, 2A BEC for internal and peripherals
  • Interfaces
    • 10x PWM outputs DShot capable, 4 outputs BDShot capable
    • 7x UARTs
    • 1x CAN
    • 1x I2C
    • 3x ADC
    • SD card for logging
    • USB-C port
  • LED
    • Red, 3.3V power indicator
    • Blue and Green, FC status
  • Size
    • 41 x 41mm PCB with 30.5mm M3 mounting holes

Pinouts

../../../images/StellarH7V2-top.png ../../../images/StellarH7V2-bot.png

UART Mapping

The UARTs are marked RX and TX in the above pinouts. The RX pin is the receive pin for the UART. The TX pin is the transmit pin for UART. All UARTS except UART6 and UART8 are DMA capable. Default protocols are shown below and can be changed by the user.

  • SERIAL0 -> USB
  • SERIAL1 -> UART1 (MAVLink2)
  • SERIAL2 -> UART2 (MAVLink2)
  • SERIAL3 -> UART3 (User)
  • SERIAL4 -> UART4 (Serial RC input)
  • SERIAL5 -> UART6 (GPS)
  • SERIAL6 -> UART7 (DisplayPort)
  • SERIAL7 -> UART8 (ESC Telemetry, RX8 pin only)

CAN and I2C

StellarH7V2 supports 1x CAN bus and 1x I2C bus

RC Input

The default RC input is configured on the UART4 RX4 input and can be used for all ArduPilot supported unidirectional receiver protocols.

OSD Support

StellarH7V2 supports using its internal OSD using OSD_TYPE 1 (MAX7456 driver). Simulatenous DisplayPort OSD operation is preconfigured on SERIAL 6 but requires OSD_TYPE2 = 5. See :ref:`common-msp-osd-overview-4.2` for more info.

PWM Output

StellarH7V2 supports up to 10 PWM outputs.

All the channels support DShot. Channels 1-6 support bi-directional DShot. Channels 9 and 10 are marked as S5 and S6 on the board. PWM outputs are grouped and every group must use the same output protocol:

  • 1, 2 are Group 1;
  • 3, 4, 5, 6 are Group 2;
  • 7, 8, 9, 10 are Group 3;

Battery Monitoring

The board has 1 built-in voltage dividers and 2x current ADC which support external 3.3V based current sensors. The voltage input is compatible with 2~8S LiPo batteries.

The default battery parameters are:

Camera Switch

GPIO 81 controls which camera input (CAM1 or CAM2) is applied to the internal OSD. A RELAY function (see :ref:`common-relay`)can be enabled to control the switching.

Compass

StellarH7V2 does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads.

Loading Firmware

Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled StellarH7V2.

Initial firmware load can be done with DFU by plugging in USB with the boot button pressed. Then you should load the "xxxx_with_bl.hex" firmware, using your favorite DFU loading tool. eg STM32CubeProgrammer

Subsequently, you can update firmware with Mission Planner or other ArduPilot compatible GCS.