mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
BoardConfig_CAN: add parameters for serial port selection and timeout
This commit is contained in:
parent
5cefd251f9
commit
979a8dea6d
@ -89,7 +89,22 @@ const AP_Param::GroupInfo AP_BoardConfig_CAN::var_info[] = {
|
||||
// @Description: CAN Driver ID to be routed to SLCAN, 0 means no routing
|
||||
// @Range: 0 3
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SLCAN_RT", 7, AP_BoardConfig_CAN, _slcan_rt, 0),
|
||||
AP_GROUPINFO("SLCAN_RT", 7, AP_BoardConfig_CAN, _slcan_rt, 1),
|
||||
|
||||
// @Param: SLCAN_SR
|
||||
// @DisplayName: SLCAN Serial Port
|
||||
// @Description: Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial
|
||||
// @Range: 0 5
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SLCAN_SR", 8, AP_BoardConfig_CAN, _slcan_sr, -1),
|
||||
|
||||
|
||||
// @Param: SLCAN_TO
|
||||
// @DisplayName: SLCAN Timeout
|
||||
// @Description: Duration of inactivity after which SLCAN in seconds
|
||||
// @Range: 0 255
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SLCAN_TO", 9, AP_BoardConfig_CAN, _slcan_to, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -88,6 +88,9 @@ public:
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
int8_t get_slcan_serial() { return _slcan_sr; }
|
||||
uint8_t get_slcan_timeout() { return _slcan_to; }
|
||||
void reset_slcan_serial() { _slcan_sr.set_and_save_ifchanged(-1); }
|
||||
private:
|
||||
class Interface {
|
||||
friend class AP_BoardConfig_CAN;
|
||||
@ -131,6 +134,8 @@ private:
|
||||
Driver _drivers[MAX_NUMBER_OF_CAN_DRIVERS];
|
||||
uint8_t _num_drivers;
|
||||
AP_Int8 _slcan_rt;
|
||||
AP_Int8 _slcan_sr;
|
||||
AP_Int8 _slcan_to;
|
||||
static AP_BoardConfig_CAN *_singleton;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user