Browse Source

AP_BoardConfig: remove CAN management from BoardConfig

zr-v5.1
Siddharth Purohit 5 years ago committed by Andrew Tridgell
parent
commit
ad2a63e173
  1. 7
      libraries/AP_BoardConfig/AP_BoardConfig.cpp
  2. 226
      libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp
  3. 163
      libraries/AP_BoardConfig/AP_BoardConfig_CAN.h
  4. 55
      libraries/AP_BoardConfig/canbus_driver.cpp
  5. 50
      libraries/AP_BoardConfig/canbus_interface.cpp
  6. 47
      libraries/AP_BoardConfig/canbus_slcan.cpp

7
libraries/AP_BoardConfig/AP_BoardConfig.cpp

@ -24,13 +24,6 @@ @@ -24,13 +24,6 @@
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#if HAL_WITH_UAVCAN
#include <AP_UAVCAN/AP_UAVCAN.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_HAL_Linux/CAN.h>
#endif
#endif
#include <stdio.h>
#ifndef BOARD_TYPE_DEFAULT

226
libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp

@ -1,226 +0,0 @@ @@ -1,226 +0,0 @@
/*
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/>.
*/
/*
* AP_BoardConfig_CAN - board specific configuration for CAN interface
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "AP_BoardConfig.h"
#include "AP_BoardConfig_CAN.h"
#if HAL_WITH_UAVCAN
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_HAL_Linux/CAN.h>
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <AP_HAL_ChibiOS/CAN.h>
#include <AP_HAL_ChibiOS/CANSerialRouter.h>
#endif
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_UAVCAN/AP_UAVCAN_SLCAN.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_KDECAN/AP_KDECAN.h>
#include <AP_ToshibaCAN/AP_ToshibaCAN.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
extern const AP_HAL::HAL& hal;
// table of user settable parameters
const AP_Param::GroupInfo AP_BoardConfig_CAN::var_info[] = {
#if MAX_NUMBER_OF_CAN_INTERFACES > 0
// @Group: P1_
// @Path: ../AP_BoardConfig/canbus_interface.cpp
AP_SUBGROUPINFO(_interfaces[0], "P1_", 1, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Interface),
#endif
#if MAX_NUMBER_OF_CAN_INTERFACES > 1
// @Group: P2_
// @Path: ../AP_BoardConfig/canbus_interface.cpp
AP_SUBGROUPINFO(_interfaces[1], "P2_", 2, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Interface),
#endif
#if MAX_NUMBER_OF_CAN_INTERFACES > 2
// @Group: P3_
// @Path: ../AP_BoardConfig/canbus_interface.cpp
AP_SUBGROUPINFO(_interfaces[2], "P3_", 3, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Interface),
#endif
#if MAX_NUMBER_OF_CAN_DRIVERS > 0
// @Group: D1_
// @Path: ../AP_BoardConfig/canbus_driver.cpp
AP_SUBGROUPINFO(_drivers[0], "D1_", 4, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
#endif
#if MAX_NUMBER_OF_CAN_DRIVERS > 1
// @Group: D2_
// @Path: ../AP_BoardConfig/canbus_driver.cpp
AP_SUBGROUPINFO(_drivers[1], "D2_", 5, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
#endif
#if MAX_NUMBER_OF_CAN_DRIVERS > 2
// @Group: D3_
// @Path: ../AP_BoardConfig/canbus_driver.cpp
AP_SUBGROUPINFO(_drivers[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
#endif
#if AP_UAVCAN_SLCAN_ENABLED
// @Group: SLCAN_
// @Path: ../AP_BoardConfig/canbus_slcan.cpp
AP_SUBGROUPINFO(_slcan, "SLCAN_", 7, AP_BoardConfig_CAN, AP_BoardConfig_CAN::SLCAN_Interface),
#endif
AP_GROUPEND
};
AP_BoardConfig_CAN *AP_BoardConfig_CAN::_singleton;
AP_BoardConfig_CAN::AP_BoardConfig_CAN()
{
AP_Param::setup_object_defaults(this, var_info);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_singleton != nullptr) {
AP_HAL::panic("AP_BoardConfig_CAN must be singleton");
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
_singleton = this;
}
void AP_BoardConfig_CAN::init()
{
// Create all drivers that we need
bool initret = true;
#if AP_UAVCAN_SLCAN_ENABLED
reset_slcan_serial();
#endif
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
// Check the driver number assigned to this physical interface
uint8_t drv_num = _interfaces[i]._driver_number_cache = _interfaces[i]._driver_number;
if (drv_num != 0 && drv_num <= MAX_NUMBER_OF_CAN_DRIVERS) {
if (hal.can_mgr[drv_num - 1] == nullptr) {
// CAN Manager is the driver
// So if this driver was not created before for other physical interface - do it
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new Linux::CANManager;
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
const_cast <AP_HAL::HAL&> (hal).can_mgr[drv_num - 1] = new ChibiOS::CANManager;
#endif
}
// For this now existing driver (manager), start the physical interface
if (hal.can_mgr[drv_num - 1] != nullptr) {
initret = initret && hal.can_mgr[drv_num - 1]->begin(_interfaces[i]._bitrate, i);
#if AP_UAVCAN_SLCAN_ENABLED
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();
ChibiOS_CAN::CanIface::slcan_router().init(drv->getIface(i), drv->getUpdateEvent());
}
#endif
} else {
printf("Failed to initialize can interface %d\n\r", i + 1);
}
}
}
if (initret) {
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
Protocol_Type prot_type = _drivers[i]._protocol_type_cache = (Protocol_Type) _drivers[i]._protocol_type.get();
if (hal.can_mgr[i] == nullptr) {
continue;
}
_num_drivers = i + 1;
hal.can_mgr[i]->initialized(true);
printf("can_mgr %d initialized well\n\r", i + 1);
if (prot_type == Protocol_Type_UAVCAN) {
_drivers[i]._driver = _drivers[i]._uavcan = new AP_UAVCAN;
if (_drivers[i]._driver == nullptr) {
AP_HAL::panic("Failed to allocate uavcan %d\n\r", i + 1);
continue;
}
AP_Param::load_object_from_eeprom(_drivers[i]._uavcan, AP_UAVCAN::var_info);
} else if (prot_type == Protocol_Type_KDECAN) {
// To be replaced with macro saying if KDECAN library is included
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
_drivers[i]._driver = _drivers[i]._kdecan = new AP_KDECAN;
if (_drivers[i]._driver == nullptr) {
AP_HAL::panic("Failed to allocate KDECAN %d\n\r", i + 1);
continue;
}
AP_Param::load_object_from_eeprom(_drivers[i]._kdecan, AP_KDECAN::var_info);
#endif
} else if (prot_type == Protocol_Type_ToshibaCAN) {
_drivers[i]._driver = _drivers[i]._tcan = new AP_ToshibaCAN;
if (_drivers[i]._driver == nullptr) {
AP_BoardConfig::config_error("ToshibaCAN init failed");
continue;
}
#if HAL_PICCOLO_CAN_ENABLE
} else if (prot_type == Protocol_Type_PiccoloCAN) {
_drivers[i]._driver = _drivers[i]._pcan = new AP_PiccoloCAN;
if (_drivers[i]._driver == nullptr) {
AP_BoardConfig::config_error("PiccoloCAN init failed");
continue;
}
#endif
} else {
continue;
}
#if AP_UAVCAN_SLCAN_ENABLED
if (_slcan._can_port == 0) {
_drivers[i]._driver->init(i, true);
} else {
_drivers[i]._driver->init(i, false);
}
#else
_drivers[i]._driver->init(i, true);
#endif
}
}
// param count could have changed
AP_Param::invalidate_count();
}
#if AP_UAVCAN_SLCAN_ENABLED
AP_HAL::UARTDriver *AP_BoardConfig_CAN::get_slcan_serial()
{
if (_slcan._ser_port != -1) {
return AP::serialmanager().get_serial_by_id(_slcan._ser_port);
}
AP_HAL::UARTDriver *ser_port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLCAN, 0);
if (ser_port != nullptr) {
if (ser_port->is_initialized()) {
return ser_port;
}
}
return nullptr;
}
#endif
AP_BoardConfig_CAN& AP::can() {
return *AP_BoardConfig_CAN::get_singleton();
}
#endif

163
libraries/AP_BoardConfig/AP_BoardConfig_CAN.h

@ -1,163 +0,0 @@ @@ -1,163 +0,0 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#if HAL_WITH_UAVCAN
#include <AP_Param/AP_Param.h>
#ifndef AP_CAN_DEBUG
#define AP_CAN_DEBUG 0
#endif
class AP_BoardConfig_CAN {
public:
AP_BoardConfig_CAN();
/* Do not allow copies */
AP_BoardConfig_CAN(const AP_BoardConfig_CAN &other) = delete;
AP_BoardConfig_CAN &operator=(const AP_BoardConfig_CAN&) = delete;
static AP_BoardConfig_CAN* get_singleton() {
return _singleton;
}
enum Protocol_Type : uint8_t {
Protocol_Type_None = 0,
Protocol_Type_UAVCAN = 1,
Protocol_Type_KDECAN = 2,
Protocol_Type_ToshibaCAN = 3,
Protocol_Type_PiccoloCAN = 4,
};
void init(void);
// returns number of active CAN drivers
uint8_t get_num_drivers(void) const { return _num_drivers; }
// return debug level for interface i
uint8_t get_debug_level(uint8_t i) const {
#if AP_CAN_DEBUG
if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
return _interfaces[i]._driver_number_cache ? _interfaces[i]._debug_level : 0;
}
#endif
return 0;
}
// return maximum level of debug of all interfaces
uint8_t get_debug_level(void) const {
uint8_t ret = 0;
#if AP_CAN_DEBUG
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
uint8_t dbg = get_debug_level(i);
ret = (dbg > ret) ? dbg : ret;
}
#endif
return ret;
}
// return maximum level of debug for driver index i
uint8_t get_debug_level_driver(uint8_t i) const {
uint8_t ret = 0;
#if AP_CAN_DEBUG
for (uint8_t j = 0; j < MAX_NUMBER_OF_CAN_INTERFACES; j++) {
if (_interfaces[j]._driver_number_cache == i) {
uint8_t dbg = get_debug_level(j);
ret = (dbg > ret) ? dbg : ret;
}
}
#endif
return ret;
}
// return driver for index i
AP_HAL::CANProtocol* get_driver(uint8_t i) const {
if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
return _drivers[i]._driver;
}
return nullptr;
}
// return protocol type index i
Protocol_Type get_protocol_type(uint8_t i) const {
if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
return _drivers[i]._protocol_type_cache;
}
return Protocol_Type_None;
}
static const struct AP_Param::GroupInfo var_info[];
#if AP_UAVCAN_SLCAN_ENABLED
AP_HAL::UARTDriver *get_slcan_serial();
uint8_t get_slcan_timeout() { return _slcan._timeout; }
void reset_slcan_serial() { _slcan._ser_port.set_and_save_ifchanged(-1); }
#endif
private:
class Interface {
friend class AP_BoardConfig_CAN;
public:
Interface() {
AP_Param::setup_object_defaults(this, var_info);
}
static const struct AP_Param::GroupInfo var_info[];
private:
AP_Int8 _driver_number;
uint8_t _driver_number_cache;
AP_Int32 _bitrate;
#if AP_CAN_DEBUG
AP_Int8 _debug_level;
#endif
};
class Driver {
friend class AP_BoardConfig_CAN;
public:
Driver() {
AP_Param::setup_object_defaults(this, var_info);
}
static const struct AP_Param::GroupInfo var_info[];
private:
AP_Int8 _protocol_type;
Protocol_Type _protocol_type_cache;
AP_HAL::CANProtocol* _driver;
AP_HAL::CANProtocol* _uavcan; // UAVCAN
AP_HAL::CANProtocol* _kdecan; // KDECAN
AP_HAL::CANProtocol* _tcan; // ToshibaCAN
AP_HAL::CANProtocol* _pcan; // PiccoloCAN
};
#if AP_UAVCAN_SLCAN_ENABLED
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;
};
SLCAN_Interface _slcan;
#endif
Interface _interfaces[MAX_NUMBER_OF_CAN_INTERFACES];
Driver _drivers[MAX_NUMBER_OF_CAN_DRIVERS];
uint8_t _num_drivers;
static AP_BoardConfig_CAN *_singleton;
};
namespace AP {
AP_BoardConfig_CAN& can();
}
#endif

55
libraries/AP_BoardConfig/canbus_driver.cpp

@ -1,55 +0,0 @@ @@ -1,55 +0,0 @@
/*
* 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"
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_ToshibaCAN/AP_ToshibaCAN.h>
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
// To be replaced with macro saying if KDECAN library is included
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#include <AP_KDECAN/AP_KDECAN.h>
#endif
// table of user settable CAN bus parameters
const AP_Param::GroupInfo AP_BoardConfig_CAN::Driver::var_info[] = {
// @Param: PROTOCOL
// @DisplayName: Enable use of specific protocol over virtual driver
// @Description: Enabling this option starts selected protocol that will use this virtual driver
// @Values{Copter,Plane,Sub}: 0:Disabled,1:UAVCAN,2:KDECAN,3:ToshibaCAN,4:PiccoloCAN
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("PROTOCOL", 1, AP_BoardConfig_CAN::Driver, _protocol_type, AP_BoardConfig_CAN::Protocol_Type_UAVCAN),
// @Group: UC_
// @Path: ../AP_UAVCAN/AP_UAVCAN.cpp
AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_BoardConfig_CAN::Driver, AP_UAVCAN),
// To be replaced with macro saying if KDECAN library is included
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
// @Group: KDE_
// @Path: ../AP_KDECAN/AP_KDECAN.cpp
AP_SUBGROUPPTR(_kdecan, "KDE_", 3, AP_BoardConfig_CAN::Driver, AP_KDECAN),
#endif
AP_GROUPEND
};
#endif

50
libraries/AP_BoardConfig/canbus_interface.cpp

@ -1,50 +0,0 @@ @@ -1,50 +0,0 @@
/*
* 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"
// table of user settable CAN bus parameters
const AP_Param::GroupInfo AP_BoardConfig_CAN::Interface::var_info[] = {
// @Param: DRIVER
// @DisplayName: Index of virtual driver to be used with physical CAN interface
// @Description: Enabling this option enables use of CAN buses.
// @Values: 0:Disabled,1:First driver,2:Second driver
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO_FLAGS("DRIVER", 1, AP_BoardConfig_CAN::Interface, _driver_number, HAL_CAN_DRIVER_DEFAULT, AP_PARAM_FLAG_ENABLE),
// @Param: BITRATE
// @DisplayName: Bitrate of CAN interface
// @Description: Bit rate can be set up to from 10000 to 1000000
// @Range: 10000 1000000
// @User: Advanced
AP_GROUPINFO("BITRATE", 2, AP_BoardConfig_CAN::Interface, _bitrate, 1000000),
#if AP_CAN_DEBUG
// @Param: DEBUG
// @DisplayName: Level of debug for CAN devices
// @Description: Enabling this option will provide debug messages
// @Values: 0:Disabled,1:Major messages,2:All messages
// @User: Advanced
AP_GROUPINFO("DEBUG", 3, AP_BoardConfig_CAN::Interface, _debug_level, 1),
#endif
AP_GROUPEND
};
#endif

47
libraries/AP_BoardConfig/canbus_slcan.cpp

@ -1,47 +0,0 @@ @@ -1,47 +0,0 @@
/*
* 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 AP_UAVCAN_SLCAN_ENABLED
#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, 0),
// @Param: SERNUM
// @DisplayName: SLCAN Serial Port
// @Description: Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial. This parameter is automatically reset on reboot or on timeout. See CAN_SLCAN_TIMOUT for timeout details
// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
// @User: Standard
AP_GROUPINFO("SERNUM", 2, AP_BoardConfig_CAN::SLCAN_Interface, _ser_port, -1),
// @Param: TIMOUT
// @DisplayName: SLCAN Timeout
// @Description: Duration of inactivity after which SLCAN is switched back to original protocol in seconds.
// @Range: 0 32767
// @User: Standard
AP_GROUPINFO("TIMOUT", 3, AP_BoardConfig_CAN::SLCAN_Interface, _timeout, 0),
AP_GROUPEND
};
#endif
Loading…
Cancel
Save