mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -04:00
AP_BoardConfig_CAN: const some accessors
This commit is contained in:
parent
f8e49e5438
commit
f2e31bb880
@ -32,10 +32,10 @@ public:
|
|||||||
void init(void);
|
void init(void);
|
||||||
|
|
||||||
// returns number of active CAN drivers
|
// returns number of active CAN drivers
|
||||||
uint8_t get_num_drivers(void) { return _num_drivers; }
|
uint8_t get_num_drivers(void) const { return _num_drivers; }
|
||||||
|
|
||||||
// return debug level for interface i
|
// return debug level for interface i
|
||||||
uint8_t get_debug_level(uint8_t i) {
|
uint8_t get_debug_level(uint8_t i) const {
|
||||||
#if AP_CAN_DEBUG
|
#if AP_CAN_DEBUG
|
||||||
if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
|
if (i < MAX_NUMBER_OF_CAN_INTERFACES) {
|
||||||
return _interfaces[i]._driver_number_cache ? _interfaces[i]._debug_level : 0;
|
return _interfaces[i]._driver_number_cache ? _interfaces[i]._debug_level : 0;
|
||||||
@ -45,7 +45,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return maximum level of debug of all interfaces
|
// return maximum level of debug of all interfaces
|
||||||
uint8_t get_debug_level(void) {
|
uint8_t get_debug_level(void) const {
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
#if AP_CAN_DEBUG
|
#if AP_CAN_DEBUG
|
||||||
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
|
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
|
||||||
@ -57,7 +57,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return maximum level of debug for driver index i
|
// return maximum level of debug for driver index i
|
||||||
uint8_t get_debug_level_driver(uint8_t i) {
|
uint8_t get_debug_level_driver(uint8_t i) const {
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
#if AP_CAN_DEBUG
|
#if AP_CAN_DEBUG
|
||||||
for (uint8_t j = 0; j < MAX_NUMBER_OF_CAN_INTERFACES; j++) {
|
for (uint8_t j = 0; j < MAX_NUMBER_OF_CAN_INTERFACES; j++) {
|
||||||
@ -71,7 +71,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return driver for index i
|
// return driver for index i
|
||||||
AP_HAL::CANProtocol* get_driver(uint8_t i) {
|
AP_HAL::CANProtocol* get_driver(uint8_t i) const {
|
||||||
if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
|
if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
|
||||||
return _drivers[i]._driver;
|
return _drivers[i]._driver;
|
||||||
}
|
}
|
||||||
@ -79,7 +79,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return protocol type index i
|
// return protocol type index i
|
||||||
Protocol_Type get_protocol_type(uint8_t i) {
|
Protocol_Type get_protocol_type(uint8_t i) const {
|
||||||
if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
|
if (i < MAX_NUMBER_OF_CAN_DRIVERS) {
|
||||||
return _drivers[i]._protocol_type_cache;
|
return _drivers[i]._protocol_type_cache;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user