AP_BoardConfig_CAN: add singleton and do naming cleanup

Also added more getter methods
This commit is contained in:
Francisco Ferreira 2018-07-18 07:24:11 +01:00
parent 1cfb38b4ee
commit 4b4ba66987
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
4 changed files with 122 additions and 102 deletions

View File

@ -44,64 +44,63 @@ const AP_Param::GroupInfo AP_BoardConfig_CAN::var_info[] = {
#if MAX_NUMBER_OF_CAN_INTERFACES > 0
// @Group: P1_
// @Path: ../AP_BoardConfig/canbus.cpp
AP_SUBGROUPINFO(_var_info_can[0], "P1_", 1, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_if_var_info),
// @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.cpp
AP_SUBGROUPINFO(_var_info_can[1], "P2_", 2, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_if_var_info),
// @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.cpp
AP_SUBGROUPINFO(_var_info_can[2], "P3_", 3, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_if_var_info),
// @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(_var_info_can_protocol[0], "D1_", 4, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_driver_var_info),
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(_var_info_can_protocol[1], "D2_", 5, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_driver_var_info),
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(_var_info_can_protocol[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::CAN_driver_var_info),
AP_SUBGROUPINFO(_drivers[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
#endif
AP_GROUPEND
};
int8_t AP_BoardConfig_CAN::_st_driver_number[MAX_NUMBER_OF_CAN_INTERFACES];
int8_t AP_BoardConfig_CAN::_st_can_debug[MAX_NUMBER_OF_CAN_INTERFACES];
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()
{
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++)
{
_st_driver_number[i] = (int8_t) _var_info_can[i]._driver_number;
_st_can_debug[i] = (int8_t) _var_info_can[i]._can_debug;
}
setup_canbus();
}
void AP_BoardConfig_CAN::setup_canbus(void)
{
// Create all drivers that we need
bool initret = true;
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 = _var_info_can[i]._driver_number;
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) {
@ -118,7 +117,7 @@ void AP_BoardConfig_CAN::setup_canbus(void)
// For this now existing driver (manager), start the physical interface
if (hal.can_mgr[drv_num - 1] != nullptr) {
initret &= hal.can_mgr[drv_num - 1]->begin(_var_info_can[i]._can_bitrate, i);
initret = initret && hal.can_mgr[drv_num - 1]->begin(_interfaces[i]._bitrate, i);
} else {
printf("Failed to initialize can interface %d\n\r", i + 1);
}
@ -127,26 +126,34 @@ void AP_BoardConfig_CAN::setup_canbus(void)
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 (_var_info_can_protocol[i]._protocol == UAVCAN_PROTOCOL_ENABLE) {
_var_info_can_protocol[i]._uavcan = new AP_UAVCAN;
if (prot_type == Protocol_Type_UAVCAN) {
_drivers[i]._driver = new AP_UAVCAN;
if (_var_info_can_protocol[i]._uavcan == nullptr) {
if (_drivers[i]._driver == nullptr) {
AP_HAL::panic("Failed to allocate uavcan %d\n\r", i + 1);
continue;
}
AP_Param::load_object_from_eeprom(_var_info_can_protocol[i]._uavcan, AP_UAVCAN::var_info);
AP_Param::load_object_from_eeprom(_drivers[i]._driver, AP_UAVCAN::var_info);
_var_info_can_protocol[i]._uavcan->init(i);
_drivers[i]._driver->init(i);
}
}
}
}
AP_BoardConfig_CAN& AP::can() {
return *AP_BoardConfig_CAN::get_singleton();
}
#endif

View File

@ -1,37 +1,87 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_BoardConfig.h"
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#if CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS //we don't have ioctls in ChibiOS
#include <sys/ioctl.h>
#endif
#if HAL_WITH_UAVCAN
#define UAVCAN_PROTOCOL_ENABLE 1
class AP_UAVCAN;
#if HAL_WITH_UAVCAN
#include <AP_Param/AP_Param.h>
class AP_BoardConfig_CAN {
public:
AP_BoardConfig_CAN() {
AP_Param::setup_object_defaults(this, var_info);
};
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,
};
void init(void);
// returns number of active CAN drivers
uint8_t get_num_drivers(void) { return _num_drivers; }
// return debug level for interface i
uint8_t get_debug_level(uint8_t i) {
if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
return _interfaces[i]._driver_number_cache ? _interfaces[i]._debug_level : 0;
}
return 0;
}
// return maximum level of debug of all interfaces
uint8_t get_debug_level(void) {
uint8_t ret = 0;
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
uint8_t dbg = get_debug_level(i);
ret = (dbg > ret) ? dbg : ret;
}
return ret;
}
// return maximum level of debug for driver index i
uint8_t get_debug_level_driver(uint8_t i) {
uint8_t ret = 0;
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;
}
}
return ret;
}
// return driver for index i
AP_HAL::CANProtocol* get_driver(uint8_t i) {
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) {
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[];
class CAN_if_var_info {
private:
class Interface {
friend class AP_BoardConfig_CAN;
public:
CAN_if_var_info()
{
Interface() {
AP_Param::setup_object_defaults(this, var_info);
}
@ -39,67 +89,35 @@ public:
private:
AP_Int8 _driver_number;
AP_Int8 _can_debug;
AP_Int32 _can_bitrate;
uint8_t _driver_number_cache;
AP_Int32 _bitrate;
AP_Int8 _debug_level;
};
class CAN_driver_var_info {
class Driver {
friend class AP_BoardConfig_CAN;
public:
CAN_driver_var_info() :
_uavcan(nullptr)
{
Driver() {
AP_Param::setup_object_defaults(this, var_info);
}
static const struct AP_Param::GroupInfo var_info[];
private:
AP_Int8 _protocol;
AP_UAVCAN* _uavcan;
AP_Int8 _protocol_type;
Protocol_Type _protocol_type_cache;
AP_HAL::CANProtocol* _driver;
};
// returns number of enabled CAN interfaces
static int8_t get_can_num_ifaces(void)
{
uint8_t ret = 0;
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
if (_st_driver_number[i]) {
ret++;
}
}
return ret;
}
static int8_t get_can_debug(uint8_t i)
{
if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
return _st_can_debug[i];
}
return 0;
}
// return maximum level of debug
static int8_t get_can_debug(void)
{
uint8_t ret = 0;
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
uint8_t dbg = get_can_debug(i);
ret = (dbg > ret) ? dbg : ret;
}
return ret;
}
CAN_if_var_info _var_info_can[MAX_NUMBER_OF_CAN_INTERFACES];
CAN_driver_var_info _var_info_can_protocol[MAX_NUMBER_OF_CAN_DRIVERS];
static int8_t _st_driver_number[MAX_NUMBER_OF_CAN_INTERFACES];
static int8_t _st_can_debug[MAX_NUMBER_OF_CAN_INTERFACES];
void setup_canbus(void);
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

View File

@ -14,26 +14,24 @@
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "AP_BoardConfig.h"
#if HAL_WITH_UAVCAN
#include "AP_BoardConfig_CAN.h"
#include <AP_UAVCAN/AP_UAVCAN.h>
// table of user settable CAN bus parameters
const AP_Param::GroupInfo AP_BoardConfig_CAN::CAN_driver_var_info::var_info[] = {
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: 0:Disabled,1:UAVCAN
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("PROTOCOL", 1, AP_BoardConfig_CAN::CAN_driver_var_info, _protocol, UAVCAN_PROTOCOL_ENABLE),
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::CAN_driver_var_info, AP_UAVCAN),
AP_SUBGROUPPTR(_driver, "UC_", 2, AP_BoardConfig_CAN::Driver, AP_UAVCAN),
AP_GROUPEND
};

View File

@ -14,36 +14,33 @@
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "AP_BoardConfig.h"
#if HAL_WITH_UAVCAN
#include "AP_BoardConfig_CAN.h"
#include <AP_UAVCAN/AP_UAVCAN.h>
// table of user settable CAN bus parameters
const AP_Param::GroupInfo AP_BoardConfig_CAN::CAN_if_var_info::var_info[] = {
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::CAN_if_var_info, _driver_number, HAL_CAN_DRIVER_DEFAULT, AP_PARAM_FLAG_ENABLE),
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::CAN_if_var_info, _can_bitrate, 1000000),
AP_GROUPINFO("BITRATE", 2, AP_BoardConfig_CAN::Interface, _bitrate, 1000000),
// @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::CAN_if_var_info, _can_debug, 2),
AP_GROUPINFO("DEBUG", 3, AP_BoardConfig_CAN::Interface, _debug_level, 1),
AP_GROUPEND
};