Skip to content

Commit

Permalink
Raccoonlab devices (#3295)
Browse files Browse the repository at this point in the history
* Add descriptions for supported RaccoonLab devices:
- manufacturer-supported FMUv6X Autopilot;
- magnetometer module;
- airspeed sensor;
- barometers;
- rangefinders;
- GNSS modules;
- PWM-ESC adapters and general-purpose DroneCAN and Cyphal/CAN nodes;
- DroneCAN power modules

* Add RaccoonLab nodes, autopilot and power modules pages to SUMMARY.md

* Shrink images

* FC subedit

* Gnss subedit

* rtk/mag subedit (table tidy)

* Only add redirects if you need the link or to redirect

* Rangefinder subedit

* minor updates to pm and dronecan

* RTK fix - linkchecker fail on anchor so revert otherwise good changes

* FC is pixhawk standard

---------

Co-authored-by: Roman Fedorenko <[email protected]>
  • Loading branch information
hamishwillee and frontw authored Jul 18, 2024
1 parent bf82e7c commit cb12f47
Show file tree
Hide file tree
Showing 23 changed files with 361 additions and 40 deletions.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added assets/flight_controller/raccoonlab/fmuv6x.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
3 changes: 3 additions & 0 deletions en/SUMMARY.md
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,7 @@
- [Holybro Pixhawk 6X-RT (FMUv6X-RT)](flight_controller/pixhawk6x-rt.md)
- [Holybro Pixhawk 6X (FMUv6X)](flight_controller/pixhawk6x.md)
- [Wiring Quickstart](assembly/quick_start_pixhawk6x.md)
- [RaccoonLab FMU6x](flight_controller/raccoonlab_fmu6x.md)
- [Holybro Pixhawk 6C (FMUv6C)](flight_controller/pixhawk6c.md)
- [Wiring Quickstart](assembly/quick_start_pixhawk6c.md)
- [Holybro Pixhawk 6C Mini(FMUv6C)](flight_controller/pixhawk6c_mini.md)
Expand Down Expand Up @@ -322,6 +323,7 @@
- [Holybro PM02D (digital)](power_module/holybro_pm02d.md)
- [Holybro PM03D (digital)](power_module/holybro_pm03d.md)
- [Pomegranate Systems Power Module](dronecan/pomegranate_systems_pm.md)
- [RaccoonLab Power Modules](dronecan/raccoonlab_power.md)
- [Sky-Drones SmartAP PDB](power_module/sky-drones_smartap-pdb.md)
- [Smart/MAVLink Batteries](smart_batteries/index.md)
- [Rotoye Batmon Battery Smartification Kit](smart_batteries/rotoye_batmon.md)
Expand All @@ -347,6 +349,7 @@
- [DroneCAN Peripherals](dronecan/index.md)
- [PX4 DroneCAN Firmware](dronecan/px4_cannode_fw.md)
- [ARK CANnode](dronecan/ark_cannode.md)
- [RaccoonLab CAN Nodes](dronecan/raccoonlab_nodes.md)
- [Cable Wiring](assembly/cable_wiring.md)
- [Companion Computers](companion_computer/index.md)
- [Pixhawk + Companion Setup](companion_computer/pixhawk_companion.md)
Expand Down
1 change: 1 addition & 0 deletions en/advanced_config/ethernet_setup.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ Supported flight controllers include:
- [CUAV Pixhawk V6X](../flight_controller/cuav_pixhawk_v6x.md)
- [Holybro Pixhawk 5X](../flight_controller/pixhawk5x.md)
- [Holybro Pixhawk 6X](../flight_controller/pixhawk6x.md)
- [RaccoonLab FMUv6X Autopilot](../flight_controller/raccoonlab_fmu6x.md)

## Setting up the Ethernet Network

Expand Down
1 change: 1 addition & 0 deletions en/dronecan/escs.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,4 @@ For more information, see the following articles for specific hardware/firmware:
- [Zubax Telega](zubax_telega.md)
- [Vertiq](../peripherals/vertiq.md) (larger modules)
- [VESC Project](../peripherals/vesc.md)
- [RaccoonLab Cyphal and DroneCAN PWM nodes](raccoonlab_nodes.md)
67 changes: 67 additions & 0 deletions en/dronecan/raccoonlab_nodes.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
# RaccoonLab Mini/Micro Nodes

Mini/Micro are general purpose CAN nodes. The functionality of these devices depends on the firmware they are running.
The default and most popular usage is as a PWM-CAN adapter to control ESCs and servos using CAN (Cyphal or DroneCAN) communication:

- Micro is the smallest node with 2 groups of pins (PWM/5V/GND) to control 2 servos or ESCs.
- Mini v2: Features 2 x PWM/5V/GND for controlling servos or ESCs and 2 x PWM/FB/GND for controlling and receiving feedback from ESCs via UART.

## Cyphal/DroneCAN CAN-PWM Adapter Firmware

_Cyphal/DroneCAN CAN-PWM_ firmwares are the default for Mini and Micro nodes.
These convert a typical PX4 CAN setpoint to PWM for controlling ESCs or servos.

Please refer to the corresponding RaccoonLab docs pages for details: [Cyphal/CAN-PWM](https://docs.raccoonlab.co/guide/can_pwm/cyphal.html), [DroneCAN-PWM](https://docs.raccoonlab.co/guide/can_pwm/dronecan.html).

![Mini v2 Node with Servo and ESC](../../assets/hardware/can_nodes/raccoonlab_mini_v2_with_servo.png)

## Cyphal & DroneCAN Rangefinder Firmware

The _Cyphal & DroneCAN Rangefinder_ firmware is a single firmware that can work in either Cyphal or DroneCAN mode.
It supports LW20/I2C, Garmin Lite v3/I2C and TL-Luna/UART lidars.
For details, please check the [Rangefinder](https://docs.raccoonlab.co/guide/can_pwm/rangefinder.html) page.

![Mini v2 Node with servo and ESC](../../assets/hardware/can_nodes/raccoonlab_mini_v2_lw20_i2c.png)

## DroneCAN Fuel Sensor Firmware

_DroneCAN fuel tank_ firmware is based on the [AS5600 sensor board](https://docs.raccoonlab.co/guide/as5600/).
Please refer to [DroneCAN Fuel Tank](https://docs.raccoonlab.co/guide/can_pwm/fuel_tank.html) for details.

## DroneCAN Servo Gripper Firmware

_DroneCAN servo gripper_ is part of a [Mini Node Template Application](https://github.com/RaccoonlabDev/mini_v2_node).
Please refer to [DroneCAN Servo Gripper](https://docs.raccoonlab.co/guide/can_pwm/servo_gripper.html) for details.

## Custom Firmware

**Custom firmware** can be developed by anyone.
If you require custom features, you can use the [Mini Node Template Application](https://github.com/RaccoonlabDev/mini_v2_node).
You can configure the external pins to work in UART, I2C or ADC mode.
From the box, it supports basic Cyphal/DroneCAN features.
It has publishers and subscribers as an example.

## Which node to choose?

The differences between [Mini v2](https://docs.raccoonlab.co/guide/can_pwm/can_pwm_mini_v2.html) and [Micro](https://docs.raccoonlab.co/guide/can_pwm/can_pwm_micro.html) are summarized in the table below.
For more details, please refer to the corresponding pages.

| | | Mini v2 | Micro |
| --- | --------------- | ----------------------------------------- | ------------------------------------ |
| | Image | ![RaccoonLab Mini v2 Node][Mini v2 Node] | ![RaccoonLab Micro Node][Micro Node] |
| 1 | Input voltage | 5.5V – 30V | 4.5V – 5.5V |
| 2 | DC-DC | Yes | No |
| 3 | Groups of pins | - PWM+5V+GND x2 </br> - PWM+FB+GND x2 | - PWM+5V+GND x2 |
| 4 | CAN connectors | - UCANPHY Micro x2 </br> - 6-pin Molex x2 | - UCANPHY Micro x2 |
| 5 | SWD interface | + | + |
| 6 | Size, LxWxH, mm | 42x35x12 | 20x10x5 |
| 7 | Mass, g | 5 | 3 |

[Mini v2 Node]: ../../assets/hardware/can_nodes/raccoonlab_mini_node.png
[Micro Node]: ../../assets/hardware/can_nodes/raccoonlab_micro_node.png

## Where to Buy

[RaccoonLab Store](https://raccoonlab.co/store)

[Cyphal store](https://cyphal.store/search?q=raccoonlab)
41 changes: 41 additions & 0 deletions en/dronecan/raccoonlab_power.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# RaccoonLab Power Connectors and Management Units

## CAN Power Connectors

CAN power connectors are designed for light unmanned aerial (UAV) and other vehicles for providing power over CAN using [CAN power cables](https://docs.raccoonlab.co/guide/pmu/wires/).

There are two types of devices:

1. `CAN-MUX` devices provide power from XT30 connector to CAN.
There are 2 variation of this type of the device with different number of connectors.
2. `Power connector node` is designed to pass current (up to 60A) to power load and CAN, measure voltage and current on load.
It behaves as Cyphal/DroneCAN node.

Please refer to the RaccoonLab docs [CAN Power Connectors](https://docs.raccoonlab.co/guide/pmu/power/) page.

**Connection example diagram**

Here are the examples:

- The first shows how to use both external high voltage power and 5V CAN power for different nodes with MUX.
The [NODE](raccoonlab_nodes.md) (the large one in the left diagram) is connected to a high-voltage power source (here 30 V).
In this case, the [uNODE](raccoonlab_nodes.md) (smaller one on the left schematic) is powered directly from the autopilot.
- The second example shows how to connect multiple [uNODEs](raccoonlab_nodes.md) that are powered by the autopilot (5V).
If these nodes are powered from a separate DCDC, that DCDC should also be connected to one of these connectors.

![RaccoonLab CAN Power Connector Example Diagram](../../assets/hardware/power_module/raccoonlab_can/raccoonlab_power_connector_example.png)

## Power Management Unit

![raccoonlab pmu ](../../assets/hardware/power_module/raccoonlab_can/raccoonlab_pmu.jpg)

This board monitors the battery (voltage and current) and allows control over charging, source and load using he DroneCAN interface.
It might be useful for applications where you need to control the power of the drone including the board computer and charging process.

Please refer to the RaccoonLab docs [Power & Connectivity](https://docs.raccoonlab.co/guide/pmu/) page.

## Where to Buy

[RaccoonLab Store](https://raccoonlab.co/store)

[Cyphal store](https://cyphal.store/search?q=raccoonlab)
1 change: 1 addition & 0 deletions en/flight_controller/autopilot_pixhawk_standard.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ The boards in this category are:
- [Holybro Pixhawk 6X-RT](../flight_controller/pixhawk6x-rt.md) (FMUv6X)
- [CUAV Pixahwk V6X](../flight_controller/cuav_pixhawk_v6x.md) (FMUv6X)
- [Holybro Pixhawk 6X](../flight_controller/pixhawk6x.md) (FMUv6X)
- [RaccoonLab FMUv6X Autopilot](../flight_controller/raccoonlab_fmu6x.md) (FMUv6X)
- [Holybro Pixhawk 6C](../flight_controller/pixhawk6c.md) (FMUv6C)
- [Holybro Pixhawk 6C Mini](../flight_controller/pixhawk6c_mini.md) (FMUv6C)
- [Holybro Pix32 v6](../flight_controller/holybro_pix32_v6.md) (FMUv6C)
Expand Down
1 change: 1 addition & 0 deletions en/flight_controller/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ There are other compatible flight controllers and variants, including those [doc
- [Holybro pix32 v6 (FMUv6C)](../flight_controller/holybro_pix32_v6.md)
- [mRo Pixracer (FMUv4)](../flight_controller/pixracer.md)
- [mRo Pixhawk (FMUv2)](../flight_controller/mro_pixhawk.md)
- [RaccoonLab FMUv6X Autopilot (FMUv6X)](../flight_controller/raccoonlab_fmu6x.md)
- [Manufacturer-Supported Autopilots](../flight_controller/autopilot_manufacturer_supported.md)
- [AIRLink](../flight_controller/airlink.md)
- [AirMind MindPX](../flight_controller/mindpx.md)
Expand Down
162 changes: 162 additions & 0 deletions en/flight_controller/raccoonlab_fmu6x.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,162 @@
# RaccoonLab FMUv6X Autopilot

:::warning
PX4 does not manufacture this (or any) autopilot.
Contact the [manufacturer](https://raccoonlab.co) for hardware support or compliance issues.
:::

The [RaccoonLab FMUv6X](https://docs.raccoonlab.co/guide/autopilot/RCLv6X.html) flight controller is based on the following Pixhawk​® standards: [Pixhawk Autopilot FMUv6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf), [Autopilot Bus Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-010%20Pixhawk%20Autopilot%20Bus%20Standard.pdf), and [Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf).

Equipped with a high-performance H7 Processor, modular design, triple redundancy, temperature-controlled IMU board, and isolated sensor domains, it delivers exceptional performance, reliability, and flexibility.
At RaccoonLab, we focus on DroneCAN and Cyphal-based onboard control system buses.
Our autopilot is part of a larger DroneCAN and Cyphal ecosystem, making it an ideal choice for next-generation intelligent vehicles.

![RaccoonLab FMUv6X](../../assets/flight_controller/raccoonlab/fmuv6x.png)

RaccoonLab offers versatile HATs for both Raspberry Pi and NVIDIA Jetson Xavier NX, enhancing connectivity and functionality.
The [Jetson Xavier NX HAT](https://docs.raccoonlab.co/guide/nx_hat/) is designed to integrate the CAN bus with the Jetson Xavier NX, enabling access to Cyphal and DroneCAN protocols.
The [Raspberry Pi CM4 HAT](https://docs.raccoonlab.co/guide/rpi_hat/) provides robust features, including CAN bus connectivity, an LTE modem, internal voltage measurement, SWD debugging for other MCUs, and UART communication with PX4 over MAVLINK.
These HATs expand the capabilities of devices, making them ideal for advanced robotics and UAV applications.

:::tip
This autopilot is [supported](../flight_controller/autopilot_pixhawk_standard.md) by the PX4 maintenance and test teams.
:::

## Key Design Points

- High performance STM32H753 Processor
- Modular flight controller: separated IMU, FMU, and Base system connected by a 100-pin & a 50-pin Pixhawk Autopilot Bus connector.
- Redundancy: 3x IMU sensors & 2x Barometer sensors on separate buses
- Triple redundancy domains: Completely isolated sensor domains with separate buses and separate power control
- Newly designed vibration isolation system to filter out high frequency vibration and reduce noise to ensure accurate readings
- Ethernet interface for high-speed mission computer integration

## Processors & Sensors

- FMU Processor: STM32H753
- 32 Bit Arm Cortex-M7, 480MHz, 2MB flash memory, 1MB RAM
- IO Processor: STM32F100
- 32 Bit Arm Cortex-M3, 24MHz, 8KB SRAM
- On-board sensors
- Accel/Gyro: ICM-20649 or BMI088
- Accel/Gyro: ICM-42688-P
- Accel/Gyro: ICM-42670-P
- Mag: BMM150
- Barometer: 2x BMP388

## Electrical data

- Voltage Ratings:
- Max input voltage: 36V
- USB Power Input: 4.75\~5.25V
- Servo Rail Input: 0\~36V
- Current Ratings:
- `TELEM1` output current limiter: 1.5A
- All other port combined output current limiter: 1.5A

## Mechanical data

- Dimensions
- Flight Controller Module: 38.8 x 31.8 x 14.6mm
- Standard Baseboard: 52.4 x 103.4 x 16.7mm
- Mini Baseboard: 43.4 x 72.8 x 14.2 mm
- Weight
- Flight Controller Module: 23g
- Standard Baseboard: 51g
- Mini Baseboard: 26.5g

3D model can be downloaded on [GrabCAD](https://grabcad.com/library/raccoonlab-autopilot-1).

![RaccoonLab FMUv6X drawings](../../assets/flight_controller/raccoonlab/fmuv6x-drw.png)

## Interfaces

- 16- PWM servo outputs
- R/C input for Spektrum / DSM
- Dedicated R/C input for PPM and S.Bus input
- Dedicated analog / PWM RSSI input and S.Bus output
- 4 general purpose serial ports
- 3 with full flow control
- 1 with separate 1.5A current limit (`TELEM1`)
- 1 with I2C and additional GPIO line for external NFC reader
- 2 GPS ports
- 1 full GPS plus Safety Switch Port
- 1 basic GPS port
- 1 I2C port
- 1 Ethernet port
- Transformerless Applications
- 100Mbps
- 1 SPI bus
- 2 chip select lines
- 2 data-ready lines
- 1 SPI SYNC line
- 1 SPI reset line
- 2 CAN Buses for CAN peripheral
- CAN Bus has individual silent controls or ESC RX-MUX control
- 2 Power input ports with SMBus
- 1 AD & IO port
- 2 additional analog input
- 1 PWM/Capture input
- 2 Dedicated debug and GPIO lines

## Serial Port Mapping

| UART | Device | Port |
| ------ | ---------- | ------------- |
| USART1 | /dev/ttyS0 | GPS |
| USART2 | /dev/ttyS1 | TELEM3 |
| USART3 | /dev/ttyS2 | Debug Console |
| UART4 | /dev/ttyS3 | UART4 & I2C |
| UART5 | /dev/ttyS4 | TELEM2 |
| USART6 | /dev/ttyS5 | PX4IO/RC |
| UART7 | /dev/ttyS6 | TELEM1 |
| UART8 | /dev/ttyS7 | GPS2 |

## Voltage Ratings

_RaccoonLab FMUv6X_ can be triple-redundant on the power supply if three power sources are supplied.
The three power rails are: **POWER1**, **POWER2** and **USB**.
The **POWER1** & **POWER2** ports on the RaccoonLab FMUv6X uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/molex/products/part-detail/pcb_receptacles/5024430670).

**Normal Operation Maximum Ratings**

Under these conditions all power sources will be used in this order to power the system:

1. **POWER1** and **POWER2** inputs (4.9V to 5.5V)
2. **USB** input (4.75V to 5.25V)

:::tip
The manufacturer [RaccoonLab Docs](https://docs.raccoonlab.co/guide/autopilot/RCLv6X.html) are the canonical reference for the RaccoonLab FMUv6X Autopilot.
They should be used by preference as they contain the most complete and up to date information.
:::

## Where to Buy

[RaccoonLab Store](https://raccoonlab.co/store)

[Cyphal store](https://cyphal.store)

## Building Firmware

:::tip
Most users will not need to build this firmware!
It is pre-built and automatically installed by _QGroundControl_ when appropriate hardware is connected.
:::

To [build PX4](../dev_setup/building_px4.md) for this target:

```sh
make px4_fmu-v6x_default
```

## Supported Platforms / Airframes

Any multicopter / airplane / rover or boat that can be controlled with normal RC servos or Futaba S-Bus servos.
The complete set of supported configurations can be seen in the [Airframes Reference](../airframes/airframe_reference.md).

## Further info

- [Pixhawk Autopilot FMUv6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf)
- [Pixhawk Autopilot Bus Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-010%20Pixhawk%20Autopilot%20Bus%20Standard.pdf)
- [Pixhawk Connector Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-009%20Pixhawk%20Connector%20Standard.pdf)
- [RaccoonLab docs](http://docs.raccoonlab.co)
Loading

0 comments on commit cb12f47

Please sign in to comment.