makeflyeasy PixSurveyA1¶
Specifications¶
Processor:
32-bit STM32F427VIT6 ARM Cortex M4 core with FPU
168 Mhz/256 KB RAM/2 MB Flash
32-bit failsafe co-processor (STMF103)
Sensors
Three redundant IMUs (accels, gyros and compass)
Gyro/Accelerometers: ICM20948 or MPU9250, ICM20602, MPU6000
Barometers: Two redundant MS5611 barometers
Compass: AK8960 or AK09916
Power
Redundant power supply with automatic failover
Power supply 4.8V-5.8V
Interfaces
14x PWM servo outputs (8 from IO, 6 from FMU)
S.Bus servo output
R/C inputs for CPPM, Spektrum / DSM and S.Bus
5x general purpose serial ports
2x I2C ports
2x CAN Bus interface
MicroSD card reader
Type-C USB
High-powered piezo buzzer driver (on expansion board)
Safety switch / LED
Dimensions
Weight 117g
Size 110mm x 100mm x 23mm
UART Mapping¶
SERIAL0 -> console (primary mavlink, usually USB)
SERIAL1 -> USART2 (telem1)
SERIAL2 -> USART3 (Telem2) RTS/CTS pins
SERIAL3 -> UART4 (primary GPS)
SERIAL4 -> UART8 (GPS2)
Connector pin assignments¶
TELEM1, TELEM2 ports¶
Pin | Signal | Volt |
---|---|---|
1 | VCC | +5V |
2 | TX (OUT) | +3.3V |
3 | RX (IN) | +3.3V |
4 | GND | GND |
I2C1, I2C2 port¶
PIN | SIGNAL | VOLT |
---|---|---|
1 | VCC | +5V |
2 | SCL | +3.3V |
3 | SDA | +3.3V |
4 | GND | GND |
CAN1, CAN2 port¶
PIN | SIGNAL | VOLT |
---|---|---|
1 | VCC | +5V |
2 | CAN_H | +12V |
3 | CAN_L | +12V |
4 | GND | GND |
Safety port¶
PIN | SIGNAL | VOLT |
---|---|---|
1 | VCC | +5V |
2 | LED | +3.3V |
3 | SafKey | +3.3V |
GPS1/I2C1, GPS2/I2C2 ports¶
PIN | SIGNAL | VOLT |
---|---|---|
1 | VCC | +5V |
2 | TX | +3.3V |
3 | RX | +3.3V |
4 | SCL | +3.3V |
5 | SDA | +3.3V |
6 | GND | GND |
Power1, Power2 ports¶
PIN | SIGNAL | VOLT |
---|---|---|
1 | VCC | +5V |
2 | VCC | +5V |
3 | CURRENT | +3.3V |
4 | VOLTAGE | +3.3V |
5 | GND | GND |
6 | GND | GND |
RC Input¶
The PPM/SBus.in pin, which by default is mapped to a timer input, can be used for all ArduPilot supported receiver protocols, except CRSF/ELRS and SRXL2 which require a true UART connection. However, FPort, when connected in this manner, will only provide RC without telemetry.
To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART, such as SERIAL4 (UART8) would need to be used for receiver connections. Below are setups using UART4. SERIAL4_PROTOCOL should be set to “23”.
FPort would require SERIAL4_OPTIONS be set to “15”.
CRSF would require SERIAL4_OPTIONS be set to “0”.
SRXL2 would require SERIAL4_OPTIONS be set to “4” and connects only the UART4 TX pin.
Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See Radio Control Systems for details.
PWM Output¶
The PixSurveyA1 supports up to 14 PWM outputs. All 14 outputs support all normal PWM output formats. All FMU outputs (9-14) support DShot.
The 6 FMU outputs are in 4 groups:
Outputs 9, 10, 11 and 12 in group1
Outputs 13 and 14 in group2
FMU outputs within the same group need to use the same output rate and protocol. If any output in a group uses DShot then all channels in that group need to use DShot.
Battery Monitor Settings¶
These should already be set by default. However, if lost or changed:
Enable Battery monitor with these parameter settings :
BATT_MONITOR =4
Then reboot.