mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_BoardConfig: split SLCAN Interface params to there own class
This commit is contained in:
parent
70da885214
commit
2c0521654c
@ -84,27 +84,7 @@ const AP_Param::GroupInfo AP_BoardConfig_CAN::var_info[] = {
|
||||
AP_SUBGROUPINFO(_drivers[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
|
||||
#endif
|
||||
|
||||
// @Param: SLCAN_RT
|
||||
// @DisplayName: SLCAN Route
|
||||
// @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, 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_SUBGROUPINFO(_slcan, "SLCAN_", 7, AP_BoardConfig_CAN, AP_BoardConfig_CAN::SLCAN_Interface),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
@ -147,7 +127,7 @@ void AP_BoardConfig_CAN::init()
|
||||
if (hal.can_mgr[drv_num - 1] != nullptr) {
|
||||
initret = initret && hal.can_mgr[drv_num - 1]->begin(_interfaces[i]._bitrate, i);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
if (_slcan_rt == (i+1) && hal.can_mgr[drv_num - 1] != nullptr ) {
|
||||
if (_slcan._can_port == (i+1) && hal.can_mgr[drv_num - 1] != nullptr ) {
|
||||
ChibiOS_CAN::CanDriver* drv = (ChibiOS_CAN::CanDriver*)hal.can_mgr[drv_num - 1]->get_driver();
|
||||
slcan_router().init(drv->getIface(i), drv->getUpdateEvent());
|
||||
}
|
||||
@ -201,7 +181,7 @@ void AP_BoardConfig_CAN::init()
|
||||
} else {
|
||||
continue;
|
||||
}
|
||||
if (_slcan_rt == 0) {
|
||||
if (_slcan._can_port == 0) {
|
||||
_drivers[i]._driver->init(i, true);
|
||||
} else {
|
||||
_drivers[i]._driver->init(i, false);
|
||||
|
@ -88,9 +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); }
|
||||
int8_t get_slcan_serial() { return _slcan._ser_port; }
|
||||
uint8_t get_slcan_timeout() { return _slcan._timeout; }
|
||||
void reset_slcan_serial() { _slcan._ser_port.set_and_save_ifchanged(-1); }
|
||||
private:
|
||||
class Interface {
|
||||
friend class AP_BoardConfig_CAN;
|
||||
@ -130,12 +130,26 @@ private:
|
||||
AP_HAL::CANProtocol* _tcan;
|
||||
};
|
||||
|
||||
class SLCAN_Interface {
|
||||
friend class AP_BoardConfig_CAN;
|
||||
|
||||
public:
|
||||
SLCAN_Interface() {
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_Int8 _can_port;
|
||||
AP_Int8 _ser_port;
|
||||
AP_Int16 _timeout;
|
||||
};
|
||||
|
||||
Interface _interfaces[MAX_NUMBER_OF_CAN_INTERFACES];
|
||||
Driver _drivers[MAX_NUMBER_OF_CAN_DRIVERS];
|
||||
SLCAN_Interface _slcan;
|
||||
uint8_t _num_drivers;
|
||||
AP_Int8 _slcan_rt;
|
||||
AP_Int8 _slcan_sr;
|
||||
AP_Int8 _slcan_to;
|
||||
static AP_BoardConfig_CAN *_singleton;
|
||||
};
|
||||
|
||||
|
49
libraries/AP_BoardConfig/canbus_slcan.cpp
Normal file
49
libraries/AP_BoardConfig/canbus_slcan.cpp
Normal file
@ -0,0 +1,49 @@
|
||||
/*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#include "AP_BoardConfig_CAN.h"
|
||||
|
||||
const AP_Param::GroupInfo AP_BoardConfig_CAN::SLCAN_Interface::var_info[] = {
|
||||
// @Param: CPORT
|
||||
// @DisplayName: SLCAN Route
|
||||
// @Description: CAN Driver ID to be routed to SLCAN, 0 means no routing
|
||||
// @Values: 0:Disabled,1:First driver,2:Second driver
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("CPORT", 1, AP_BoardConfig_CAN::SLCAN_Interface, _can_port, 1),
|
||||
|
||||
// @Param: SERNUM
|
||||
// @DisplayName: SLCAN Serial Port
|
||||
// @Description: Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial
|
||||
// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("SERNUM", 2, AP_BoardConfig_CAN::SLCAN_Interface, _ser_port, -1),
|
||||
|
||||
|
||||
// @Param: TIMOUT
|
||||
// @DisplayName: SLCAN Timeout
|
||||
// @Description: Duration of inactivity after which SLCAN in seconds
|
||||
// @Range: 0 32767
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TIMOUT", 3, AP_BoardConfig_CAN::SLCAN_Interface, _timeout, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user