# Setup Guide

## Mounting​&#x20;

The recommended mounting orientation is with the connectors on the board pointing toward the back of the vehicle, as shown in the following picture.

<figure><img src="https://2367252986-files.gitbook.io/~/files/v0/b/gitbook-x-prod.appspot.com/o/spaces%2FLIgtGDAvVGkCKGOJb1bR%2Fuploads%2FRI9OP6CJkgaC0cJScXcy%2Fflow_mount1.png?alt=media&#x26;token=63fce5c8-6531-41e4-bd0c-ab99edbb60cf" alt=""><figcaption></figcaption></figure>

This corresponds to the default value (0) of the parameter SENS\_FLOW\_ROT. Change the parameter appropriately if using a different orientation. The sensor can be mounted anywhere on the frame, but you will need to specify the focal point position, relative to the vehicle's center of gravity,  during PX4 configuration.

## PX4 Configuration&#x20;

1. Connect H-FLOW to CAN port
2. Set the following parameters:

* Enable optical flow fusion by setting [EKF2\_OF\_CTRL](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_OF_CTRL).
* To optionally disable GPS aiding, set [EKF2\_GPS\_CTRL](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_GPS_CTRL) to `0`.
* Enable [UAVCAN\_SUB\_FLOW](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#UAVCAN_SUB_FLOW).
* Enable [UAVCAN\_SUB\_RNG](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#UAVCAN_SUB_RNG).
* Set [EKF2\_RNG\_A\_HMAX](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_RNG_A_HMAX) to `10`.
* Set [EKF2\_RNG\_QLTY\_T](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_RNG_QLTY_T) to `0.2`.
* Set [UAVCAN\_RNG\_MIN](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#UAVCAN_RNG_MIN) to `0.08` (minimum range is 80mm)
* Set [UAVCAN\_RNG\_MAX](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#UAVCAN_RNG_MAX) to `30` (max range is 30m)
* Set [SENS\_FLOW\_MINHGT](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#SENS_FLOW_MINHGT) to `0.08`.
* Set [SENS\_FLOW\_MAXHGT](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#SENS_FLOW_MAXHGT) to `30`.
* Set [SENS\_FLOW\_MAXR](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#SENS_FLOW_MAXR) to `7.4`match the PAW3902 maximum angular flow rate.
* The parameters [EKF2\_OF\_POS\_X](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_OF_POS_X), [EKF2\_OF\_POS\_Y](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_OF_POS_Y), and [EKF2\_OF\_POS\_Z](https://docs.px4.io/main/en/advanced_config/parameter_reference.html#EKF2_OF_POS_Z) can be set to account for the offset of the H-Flow from the vehicle centre of gravity.

3. Reboot

After connecting the sensor to the controller, connect it to the controller using QGroundControl. Open the MAVLink Inspector screen for DISTANCE\_SENSOR. If the sensor is OK, you can see that the current\_distance number is non-zero.

<figure><img src="https://2367252986-files.gitbook.io/~/files/v0/b/gitbook-x-prod.appspot.com/o/spaces%2FLIgtGDAvVGkCKGOJb1bR%2Fuploads%2FqUZJ93dBd4ZfYzmAVT9w%2Fflow_qgc_insp.png?alt=media&#x26;token=e2b2aeff-05a3-4739-b895-58523af5c4cf" alt=""><figcaption></figcaption></figure>

Refer to link below for the latest PX4 Optical Flow setup info

{% embed url="<https://docs.px4.io/main/en/sensor/optical_flow.html>" %}

## Ardupilot Setup Guide

1. Connect H-FLOW to CAN port
2. Set the following parameters:

* FLOW\_TYPE = 6 (DroneCAN)
* CAN\_P1\_DRIVER = 1&#x20;
* CAN\_D1\_PROTOCOL = 1&#x20;
* RNGFND1\_TYPE = 24
* RNGFND1\_MAX\_CM = 3000 (max range 30m）
* EK3\_SRC\_OPTIONS = 0 (disable FuseALLVelocities）
* EK3\_FLOW\_DELAY (default)
* EK3\_SRC1\_POSXY = 0 (use optical flow)
* EK3\_SRC1\_VELXY = 5
* EK3\_SRC1\_POSZ = 1
* EK3\_SRC1\_VELZ = 0
* EK3\_SRC1\_YAW = 1
* FLOW\_POS\_X, FLOW\_POS\_Y, FLOW\_POS\_Z (H-FLOW position offsets based on its mounting position)

3. Reboot

After connecting the sensor to the controller, connect the controller to Mission Planner and open the Status tab of the Flight Data screen. If the sensor is operational, you should see non-zero opt\_m\_x, opt\_m\_y, and opt\_qua values.

<figure><img src="https://2367252986-files.gitbook.io/~/files/v0/b/gitbook-x-prod.appspot.com/o/spaces%2FLIgtGDAvVGkCKGOJb1bR%2Fuploads%2F9pqWv44rmSVtsWgS5Ynx%2Fflow_mp_insp.png?alt=media&#x26;token=dfca7168-b745-468f-8a8c-939972c6eb0b" alt=""><figcaption></figcaption></figure>

Refer to link below for the latest Ardupilot Optical Flow setup info

{% embed url="<https://ardupilot.org/copter/docs/common-optical-flow-sensor-setup.html>" %}


---

# Agent Instructions: Querying This Documentation

If you need additional information that is not directly available in this page, you can query the documentation dynamically by asking a question.

Perform an HTTP GET request on the current page URL with the `ask` query parameter:

```
GET https://docs.holybro.com/peripherals/h-flow-dronecan/setup-guide.md?ask=<question>
```

The question should be specific, self-contained, and written in natural language.
The response will contain a direct answer to the question and relevant excerpts and sources from the documentation.

Use this mechanism when the answer is not explicitly present in the current page, you need clarification or additional context, or you want to retrieve related documentation sections.
