2019-10-28 19:36:47 -03:00
|
|
|
# AP_Periph UAVCAN Peripheral Firmware
|
2019-09-10 03:40:25 -03:00
|
|
|
|
2019-10-28 19:36:47 -03:00
|
|
|
This is an ArduPilot based UAVCAN peripheral firmware. This firmware
|
|
|
|
takes advantage of the wide range of sensor drivers in ArduPilot to
|
2019-10-29 01:22:29 -03:00
|
|
|
make building a UAVCAN peripheral firmware easy.
|
2019-10-28 19:36:47 -03:00
|
|
|
|
|
|
|
The AP_Periph firmware is based on the same ChibiOS hwdef.dat system
|
|
|
|
that is used to define pinouts for STM32 based flight controllers
|
|
|
|
supported by ArduPilot. That means you can add support for a new
|
|
|
|
UAVCAN peripheral based on the STM32 by just writing a simple
|
|
|
|
hwdef.dat that defines the pinout of your device.
|
|
|
|
|
2019-11-07 00:49:38 -04:00
|
|
|
Currently we have four targets building for AP_Periph firmwares:
|
2019-09-10 03:40:25 -03:00
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
- A STM32F103 128k flash part made by mRobotics (target f103-GPS)
|
2019-09-10 03:40:25 -03:00
|
|
|
- A STM32F412 512k flash part made by CUAV (target CUAV_GPS)
|
2019-10-28 19:36:47 -03:00
|
|
|
- A STM32F105 256k flash part (used in ZubaxGNSSv2)
|
2019-10-31 18:37:00 -03:00
|
|
|
- A STM32F303 256k flash part made by mRobotics (target f303-GPS)
|
2019-10-28 19:36:47 -03:00
|
|
|
|
2019-10-31 18:37:00 -03:00
|
|
|
More can be added using the hwdef.dat system
|
2019-10-28 19:36:47 -03:00
|
|
|
|
|
|
|
# Features
|
|
|
|
|
|
|
|
The AP_Periph firmware can be configured to enable a wide range of
|
|
|
|
UAVCAN sensor types. Support is included for:
|
|
|
|
|
|
|
|
- GPS modules (including RTK GPS)
|
|
|
|
- Magnetometers (SPI or I2C)
|
|
|
|
- Barometers (SPI or I2C)
|
|
|
|
- Airspeed sensors (I2C)
|
|
|
|
- Rangefinders (UART or I2C)
|
|
|
|
- ADSB (Ping ADSB receiver on UART)
|
|
|
|
- LEDs (GPIO, I2C or WS2812 serial)
|
|
|
|
- Safety LED and Safety Switch
|
|
|
|
- Buzzer (tonealarm or simple GPIO)
|
|
|
|
|
|
|
|
An AP_Periph UAVCAN firmware supports these UAVCAN features:
|
|
|
|
|
|
|
|
- dynamic or static CAN node allocation
|
|
|
|
- firmware upload
|
|
|
|
- automatically generated bootloader
|
|
|
|
- parameter storage in flash
|
|
|
|
- easy bootloader update
|
|
|
|
- high resiliance features using watchdog, CRC and board checks
|
|
|
|
- firmware update via MissionPlanner or uavcan-gui-tool
|
2019-09-10 03:40:25 -03:00
|
|
|
|
|
|
|
# Building
|
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
Using f103-GPS as an example, build the main firmware like this:
|
2019-09-10 03:40:25 -03:00
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
- ./waf configure --board f103-GPS
|
2019-09-10 03:40:25 -03:00
|
|
|
- ./waf AP_Periph
|
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
that will build a file build/f103-GPS/bin/AP_Periph.bin. You can
|
2019-09-10 03:40:25 -03:00
|
|
|
now load that using the CAN bootloader and either uavcan_gui_tool or
|
2019-10-29 01:22:29 -03:00
|
|
|
MissionPlanner SLCAN support.
|
2019-09-10 03:40:25 -03:00
|
|
|
|
|
|
|
# Flashing
|
|
|
|
|
|
|
|
To load directly with a stlink-v2, do this:
|
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
- st-flash write build/f103-GPS/bin/AP_Periph.bin 0x8006400
|
2019-09-10 03:40:25 -03:00
|
|
|
|
|
|
|
for the CUAV_GPS which loads at offset 0x10000 use this:
|
|
|
|
|
|
|
|
- st-flash write build/CUAV_GPS/bin/AP_Periph.bin 0x8010000
|
|
|
|
|
|
|
|
# Flashing bootloader
|
|
|
|
|
|
|
|
To flash the bootloader use this:
|
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
- st-flash write Tools/bootloaders/f103-GPS_bl.bin 0x8000000
|
2019-09-10 03:40:25 -03:00
|
|
|
|
|
|
|
# Building bootloader
|
|
|
|
|
|
|
|
To build the bootloader use this:
|
|
|
|
|
2019-10-02 08:55:41 -03:00
|
|
|
- Tools/scripts/build_bootloader.py f103-GPS
|
2019-09-10 03:40:25 -03:00
|
|
|
|
|
|
|
the resulting bootloader will be in Tools/bootloaders
|
|
|
|
|
2019-11-07 00:49:38 -04:00
|
|
|
# Firmware Builds
|
|
|
|
|
|
|
|
Firmware targets are automatically built and distributed on the
|
|
|
|
ArduPilot firmware server on firmware.ardupilot.org. These firmwares
|
|
|
|
can be loaded using Mission Planner or the UAVCAN GUI Tool. Parameters
|
|
|
|
for peripherals can be changed using the Mission Planner SLCAN support
|
|
|
|
or using UAVCAN GUI Tools.
|
2019-11-09 05:45:15 -04:00
|
|
|
|
|
|
|
# User Bootloader Update
|
|
|
|
|
|
|
|
The bootloader is automatically stored in ROMFS in the main
|
|
|
|
firmware. End users can update the bootloader by setting the UAVCAN
|
|
|
|
parameter "FLASH_BOOTLOADER" to 1. After setting it to 1 the node will
|
|
|
|
respond with a debug text message which can be seen in the UAVCAN GUI
|
|
|
|
tool to show the result of the flash.
|
2019-11-09 06:54:43 -04:00
|
|
|
|
|
|
|
# Discussion and Feedback
|
|
|
|
|
|
|
|
Please join the discussions at these locations:
|
|
|
|
|
|
|
|
- https://discuss.ardupilot.org/t/ap-periph-1-0-0-stable-released/49049
|
|
|
|
- https://gitter.im/ArduPilot/CANBUS
|