mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: fix copy and paste error on gpio table
This commit is contained in:
parent
9eb53e333b
commit
d31e85e738
|
@ -23,6 +23,6 @@ const unsigned Linux::GPIO_Sysfs::pin_table[] = {
|
|||
const uint8_t Linux::GPIO_Sysfs::n_pins = _EDGE_GPIO_MAX;
|
||||
|
||||
static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _EDGE_GPIO_MAX,
|
||||
"GPIO pin_table must have the same size of entries in enum gpio_minnow");
|
||||
"GPIO pin_table must have the same size of entries in enum edge");
|
||||
|
||||
#endif
|
||||
|
|
|
@ -19,6 +19,6 @@ const unsigned Linux::GPIO_Sysfs::pin_table[] = {
|
|||
const uint8_t Linux::GPIO_Sysfs::n_pins = _NAVIO_GPIO_MAX;
|
||||
|
||||
static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _NAVIO_GPIO_MAX,
|
||||
"GPIO pin_table must have the same size of entries in enum gpio_minnow");
|
||||
"GPIO pin_table must have the same size of entries in enum gpio_navio");
|
||||
|
||||
#endif
|
||||
|
|
|
@ -29,6 +29,6 @@ const unsigned Linux::GPIO_Sysfs::pin_table[] = {
|
|||
const uint8_t Linux::GPIO_Sysfs::n_pins = _NAVIO2_GPIO_MAX;
|
||||
|
||||
static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _NAVIO2_GPIO_MAX,
|
||||
"GPIO pin_table must have the same size of entries in enum gpio_minnow");
|
||||
"GPIO pin_table must have the same size of entries in enum gpio_navio2");
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue