ardupilot/Tools/AP_Periph
Andrew Tridgell 4c0ef40d3b AP_Periph: fixed IMU in periph
wait_for_sample() can't handle very low sample rates without a
separate delay() by a ms value
2024-12-10 09:29:37 +11:00
..
Web/scripts AP_Periph: show MCU temp in PPPGW web UI 2024-06-27 10:11:14 +10:00
AP_Periph.cpp AP_Periph: Prepare reboot before rebooting via AP_Periph:reboot() 2024-11-19 16:08:40 +11:00
AP_Periph.h AP_Periph: added simulation of DroneCAN servo status 2024-12-03 07:38:17 +11:00
GCS_MAVLink.cpp Rover: add specific defines for sending of GPS mavlink messages 2024-11-13 19:40:19 +11:00
GCS_MAVLink.h AP_Periph: add missing mandatory virtual method define for GCS_MAVLink 2024-11-15 11:25:19 +11:00
Parameters.cpp AP_Periph: Fix documentation for INS parameters 2024-11-05 10:05:01 +09:00
Parameters.h AP_Periph: add support for publishing raw imu data 2024-10-23 06:46:22 +09:00
README.md Tools:add qualifier for ADSB type in readme 2023-09-18 13:41:04 -07:00
ReleaseNotes.txt AP_Periph: release notes for 1.7.0 2024-02-26 07:52:55 +11:00
adsb.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
airspeed.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
baro.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
batt_balance.cpp Tools: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
batt_balance.h AP_Periph: added battery balance plug node 2023-08-26 21:12:42 +10:00
battery.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
buzzer.cpp AP_Periph: rename Notify buzzertype enumeration 2024-06-20 14:47:20 +10:00
can.cpp AP_Periph: make can broadcast threadsafe, like can_printf call from lua thread 2024-09-16 19:45:24 +10:00
compass.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
efi.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
esc_apd_telem.cpp AP_Periph: rearrange apd periph initialiser for --error=reorder 2024-11-13 06:40:37 +11:00
esc_apd_telem.h AP_Periph: Support APD ESC telemetry 2023-05-25 17:35:27 -07:00
gps.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
hardpoint.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
hwing_esc.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
hwing_esc.h AP_Periph: fixed HWESC temperature decoding 2020-04-02 11:43:37 +11:00
i2c.h AP_Periph: added peripheral firmware 2019-08-27 10:29:56 +10:00
imu.cpp AP_Periph: fixed IMU in periph 2024-12-10 09:29:37 +11:00
msp.cpp AP_Periph: use gmtime_r() instead of gmtime() 2024-02-21 12:09:48 +11:00
networking.cpp AP_Periph: added reboot link to web UI 2024-01-21 12:30:08 +11:00
networking.h AP_Periph: added reboot link to web UI 2024-01-21 12:30:08 +11:00
networking_passthru.cpp AP_Periph: fix include order network build error 2023-11-29 12:29:19 +11:00
proximity.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
rangefinder.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
rc_in.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
rc_in.h AP_Periph: move RC IN parameters to sub-object 2023-08-19 20:27:24 +10:00
rc_out.cpp AP_Periph: added simulation of DroneCAN servo status 2024-12-03 07:38:17 +11:00
relay.cpp Tools: AP_Periph: add support for relay via incoming hardpoint command 2024-01-10 18:29:24 +11:00
rpm.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
serial_options.cpp AP_Periph: added support for SERIAL_OPTIONS 2023-12-27 05:13:14 -07:00
serial_options.h AP_Periph: added support for SERIAL_OPTIONS 2023-12-27 05:13:14 -07:00
serial_options_dev.cpp AP_Periph: added support for SERIAL_OPTIONS 2023-12-27 05:13:14 -07:00
serial_tunnel.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
temperature.cpp AP_Periph: remove redundant DroneCAN packet buffer initialization 2024-08-03 19:02:39 +10:00
version.cpp AP_Periph: fix version setting in CheckFirmware app descriptor 2024-02-21 18:54:17 +11:00
version.h AP_Periph: mark master as 1.8.0 dev 2024-02-26 07:53:39 +11:00
wscript AP_Periph: fixed build with scripting 2024-11-20 07:32:03 +11:00

README.md

AP_Periph DroneCAN Peripheral Firmware

This is an ArduPilot based DroneCAN peripheral firmware. This firmware takes advantage of the wide range of sensor drivers in ArduPilot to make building a DroneCAN peripheral firmware easy.

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 DroneCAN peripheral based on the STM32 by just writing a simple hwdef.dat that defines the pinout of your device.

We have over 60 build targets building for AP_Periph firmwares. All ArduPilot supported MCUs can be used, including:

  • STM32F1xx
  • STM32F3xx
  • STM32F4xx
  • STM32F7xx
  • STM32H7xx
  • STM32L4xx
  • STM32G4xx

More can be added using the hwdef.dat system

Features

The AP_Periph firmware can be configured to enable a wide range of DroneCAN 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 (uAvionix compatible Ping ADSB receiver on UART)
  • Battery Monitor (Analog, I2C/SMBus, UART)
  • LEDs (GPIO, I2C or WS2812 serial)
  • Safety LED and Safety Switch
  • Buzzer (tonealarm or simple GPIO)
  • RC Output (All standard RCOutput protocols)
  • RC input
  • battery balance monitor
  • EFI engines
  • Proximity sensors

An AP_Periph DroneCAN firmware supports these DroneCAN 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 and parameter update via MissionPlanner or DroneCAN GUI tool when attached to an autopilot
  • firmware update via USB if USB port is provided
  • parameter update using SLCAN and DroneCAN GUI on standalone peripheral via USB, if provided

Building

Using f103-GPS as an example, build the main firmware like this:

  • ./waf configure --board f103-GPS
  • ./waf AP_Periph

that will build a file build/f103-GPS/bin/AP_Periph.bin. You can now load that using the CAN bootloader and either dronecan_gui_tool or MissionPlanner DroneCAN support.

Flashing

To load directly with a stlink-v2, do this:

  • st-flash write build/f103-GPS/bin/AP_Periph.bin 0x8006400

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:

  • st-flash write Tools/bootloaders/f103-GPS_bl.bin 0x8000000

Building bootloader

To build the bootloader use this:

  • Tools/scripts/build_bootloaders.py f103-GPS

the resulting bootloader will be in Tools/bootloaders

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 DroneCAN GUI Tool. Parameters for peripherals can be changed using the Mission Planner DroneCAN support or using DroneCAN GUI Tools.

User Bootloader Update

The bootloader is automatically stored in ROMFS in the main firmware. End users can update the bootloader by setting the DroneCAN 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 DroneCAN GUI tool to show the result of the flash.

SITL Testing

A wide range of DroneCAN peripherals are supported in the SITL simulation system. The simplest way of starting a DroneCAN enabled simulated vehicle is to use sim_vehicle.py.

For a quadplane use: sim_vehicle.py with the option -f quadplane-can

For a quadcopter use: sim_vehicle.py with the option -f quad-can

Discussion and Feedback

Please join the discussions at these locations: