Browse Source

AP_HAL_Linux: Fix comment and panic on Bebop

master
Julien BERAUD 9 years ago committed by Lucas De Marchi
parent
commit
cadef09542
  1. 2
      libraries/AP_HAL_Linux/GPIO_Bebop.cpp
  2. 2
      libraries/AP_HAL_Linux/RCOutput_Bebop.cpp

2
libraries/AP_HAL_Linux/GPIO_Bebop.cpp

@ -11,6 +11,6 @@ const unsigned Linux::GPIO_Sysfs::pin_table[] = { @@ -11,6 +11,6 @@ const unsigned Linux::GPIO_Sysfs::pin_table[] = {
const uint8_t Linux::GPIO_Sysfs::n_pins = _BEBOP_GPIO_MAX;
static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _BEBOP_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_bebop");
#endif

2
libraries/AP_HAL_Linux/RCOutput_Bebop.cpp

@ -374,7 +374,7 @@ void RCOutput_Bebop::_run_rcout() @@ -374,7 +374,7 @@ void RCOutput_Bebop::_run_rcout()
memset(current_period_us, 0, sizeof(current_period_us));
if (!_get_info(&info)) {
AP_HAL::panic("failed to get BLDC info\n");
AP_HAL::panic("failed to get BLDC info");
}
/* Set motor order depending on BLDC version.On bebop 1 with version 1

Loading…
Cancel
Save