Skip to content

Commit

Permalink
AP_DroneCAN: support CAN serial ports
Browse files Browse the repository at this point in the history
this allows any serial protocol to be mapped to a remote DroneCAN node
  • Loading branch information
tridge committed Nov 18, 2023
1 parent 7f55b94 commit de8ced1
Show file tree
Hide file tree
Showing 4 changed files with 425 additions and 1 deletion.
112 changes: 111 additions & 1 deletion libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@
#include <AP_Mount/AP_Mount_Xacti.h>
#include <string.h>

#if AP_DRONECAN_SERIAL_ENABLED
#include "AP_DroneCAN_serial.h"
#endif

extern const AP_HAL::HAL& hal;

// setup default pool size
Expand Down Expand Up @@ -148,7 +152,105 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = {
// @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32
// @User: Advanced
AP_GROUPINFO("ESC_RV", 9, AP_DroneCAN, _esc_rv, 0),


#if AP_DRONECAN_SERIAL_ENABLED
/*
due to the parameter tree depth limitation we can't use a sub-table for the serial parameters
*/

// @Param: SER_EN
// @DisplayName: Serial enable
// @Description: Enable DroneCAN virtual serial ports
// @Values: 0:Disabled, 1:Enabled
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO_FLAGS("SER_EN", 10, AP_DroneCAN, serial.enable, 0, AP_PARAM_FLAG_ENABLE),

// @Param: S1_NOD
// @DisplayName: Serial CAN node number
// @Description: CAN node number for serial port
// @Range: 0 127
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("S1_NOD", 11, AP_DroneCAN, serial.ports[0].node, 0),

// @Param: S1_IDX
// @DisplayName: Serial1 index
// @Description: Serial port number on remote CAN node
// @Range: 0 100
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("S1_IDX", 12, AP_DroneCAN, serial.ports[0].idx, 0),

// @Param: S1_BD
// @DisplayName: Serial default baud rate
// @Description: Serial baud rate on remote CAN node
// @CopyFieldsFrom: SERIAL0_BAUD
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("S1_BD", 13, AP_DroneCAN, serial.ports[0].state.baud, 57600),

// @Param: S1_PRO
// @DisplayName: Serial protocol
// @Description: Serial protocol
// @CopyFieldsFrom: SERIAL0_PROTOCOL
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO("S1_PRO", 14, AP_DroneCAN, serial.ports[0].state.protocol, -1),

#if AP_DRONECAN_SERIAL_NUM_PORTS > 1
// @Param: S2_NOD
// @DisplayName: S2_NOD
// @Description: CAN node number for serial port
// @CopyFieldsFrom: CAN_D1_UC_S1_NOD
AP_GROUPINFO("S2_NOD", 15, AP_DroneCAN, serial.ports[1].node, 0),

// @Param: S2_IDX
// @DisplayName: S2_IDX
// @Description: Serial port number on remote CAN node
// @CopyFieldsFrom: CAN_D1_UC_S1_IDX
AP_GROUPINFO("S2_IDX", 16, AP_DroneCAN, serial.ports[1].idx, 0),

// @Param: S2_BD
// @DisplayName: S2_BD
// @Description: Serial baud rate on remote CAN node
// @CopyFieldsFrom: CAN_D1_UC_S1_BD
AP_GROUPINFO("S2_BD", 17, AP_DroneCAN, serial.ports[1].state.baud, 57600),

// @Param: S2_PRO
// @DisplayName: S2_PRO
// @Description: Serial protocol
// @CopyFieldsFrom: CAN_D1_UC_S1_PRO
AP_GROUPINFO("S2_PRO", 18, AP_DroneCAN, serial.ports[1].state.protocol, -1),
#endif

#if AP_DRONECAN_SERIAL_NUM_PORTS > 2
// @Param: S3_NOD
// @DisplayName: S3_NOD
// @Description: CAN node number for serial port
// @CopyFieldsFrom: CAN_D1_UC_S1_NOD
AP_GROUPINFO("S3_NOD", 19, AP_DroneCAN, serial.ports[2].node, 0),

// @Param: S3_IDX
// @DisplayName: S3_IDX
// @Description: Serial port number on remote CAN node
// @CopyFieldsFrom: CAN_D1_UC_S1_IDX
AP_GROUPINFO("S3_IDX", 20, AP_DroneCAN, serial.ports[2].idx, 0),

// @Param: S3_BD
// @DisplayName: S3_BD
// @Description: Serial baud rate on remote CAN node
// @CopyFieldsFrom: CAN_D1_UC_S1_BD
AP_GROUPINFO("S3_BD", 21, AP_DroneCAN, serial.ports[2].state.baud, 57600),

// @Param: S3_PRO
// @DisplayName: S3_PRO
// @Description: Serial protocol
// @CopyFieldsFrom: CAN_D1_UC_S1_PRO
AP_GROUPINFO("S3_PRO", 22, AP_DroneCAN, serial.ports[2].state.protocol, -1),
#endif
#endif // AP_DRONECAN_SERIAL_ENABLED

AP_GROUPEND
};

Expand Down Expand Up @@ -369,6 +471,10 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
return;
}

#if AP_DRONECAN_SERIAL_ENABLED
serial.init(this);
#endif

_initialized = true;
debug_dronecan(AP_CANManager::LOG_INFO, "DroneCAN: init done\n\r");
}
Expand Down Expand Up @@ -421,6 +527,10 @@ void AP_DroneCAN::loop(void)
}
}
}

#if AP_DRONECAN_SERIAL_ENABLED
serial.update();
#endif
}
}

Expand Down
13 changes: 13 additions & 0 deletions libraries/AP_DroneCAN/AP_DroneCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "AP_DroneCAN_DNA_Server.h"
#include <canard.h>
#include <dronecan_msgs.h>
#include <AP_SerialManager/AP_SerialManager_config.h>

#ifndef DRONECAN_SRV_NUMBER
#define DRONECAN_SRV_NUMBER NUM_SERVO_CHANNELS
Expand All @@ -58,6 +59,14 @@
#define AP_DRONECAN_HIMARK_SERVO_SUPPORT (BOARD_FLASH_SIZE>1024)
#endif

#ifndef AP_DRONECAN_SERIAL_ENABLED
#define AP_DRONECAN_SERIAL_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024)
#endif

#if AP_DRONECAN_SERIAL_ENABLED
#include "AP_DroneCAN_serial.h"
#endif

// fwd-declare callback classes
class AP_DroneCAN_DNA_Server;

Expand Down Expand Up @@ -258,6 +267,10 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend {

CanardInterface canard_iface;

#if AP_DRONECAN_SERIAL_ENABLED
AP_DroneCAN_Serial serial;
#endif

Canard::Publisher<uavcan_protocol_NodeStatus> node_status{canard_iface};
Canard::Publisher<dronecan_protocol_CanStats> can_stats{canard_iface};
Canard::Publisher<dronecan_protocol_Stats> protocol_stats{canard_iface};
Expand Down
Loading

0 comments on commit de8ced1

Please sign in to comment.