mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_VRBRAIN: removed empty lines
This commit is contained in:
parent
fabd7601f0
commit
b420a5c6db
@ -79,11 +79,6 @@ VRBRAINAnalogSource::VRBRAINAnalogSource(int16_t pin, float initial_value) :
|
||||
_sum_value(0),
|
||||
_sum_ratiometric(0)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
float VRBRAINAnalogSource::read_average()
|
||||
@ -224,15 +219,6 @@ void VRBRAINAnalogIn::_timer_tick(void)
|
||||
if (ret > 0) {
|
||||
// match the incoming channels to the currently active pins
|
||||
for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
|
||||
Debug("chan %u value=%u\n",
|
||||
(unsigned)buf_adc[i].am_channel,
|
||||
(unsigned)buf_adc[i].am_data);
|
||||
@ -245,7 +231,6 @@ void VRBRAINAnalogIn::_timer_tick(void)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// check for new battery data on FMUv1
|
||||
if (_battery_handle != -1) {
|
||||
struct battery_status_s battery;
|
||||
@ -269,51 +254,6 @@ void VRBRAINAnalogIn::_timer_tick(void)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
AP_HAL::AnalogSource* VRBRAINAnalogIn::channel(int16_t pin)
|
||||
|
@ -43,12 +43,6 @@ static VRBRAINAnalogIn analogIn;
|
||||
static VRBRAINUtil utilInstance;
|
||||
static VRBRAINGPIO gpioDriver;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//We only support 3 serials for VRBRAIN at the moment
|
||||
#if defined(CONFIG_ARCH_BOARD_VRBRAIN_V40)
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
|
||||
|
@ -38,31 +38,12 @@ void VRBRAINRCOutput::init(void* unused)
|
||||
hal.console->printf("RCOutput: Unable to get servo count\n");
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
void VRBRAINRCOutput::_init_alt_channels(void)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
void VRBRAINRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
@ -128,12 +109,6 @@ uint16_t VRBRAINRCOutput::get_freq(uint8_t ch)
|
||||
|
||||
void VRBRAINRCOutput::enable_ch(uint8_t ch)
|
||||
{
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
_enabled_channels |= (1U<<ch);
|
||||
}
|
||||
|
||||
@ -236,19 +211,7 @@ void VRBRAINRCOutput::_timer_tick(void)
|
||||
if (_need_update && _pwm_fd != -1) {
|
||||
_need_update = false;
|
||||
perf_begin(_perf_rcout);
|
||||
|
||||
::write(_pwm_fd, _period, _max_channel*sizeof(_period[0]));
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
::write(_pwm_fd, _period, _max_channel*sizeof(_period[0]));
|
||||
perf_end(_perf_rcout);
|
||||
_last_output = now;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user