diff --git a/assets/flight_controller/raccoonlab/fmuv6x-drw.png b/assets/flight_controller/raccoonlab/fmuv6x-drw.png new file mode 100644 index 000000000000..d269df200b22 Binary files /dev/null and b/assets/flight_controller/raccoonlab/fmuv6x-drw.png differ diff --git a/assets/flight_controller/raccoonlab/fmuv6x.png b/assets/flight_controller/raccoonlab/fmuv6x.png new file mode 100644 index 000000000000..acfaeb1ea539 Binary files /dev/null and b/assets/flight_controller/raccoonlab/fmuv6x.png differ diff --git a/assets/hardware/can_nodes/raccoonlab_micro_node.png b/assets/hardware/can_nodes/raccoonlab_micro_node.png new file mode 100644 index 000000000000..0bd913ec72cc Binary files /dev/null and b/assets/hardware/can_nodes/raccoonlab_micro_node.png differ diff --git a/assets/hardware/can_nodes/raccoonlab_mini_node.png b/assets/hardware/can_nodes/raccoonlab_mini_node.png new file mode 100644 index 000000000000..b4c0bff535f3 Binary files /dev/null and b/assets/hardware/can_nodes/raccoonlab_mini_node.png differ diff --git a/assets/hardware/can_nodes/raccoonlab_mini_v2_lw20_i2c.png b/assets/hardware/can_nodes/raccoonlab_mini_v2_lw20_i2c.png new file mode 100644 index 000000000000..70817a2b0461 Binary files /dev/null and b/assets/hardware/can_nodes/raccoonlab_mini_v2_lw20_i2c.png differ diff --git a/assets/hardware/can_nodes/raccoonlab_mini_v2_with_servo.png b/assets/hardware/can_nodes/raccoonlab_mini_v2_with_servo.png new file mode 100644 index 000000000000..2a15681ba484 Binary files /dev/null and b/assets/hardware/can_nodes/raccoonlab_mini_v2_with_servo.png differ diff --git a/assets/hardware/power_module/raccoonlab_can/raccoonlab_pmu.jpg b/assets/hardware/power_module/raccoonlab_can/raccoonlab_pmu.jpg new file mode 100644 index 000000000000..ef4528a02212 Binary files /dev/null and b/assets/hardware/power_module/raccoonlab_can/raccoonlab_pmu.jpg differ diff --git a/assets/hardware/power_module/raccoonlab_can/raccoonlab_power_connector_example.png b/assets/hardware/power_module/raccoonlab_can/raccoonlab_power_connector_example.png new file mode 100644 index 000000000000..beb5e4c5ba62 Binary files /dev/null and b/assets/hardware/power_module/raccoonlab_can/raccoonlab_power_connector_example.png differ diff --git a/en/SUMMARY.md b/en/SUMMARY.md index faf5a7230e5d..25270cfe8bb3 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -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) @@ -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) @@ -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) diff --git a/en/advanced_config/ethernet_setup.md b/en/advanced_config/ethernet_setup.md index 0a13d77bc3ac..a2b681f054b4 100644 --- a/en/advanced_config/ethernet_setup.md +++ b/en/advanced_config/ethernet_setup.md @@ -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 diff --git a/en/dronecan/escs.md b/en/dronecan/escs.md index 05ecfab59547..44b4a4acc3d9 100644 --- a/en/dronecan/escs.md +++ b/en/dronecan/escs.md @@ -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) diff --git a/en/dronecan/raccoonlab_nodes.md b/en/dronecan/raccoonlab_nodes.md new file mode 100644 index 000000000000..4912abb94ca0 --- /dev/null +++ b/en/dronecan/raccoonlab_nodes.md @@ -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
- PWM+FB+GND x2 | - PWM+5V+GND x2 | +| 4 | CAN connectors | - UCANPHY Micro x2
- 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) diff --git a/en/dronecan/raccoonlab_power.md b/en/dronecan/raccoonlab_power.md new file mode 100644 index 000000000000..245658e1cf36 --- /dev/null +++ b/en/dronecan/raccoonlab_power.md @@ -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) diff --git a/en/flight_controller/autopilot_pixhawk_standard.md b/en/flight_controller/autopilot_pixhawk_standard.md index 9e869fb12caf..d4a669b71595 100644 --- a/en/flight_controller/autopilot_pixhawk_standard.md +++ b/en/flight_controller/autopilot_pixhawk_standard.md @@ -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) diff --git a/en/flight_controller/index.md b/en/flight_controller/index.md index b0383db5c813..e64d21b11c02 100644 --- a/en/flight_controller/index.md +++ b/en/flight_controller/index.md @@ -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) diff --git a/en/flight_controller/raccoonlab_fmu6x.md b/en/flight_controller/raccoonlab_fmu6x.md new file mode 100644 index 000000000000..728a87de242b --- /dev/null +++ b/en/flight_controller/raccoonlab_fmu6x.md @@ -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) diff --git a/en/gps_compass/index.md b/en/gps_compass/index.md index 326ec8ff19a7..1b2bc32dec1a 100644 --- a/en/gps_compass/index.md +++ b/en/gps_compass/index.md @@ -15,7 +15,6 @@ Up to two GPS modules can be connected using either a UART or the CAN bus: PX4 also supports [Real Time Kinematic (RTK)](../gps_compass/rtk_gps.md) and **Post-Processing Kinematic (PPK)** GNSS Receivers, which extend GNSS systems to centimetre-level precision. ::: - ## Supported GNSS PX4 should work with any unit that communicates via the u-blox, MTK Ashtech or Emlid protocols, or via UAVCAN. @@ -23,28 +22,29 @@ PX4 should work with any unit that communicates via the u-blox, MTK Ashtech or E This table contains non-RTK GNSS units (most of which also have a compass). These have been tested by the PX4 dev team, or which are popular within the PX4 community. -| Device | GPS | Compass | [CAN](../dronecan/index.md) | Buzzer / SafeSw / LED | Notes | -| :------------------------------------------------------------------------ | :---------: | :-----------------------: | :-------------------------: | :-------------------: | :-------------------------- | -| [ARK GPS](https://arkelectron.com/product/ark-gps/) | M9N | ICM42688p | ✓ | ✓ | + Baro, IMU | -| [Avionics Anonymous UAVCAN GNSS/Mag][avionics_anon_can_gnss] | SAM-M8Q | MMC5983MA | ✓ | ✗ | -| [CUAV NEO 3 GPS](../gps_compass/gps_cuav_neo_3.md) | M9N | IST8310 | | ✓ | -| [CUAV NEO 3 Pro GPS](../gps_compass/gps_cuav_neo_3pro.md) | M9N | RM3100 | ✓ | ✓ | + Baro | -| [CUAV NEO 3X GPS](../gps_compass/gps_cuav_neo_3x.md) | M9N | RM3100 | ✓ | ✗✓✓ | + Baro. | -| [CubePilot Here2 GNSS GPS (M8N)](../gps_compass/gps_hex_here2.md) | M8N | ICM20948 | | ✓ | Superseded by HERE3 | -| [Emlid Reach M+](https://emlid.com/reach/) | ✓ | ✗ | | ✗ | Supports PPK. RTK expected. | -| [Holybro DroneCAN M8N GPS](../dronecan/holybro_m8n_gps.md) | M8N | BMM150 | ✓ | ✗ | + Baro | -| [Holybro Micro M8N GPS](https://holybro.com/products/micro-m8n-gps) | M8N | IST8310 | | ✗ | -| [Holybro Nano Ublox M8 5883 GPS][hb_nano_m8_5883] | UBX-M8030 | QMC5883 | | ✗ | -| [Holybro M8N GPS](../gps_compass/gps_holybro_m8n_m9n.md) | M8N | IST8310 | | ✓ | -| [Holybro M9N GPS](../gps_compass/gps_holybro_m8n_m9n.md) | M9N | IST8310 | | ✓ | -| [Holybro DroneCAN M9N GPS](https://holybro.com/products/dronecan-m9n-gps) | M9N | BMM150 | ✓ | ✓ | -| [Hobbyking u-blox Neo-M8N GPS with Compass][hk_ublox_neo_8mn] | M8N | ✓ | | ✗ | -| [LOCOSYS Hawk A1 GNSS receiver](../gps_compass/gps_locosys_hawk_a1.md) | MC-1612-V2b | optional | | ✗✗✓ | -| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | ✗✗✓ | -| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | ✗✗✓ | -| [mRo GPS u-blox Neo-M8N Dual Compass][mro_neo8mn_dual_mag] | M8N | LIS3MDL, IST8308 | | ✗ | -| [Sky-Drones SmartAP GPS](../gps_compass/gps_smartap.md) | M8N | HMC5983, IST8310, LIS3MDL | | ✓ | + Baro | -| [Zubax GNSS 2](https://zubax.com/products/gnss_2) | MAX-M8Q | LIS3MDL | | ✗ | + Baro | +| Device | GPS | Compass | [CAN](../dronecan/index.md) | Buzzer / SafeSw / LED | Notes | +| :--------------------------------------------------------------------- | :---------: | :-----------------------: | :-------------------------: | :-------------------: | :-------------------------- | +| [ARK GPS](https://arkelectron.com/product/ark-gps/) | M9N | ICM42688p | ✓ | ✓ | + Baro, IMU | +| [Avionics Anonymous UAVCAN GNSS/Mag][avionics_anon_can_gnss] | SAM-M8Q | MMC5983MA | ✓ | ✗ | +| [CUAV NEO 3 GPS](../gps_compass/gps_cuav_neo_3.md) | M9N | IST8310 | | ✓ | +| [CUAV NEO 3 Pro GPS](../gps_compass/gps_cuav_neo_3pro.md) | M9N | RM3100 | ✓ | ✓ | + Baro | +| [CUAV NEO 3X GPS](../gps_compass/gps_cuav_neo_3x.md) | M9N | RM3100 | ✓ | ✗✓✓ | + Baro. | +| [CubePilot Here2 GNSS GPS (M8N)](../gps_compass/gps_hex_here2.md) | M8N | ICM20948 | | ✓ | Superseded by HERE3 | +| [Emlid Reach M+](https://emlid.com/reach/) | ✓ | ✗ | | ✗ | Supports PPK. RTK expected. | +| [Holybro DroneCAN M8N GPS](../dronecan/holybro_m8n_gps.md) | M8N | BMM150 | ✓ | ✗ | + Baro | +| [Holybro Micro M8N GPS](https://holybro.com/products/micro-m8n-gps) | M8N | IST8310 | | ✗ | +| [Holybro Nano Ublox M8 5883 GPS][hb_nano_m8_5883] | UBX-M8030 | QMC5883 | | ✗ | +| [Holybro M8N GPS](../gps_compass/gps_holybro_m8n_m9n.md) | M8N | IST8310 | | ✓ | +| [Holybro M9N GPS](../gps_compass/gps_holybro_m8n_m9n.md) | M9N | IST8310 | | ✓ | +| [Holybro DroneCAN M9N GPS][hb_can_m9n] | M9N | BMM150 | ✓ | ✓ | +| [Hobbyking u-blox Neo-M8N GPS & Compass][hk_ublox_neo_8mn] | M8N | ✓ | | ✗ | +| [LOCOSYS Hawk A1 GNSS receiver](../gps_compass/gps_locosys_hawk_a1.md) | MC-1612-V2b | optional | | ✗✗✓ | +| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | ✗✗✓ | +| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | ✗✗✓ | +| [mRo GPS u-blox Neo-M8N Dual Compass][mro_neo8mn_dual_mag] | M8N | LIS3MDL, IST8308 | | ✗ | +| [RaccoonLab L1 GNSS NEO-M8N][RccnLabGNSS250] | NEO-M8N | RM3100 | ✓ | ✗✗✓ | + Baro | +| [Sky-Drones SmartAP GPS](../gps_compass/gps_smartap.md) | M8N | HMC5983, IST8310, LIS3MDL | | ✓ | + Baro | +| [Zubax GNSS 2](https://zubax.com/products/gnss_2) | MAX-M8Q | LIS3MDL | | ✗ | + Baro | @@ -52,6 +52,8 @@ These have been tested by the PX4 dev team, or which are popular within the PX4 [hk_ublox_neo_8mn]: https://hobbyking.com/en_us/ublox-neo-m8n-gps-with-compass.html [mro_neo8mn_dual_mag]: https://store.mrobotics.io/product-p/m10034-8308.htm [hb_nano_m8_5883]: https://holybro.com/products/nano-m8-5883-gps-module +[hb_can_m9n]: https://holybro.com/products/dronecan-m9n-gps +[RccnLabGNSS250]: https://docs.raccoonlab.co/guide/gps_mag_baro/gnss_v250.html Notes: diff --git a/en/gps_compass/magnetometer.md b/en/gps_compass/magnetometer.md index 0654e856a6ab..320fa1d7c378 100644 --- a/en/gps_compass/magnetometer.md +++ b/en/gps_compass/magnetometer.md @@ -42,6 +42,7 @@ This list contains stand-alone magnetometer modules (without GNSS). | :--------------------------------------------------------------------------------------------------------------- | :-----: | :------: | | [Avionics Anonymous UAVCAN Magnetometer](https://www.tindie.com/products/avionicsanonymous/uavcan-magnetometer/) | ? | | [Holybro DroneCAN RM3100 Compass/Magnetometer](https://holybro.com/products/dronecan-rm3100-compass) | RM3100 | ✓ | +| [RaccoonLab DroneCAN/Cyphal Magnetometer RM3100](https://holybro.com/products/dronecan-rm3100-compass) | RM3100 | ✓ | Note: diff --git a/en/gps_compass/rtk_gps.md b/en/gps_compass/rtk_gps.md index 8ac7d1c10fbd..790a4c1e7c81 100644 --- a/en/gps_compass/rtk_gps.md +++ b/en/gps_compass/rtk_gps.md @@ -42,12 +42,20 @@ Device | GPS | Compass | [DroneCAN](../dronecan/index.md) | [GPS Yaw](#configuri [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | | [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | | [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | | ✓ | +[RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | | +[RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | | [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | ✓ | Septentrio dual antenna heading | ✓ | [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | ✓ | Septentrio dual antenna heading | ✓ | [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | | ✓ | [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | | ✓ | [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | | | + + +[RaccnLabL1L2ZED-F9P ext_ant]: https://docs.raccoonlab.co/guide/gps_mag_baro/gnss_external_antenna_f9p_v320.html +[RaccoonLab L1/L2 ZED-F9P]: https://docs.raccoonlab.co/guide/gps_mag_baro/gps_l1_l2_zed_f9p.html + + Notes: - ✓ or a specific part number indicate that a features is supported, while ✗ or empty show that the feature is not supported. @@ -58,7 +66,6 @@ Notes: For example [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) is discontinued and may be removed from the list in a future release. Check earlier versions if a discontinued module is not mentioned here. - ## Positioning Setup/Configuration RTK positioning requires a _pair_ of [RTK GNSS devices](#supported-devices): a "base" for the ground station and a "rover" for the vehicle. @@ -141,10 +148,16 @@ GPS can be used as a source for yaw fusion when using modules where _yaw output When using GPS for yaw fusion you will need to configure the following parameters: -Parameter | Setting ---- | --- -[GPS_YAW_OFFSET](../advanced_config/parameter_reference.md#GPS_YAW_OFFSET) | The angle made by the *baseline* (the line between the two GPS antennas) relative to the vehicle x-axis (front/back axis, as shown [here](../config/flight_controller_orientation.md#calculating-orientation)). -[EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) | Set bit position 3 "Dual antenna heading" to `1` (i.e. add 8 to the parameter value). | +| Parameter | Setting | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [GPS_YAW_OFFSET][GPS_YAW_OFFSET] | The angle made by the _baseline_ (the line between the two GPS antennas) relative to the vehicle x-axis (front/back axis, as shown [here][fc_orientation]). | +| [EKF2_GPS_CTRL][EKF2_GPS_CTRL] | Set bit position 3 "Dual antenna heading" to `1` (i.e. add 8 to the parameter value). | + + + +[GPS_YAW_OFFSET]: ../advanced_config/parameter_reference.md#GPS_YAW_OFFSET +[EKF2_GPS_CTRL]: ../advanced_config/parameter_reference.md#EKF2_GPS_CTRL +[fc_orientation]: ../config/flight_controller_orientation.md#calculating-orientation :::tip If using this feature, all other configuration should be setup up as normal (e.g. [RTK Positioning](../gps_compass/rtk_gps.md#positioning-setup-configuration)). diff --git a/en/power_module/index.md b/en/power_module/index.md index 543bb1134c0a..fb177f63bb85 100644 --- a/en/power_module/index.md +++ b/en/power_module/index.md @@ -18,15 +18,16 @@ In in practice flight controllers may have different recommendations or preferen This section provides information about a number of power modules and power distribution boards (see FC manufacturer docs for more options): -* Analog voltage and current power modules: - * [CUAV HV PM](../power_module/cuav_hv_pm.md) - * [Holybro PM02](../power_module/holybro_pm02.md) - * [Holybro PM07](../power_module/holybro_pm07_pixhawk4_power_module.md) - * [Holybro PM06 V2](../power_module/holybro_pm06_pixhawk4mini_power_module.md) - * [Sky-Drones SmartAP PDB](../power_module/sky-drones_smartap-pdb.md) -* Digital (I2C) voltage and current power modules (for Pixhawk FMUv6X and FMUv5X derived controllers): - * [Holybro PM02D](../power_module/holybro_pm02d.md) - * [Holybro PM03D](../power_module/holybro_pm03d.md) -* [DroneCAN](../dronecan/index.md) power modules - * [CUAV CAN PMU](../dronecan/cuav_can_pmu.md) - * [Pomegranate Systems Power Module](../dronecan/pomegranate_systems_pm.md) +- Analog voltage and current power modules: + - [CUAV HV PM](../power_module/cuav_hv_pm.md) + - [Holybro PM02](../power_module/holybro_pm02.md) + - [Holybro PM07](../power_module/holybro_pm07_pixhawk4_power_module.md) + - [Holybro PM06 V2](../power_module/holybro_pm06_pixhawk4mini_power_module.md) + - [Sky-Drones SmartAP PDB](../power_module/sky-drones_smartap-pdb.md) +- Digital (I2C) voltage and current power modules (for Pixhawk FMUv6X and FMUv5X derived controllers): + - [Holybro PM02D](../power_module/holybro_pm02d.md) + - [Holybro PM03D](../power_module/holybro_pm03d.md) +- [DroneCAN](../dronecan/index.md) power modules + - [CUAV CAN PMU](../dronecan/cuav_can_pmu.md) + - [Pomegranate Systems Power Module](../dronecan/pomegranate_systems_pm.md) + - [RaccoonLab Power Connectors and PMU](../dronecan/raccoonlab_power.md) diff --git a/en/sensor/airspeed.md b/en/sensor/airspeed.md index 10feb76abff1..0b7d6a90abd6 100644 --- a/en/sensor/airspeed.md +++ b/en/sensor/airspeed.md @@ -17,6 +17,7 @@ Recommended digital airspeed sensors include: - [EagleTree Airspeed MicroSensor V3](http://www.eagletreesystems.com/index.php?route=product/product&product_id=63) (eagletreesystems) - [Sensirion SDP3x Airspeed Sensor Kit](https://store-drotek.com/793-digital-differential-airspeed-sensor-kit-.html) - [Holybro Digital Air Speed Sensor](https://holybro.com/products/digital-air-speed-sensor) + - [RaccoonLab Cyphal/CAN and DroneCAN Airspeed Sensor](https://raccoonlab.co/tproduct/360882105-652259850171-cyphal-and-dronecan-airspeed-v2) - Based on [Venturi effect](https://en.wikipedia.org/wiki/Venturi_effect) - [TFSLOT](airspeed_tfslot.md) Venturi effect airspeed sensor. diff --git a/en/sensor/barometer.md b/en/sensor/barometer.md index f48da0d7ebe8..46f77a8d8bdb 100644 --- a/en/sensor/barometer.md +++ b/en/sensor/barometer.md @@ -15,6 +15,7 @@ Generally barometers require no user configuration (or thought)! They are also present in other hardware: - [CUAV NEO 3 Pro GNSS module](https://doc.cuav.net/gps/neo-series-gnss/en/neo-3-pro.html#key-data) ([MS5611](../modules/modules_driver_baro.md#ms5611)) +- [RaccoonLab L1 GNSS NEO-M8N](https://raccoonlab.co/tproduct/360882105-258620719271-cyphal-and-dronecan-gnss-m8n-magnetomete) At time of writing, drivers/parts include: bmp280, bmp388 (and BMP380), dps310, goertek (spl06), invensense (icp10100, icp10111, icp101xx, icp201xx), lps22hb, lps25h, lps33hw, maiertek (mpc2520), mpl3115a2, ms5611, ms5837, tcbp001ta. diff --git a/en/sensor/rangefinders.md b/en/sensor/rangefinders.md index 674e7e0a6abd..bd0d997dd7cc 100644 --- a/en/sensor/rangefinders.md +++ b/en/sensor/rangefinders.md @@ -41,6 +41,8 @@ The rangefinders are enabled using the parameter [SENS_EN_MB12XX](../advanced_co PX4 supports: SF11/c and SF/LW20. PX4 can also be used with the following discontinued models: SF02, SF10/a, SF10/b, SF10/c. +Others may be supported via the [RaccoonLab Cyphal and DroneCAN Rangefinder Adapter](#raccoonlab-cyphal-and-dronecan-rangefinder-adapter) described below. + PX4 also supports the [LightWare LiDAR SF45 Rotating Lidar](https://www.lightwarelidar.com/shop/sf45-b-50-m/) for [collision prevention](../computer_vision/collision_prevention.md#lightware-lidar-sf45-rotating-lidar) applications. ### TeraRanger Rangefinders @@ -74,6 +76,29 @@ It must be connected to a UART/serial bus. The [Avionics Anonymous UAVCAN Laser Altimeter Interface](../dronecan/avanon_laser_interface.md) allows several common rangefinders (e.g. [Lightware SF11/c, SF30/D](../sensor/sfxx_lidar.md), etc) to be connected to the [CAN](../can/index.md) bus via [DroneCAN](../dronecan/index.md), a more robust interface than I2C. +### RaccoonLab Cyphal and DroneCAN Rangefinder Adapter + +The [RaccoonLab Cyphal and DroneCAN Rangefinder Adapter](https://raccoonlab.co/tproduct/360882105-910084093051-cyphal-and-dronecan-rangefinder-adapter) allows several common rangefinders to be connected to the CAN bus via Cyphal or DroneCAN, providing a more robust interface than I2C or UART. +This adapter efficiently reads measurements via I2C or UART and publishes range data in meters, making it a versatile solution for UAVs, robotics, and technical documentation applications. + +Supported rangefinders include: + +- LightWare LW20/C +- TF-Luna +- Garmin Lite V3 +- VL53L1CB + +### RaccoonLab Cyphal and DroneCAN µRANGEFINDER + +[RaccoonLab µRANGEFINDER](https://docs.raccoonlab.co/guide/rangefinder/uRANGEFINDER.html) is designed to measure distance and publish it via Cyphal/DroneCAN protocols. +It can be used to estimate precision landing or object avoidance. + +Features: + +- [VL53L1CBV0FY-1](https://www.st.com/resource/en/datasheet/vl53l1.pdf) sensor +- Input voltage sensor +- CAN connectors: 2 [UCANPHY Micro (JST-GH 4)](https://raccoonlabdev.github.io/docs/guide/wires/). + ## Configuration/Setup