mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tools: update periph README.md
This commit is contained in:
parent
b612c245bd
commit
789aab7fee
@ -1,28 +1,32 @@
|
|||||||
# AP_Periph UAVCAN Peripheral Firmware
|
# AP_Periph DroneCAN Peripheral Firmware
|
||||||
|
|
||||||
This is an ArduPilot based UAVCAN peripheral firmware. This firmware
|
This is an ArduPilot based DroneCAN peripheral firmware. This firmware
|
||||||
takes advantage of the wide range of sensor drivers in ArduPilot to
|
takes advantage of the wide range of sensor drivers in ArduPilot to
|
||||||
make building a UAVCAN peripheral firmware easy.
|
make building a DroneCAN peripheral firmware easy.
|
||||||
|
|
||||||
The AP_Periph firmware is based on the same ChibiOS hwdef.dat system
|
The AP_Periph firmware is based on the same ChibiOS hwdef.dat system
|
||||||
that is used to define pinouts for STM32 based flight controllers
|
that is used to define pinouts for STM32 based flight controllers
|
||||||
supported by ArduPilot. That means you can add support for a new
|
supported by ArduPilot. That means you can add support for a new
|
||||||
UAVCAN peripheral based on the STM32 by just writing a simple
|
DroneCAN peripheral based on the STM32 by just writing a simple
|
||||||
hwdef.dat that defines the pinout of your device.
|
hwdef.dat that defines the pinout of your device.
|
||||||
|
|
||||||
Currently we have four targets building for AP_Periph firmwares:
|
We have over 60 build targets building for AP_Periph firmwares. All
|
||||||
|
ArduPilot supported MCUs can be used, including:
|
||||||
|
|
||||||
- A STM32F103 128k flash part made by mRobotics (target f103-GPS)
|
- STM32F1xx
|
||||||
- A STM32F412 512k flash part made by CUAV (target CUAV_GPS)
|
- STM32F3xx
|
||||||
- A STM32F105 256k flash part (used in ZubaxGNSSv2)
|
- STM32F4xx
|
||||||
- A STM32F303 256k flash part made by mRobotics (target f303-GPS)
|
- STM32F7xx
|
||||||
|
- STM32H7xx
|
||||||
|
- STM32L4xx
|
||||||
|
- STM32G4xx
|
||||||
|
|
||||||
More can be added using the hwdef.dat system
|
More can be added using the hwdef.dat system
|
||||||
|
|
||||||
# Features
|
# Features
|
||||||
|
|
||||||
The AP_Periph firmware can be configured to enable a wide range of
|
The AP_Periph firmware can be configured to enable a wide range of
|
||||||
UAVCAN sensor types. Support is included for:
|
DroneCAN sensor types. Support is included for:
|
||||||
|
|
||||||
- GPS modules (including RTK GPS)
|
- GPS modules (including RTK GPS)
|
||||||
- Magnetometers (SPI or I2C)
|
- Magnetometers (SPI or I2C)
|
||||||
@ -35,8 +39,12 @@ UAVCAN sensor types. Support is included for:
|
|||||||
- Safety LED and Safety Switch
|
- Safety LED and Safety Switch
|
||||||
- Buzzer (tonealarm or simple GPIO)
|
- Buzzer (tonealarm or simple GPIO)
|
||||||
- RC Output (All standard RCOutput protocols)
|
- RC Output (All standard RCOutput protocols)
|
||||||
|
- RC input
|
||||||
|
- battery balance monitor
|
||||||
|
- EFI engines
|
||||||
|
- Proximity sensors
|
||||||
|
|
||||||
An AP_Periph UAVCAN firmware supports these UAVCAN features:
|
An AP_Periph DroneCAN firmware supports these DroneCAN features:
|
||||||
|
|
||||||
- dynamic or static CAN node allocation
|
- dynamic or static CAN node allocation
|
||||||
- firmware upload
|
- firmware upload
|
||||||
@ -56,8 +64,8 @@ Using f103-GPS as an example, build the main firmware like this:
|
|||||||
- ./waf AP_Periph
|
- ./waf AP_Periph
|
||||||
|
|
||||||
that will build a file build/f103-GPS/bin/AP_Periph.bin. You can
|
that will build a file build/f103-GPS/bin/AP_Periph.bin. You can
|
||||||
now load that using the CAN bootloader and either uavcan_gui_tool or
|
now load that using the CAN bootloader and either dronecan_gui_tool or
|
||||||
MissionPlanner SLCAN support.
|
MissionPlanner DroneCAN support.
|
||||||
|
|
||||||
# Flashing
|
# Flashing
|
||||||
|
|
||||||
@ -87,95 +95,32 @@ the resulting bootloader will be in Tools/bootloaders
|
|||||||
|
|
||||||
Firmware targets are automatically built and distributed on the
|
Firmware targets are automatically built and distributed on the
|
||||||
ArduPilot firmware server on firmware.ardupilot.org. These firmwares
|
ArduPilot firmware server on firmware.ardupilot.org. These firmwares
|
||||||
can be loaded using Mission Planner or the UAVCAN GUI Tool. Parameters
|
can be loaded using Mission Planner or the DroneCAN GUI Tool. Parameters
|
||||||
for peripherals can be changed using the Mission Planner SLCAN support
|
for peripherals can be changed using the Mission Planner DroneCAN support
|
||||||
or using UAVCAN GUI Tools.
|
or using DroneCAN GUI Tools.
|
||||||
|
|
||||||
# User Bootloader Update
|
# User Bootloader Update
|
||||||
|
|
||||||
The bootloader is automatically stored in ROMFS in the main
|
The bootloader is automatically stored in ROMFS in the main
|
||||||
firmware. End users can update the bootloader by setting the UAVCAN
|
firmware. End users can update the bootloader by setting the DroneCAN
|
||||||
parameter "FLASH_BOOTLOADER" to 1. After setting it to 1 the node will
|
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
|
respond with a debug text message which can be seen in the DroneCAN GUI
|
||||||
tool to show the result of the flash.
|
tool to show the result of the flash.
|
||||||
|
|
||||||
# SITL Testing
|
# SITL Testing
|
||||||
|
|
||||||
Currently GPS peripheral build is supported under linux environment,
|
A wide range of DroneCAN peripherals are supported in the SITL
|
||||||
we simulate a UAVCAN GPS Peripheral on SocketCAN.
|
simulation system. The simplest way of starting a DroneCAN enabled
|
||||||
|
simulated vehicle is to use sim_vehicle.py.
|
||||||
|
|
||||||
Setup can be done as follows, this is on top of usual setup required
|
For a quadplane use: sim_vehicle.py with the option -f quadplane-can
|
||||||
to build ardupilot:
|
|
||||||
|
|
||||||
```
|
For a quadcopter use: sim_vehicle.py with the option -f quad-can
|
||||||
sudo dpkg --add-architecture i386
|
|
||||||
sudo apt-get update
|
|
||||||
sudo apt-get install -y gcc-multilib g++-multilib
|
|
||||||
sudo apt-get update
|
|
||||||
sudo apt-get -y install can-utils iproute2 linux-modules-extra-$(uname -r)
|
|
||||||
sudo modprobe vcan
|
|
||||||
sudo ip link add dev vcan0 type vcan
|
|
||||||
sudo ip link set up vcan0
|
|
||||||
```
|
|
||||||
Build Commands:
|
|
||||||
```
|
|
||||||
./waf configure --board sitl_periph_gps
|
|
||||||
./waf AP_Periph
|
|
||||||
```
|
|
||||||
Autotest Command:
|
|
||||||
```
|
|
||||||
Tools/autotest/autotest.py -v Copter build.SITLPeriphGPS test.CAN
|
|
||||||
```
|
|
||||||
|
|
||||||
|
|
||||||
---
|
|
||||||
**Note**
|
|
||||||
|
|
||||||
To run valgrind on AP_Periph binary you might need to get 32 bit version of libc6-dbg which can be simply get using following command for Ubuntu machines: `sudo apt-get install libc6-dbg:i386`
|
|
||||||
|
|
||||||
---
|
|
||||||
|
|
||||||
|
|
||||||
https://github.com/linux-can/can-utils contains a nice set of utility to do CAN related testings on Linux system. I used Ubuntu for this development, for Ubuntu systems you can simply download this tool using `sudo apt-get install can-utils`
|
|
||||||
|
|
||||||
Following are the common commands that can be used while testing or developing:
|
|
||||||
* Create Virtual CAN Interface:
|
|
||||||
```
|
|
||||||
sudo modprobe vcan
|
|
||||||
sudo ip link add dev vcan0 type vcan
|
|
||||||
sudo ip link set up vcan0
|
|
||||||
sudo ip link add dev vcan1 type vcan
|
|
||||||
sudo ip link set up vcan1
|
|
||||||
```
|
|
||||||
* Route one CANSocket to another
|
|
||||||
```
|
|
||||||
sudo modprobe can-gw
|
|
||||||
sudo cangw -A -s vcan0 -d vcan1 -e
|
|
||||||
sudo cangw -A -s vcan1 -d vcan0 -e
|
|
||||||
```
|
|
||||||
* Delete routes
|
|
||||||
```
|
|
||||||
sudo cangw -D -s vcan0 -d vcan1 -e
|
|
||||||
sudo cangw -D -s vcan1 -d vcan0 -e
|
|
||||||
```
|
|
||||||
* Route SLCAN to VCAN, this allows connecting CAN devices to SITL run via CAN Adapter like the one running in Ardupilot itself.
|
|
||||||
```
|
|
||||||
sudo modprobe slcan
|
|
||||||
sudo modprobe can-gw
|
|
||||||
sudo slcan_attach -f -s8 -o /dev/ttyACM0
|
|
||||||
sudo slcand ttyACM0 slcan0
|
|
||||||
sudo ifconfig slcan0 up
|
|
||||||
sudo cangw -A -s vcan0 -d slcan0 -e
|
|
||||||
sudo cangw -A -s slcan0 -d vcan0 -e
|
|
||||||
```
|
|
||||||
* Dump can messages:
|
|
||||||
```
|
|
||||||
sudo candump vcan0
|
|
||||||
```
|
|
||||||
|
|
||||||
# Discussion and Feedback
|
# Discussion and Feedback
|
||||||
|
|
||||||
Please join the discussions at these locations:
|
Please join the discussions at these locations:
|
||||||
|
|
||||||
- https://discuss.ardupilot.org/t/ap-periph-1-0-0-stable-released/49049
|
- https://discuss.ardupilot.org/
|
||||||
- https://gitter.im/ArduPilot/CANBUS
|
- https://ardupilot.org/discord
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user