Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions docs/en/dronecan/ark_cannode.md
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter

On the ARK CANnode, you may need to configure the following parameters:

| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |

## LED Meanings

Expand Down
7 changes: 4 additions & 3 deletions docs/en/dronecan/ark_flow.md
Original file line number Diff line number Diff line change
Expand Up @@ -110,9 +110,10 @@ When optical flow is the only source of horizontal position/velocity, then lower

On the ARK Flow, you may need to configure the following parameters:

| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |

## LED Meanings

Expand Down
7 changes: 4 additions & 3 deletions docs/en/dronecan/ark_flow_mr.md
Original file line number Diff line number Diff line change
Expand Up @@ -105,9 +105,10 @@ Set the following parameters in _QGroundControl_:

You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself:

| Parameter | Description |
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |

## LED Meanings

Expand Down
10 changes: 9 additions & 1 deletion docs/en/dronecan/ark_gps.md
Original file line number Diff line number Diff line change
Expand Up @@ -91,9 +91,17 @@ If the sensor is not centred within the vehicle you will also need to define sen

- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus.
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity.

### ARK GPS Configuration

You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself:

| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |

## LED Meanings

You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly.
Expand Down
10 changes: 9 additions & 1 deletion docs/en/dronecan/ark_rtk_gps.md
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus.

### ARK RTK GPS Configuration

You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself:

| Parameter | Description |
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |

### Setting Up Rover and Fixed Base

Expand Down
9 changes: 9 additions & 0 deletions docs/en/dronecan/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,10 @@ If the DNA is still running and certain devices need to be manually configured,
::: info
The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter.
The parameter is set to 1 by default.

Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the
[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID.
Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID.
:::

:::warning
Expand Down Expand Up @@ -282,6 +286,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i

![QGC Parameter showing selected DroneCAN node](../../assets/can/dronecan/qgc_can_parameters.png)

Common CANNODE parameters that you can configure include:

- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information.
- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus.

## Device Specific Setup

Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation.
Expand Down
20 changes: 20 additions & 0 deletions docs/en/dronecan/px4_cannode_fw.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,26 @@ make ark_can-flow_default

This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware.

## Configuration

### Static Node ID

By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller.
However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter.

To configure a static node ID:

1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration)
2. Reboot the device

To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0.
Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior).

:::warning
When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID.
Configuring two devices with the same ID will cause communication conflicts.
:::

## Developer Information

This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot.
Expand Down
21 changes: 21 additions & 0 deletions src/drivers/uavcannode/UavcanNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -824,6 +824,27 @@ extern "C" int uavcannode_start(int argc, char *argv[])
}
}

// Read the static node ID parameter and use it if no valid node_id from shared memory
int32_t cannode_node_id = 0;
param_get(param_find("CANNODE_NODE_ID"), &cannode_node_id);

// Check if the static node ID is in range
if (cannode_node_id < 0 || cannode_node_id > 127) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (cannode_node_id < 0 || cannode_node_id > 127) {
if (cannode_node_id < 0 || cannode_node_id > uavcan::NodeID::Max) {

PX4_ERR("Invalid static node ID %ld, using dynamic allocation", cannode_node_id);
cannode_node_id = 0;
}

// Assign the static node ID if no dynamic allocation is used. Do wen't override a valid node ID from the bootloader?
if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= 127) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= 127) {
if (node_id == 0 && cannode_node_id > 0 && cannode_node_id <= uavcan::NodeID::Max) {

node_id = cannode_node_id;
}

// Persist the node ID for the bootloader
bootloader_app_shared_t shared_write = {};
shared_write.node_id = node_id;
shared_write.bus_speed = bitrate;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There's not really any error checking or validation on the bitrate, it might be safer to do this a bit later after the node has actually started spinning successfully.

For example you could do it here, and only if there was no dynamic node ID allocation. https://github.com/AlexKlimaj/PX4-Autopilot/blob/a4064072c793787aa9aac149c376bbf3c613d8b0/src/drivers/uavcannode/UavcanNode.cpp#L558-L580

bootloader_app_shared_write(&shared_write, BootLoader);

if (
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
board_booted_by_px4() &&
Expand Down
9 changes: 9 additions & 0 deletions src/drivers/uavcannode/uavcannode_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,15 @@
*
****************************************************************************/

/**
* UAVCAN CAN node ID (0 for dynamic allocation).
*
* @min 0
* @max 127
* @group UAVCAN
*/
PARAM_DEFINE_INT32(CANNODE_NODE_ID, 0);

/**
* UAVCAN CAN bus bitrate.
*
Expand Down
Loading