From 191ec10554d6157292a899ccc3edb21fab06e2a1 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Fri, 21 Aug 2015 18:42:35 -0300 Subject: [PATCH] AP_HAL_Linux: remove unused write method --- libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp | 13 ------------- libraries/AP_HAL_Linux/RCOutput_AioPRU.h | 1 - libraries/AP_HAL_Linux/RCOutput_Bebop.cpp | 6 ------ libraries/AP_HAL_Linux/RCOutput_Bebop.h | 1 - libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp | 6 ------ libraries/AP_HAL_Linux/RCOutput_PCA9685.h | 1 - libraries/AP_HAL_Linux/RCOutput_PRU.cpp | 11 ----------- libraries/AP_HAL_Linux/RCOutput_PRU.h | 1 - libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp | 6 ------ libraries/AP_HAL_Linux/RCOutput_Raspilot.h | 1 - libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp | 11 ----------- libraries/AP_HAL_Linux/RCOutput_ZYNQ.h | 1 - 12 files changed, 59 deletions(-) diff --git a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp index 664af613d5..9ae9ad4354 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp @@ -108,19 +108,6 @@ void LinuxRCOutput_AioPRU::write(uint8_t ch, uint16_t period_us) } } -void LinuxRCOutput_AioPRU::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - uint8_t i; - - if(len > PWM_CHAN_COUNT) { - len = PWM_CHAN_COUNT; - } - - for(i = 0; i < len; i++) { - write(ch + i, period_us[i]); - } -} - uint16_t LinuxRCOutput_AioPRU::read(uint8_t ch) { uint16_t ret = 0; diff --git a/libraries/AP_HAL_Linux/RCOutput_AioPRU.h b/libraries/AP_HAL_Linux/RCOutput_AioPRU.h index 7978d07cdc..87b149e515 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AioPRU.h +++ b/libraries/AP_HAL_Linux/RCOutput_AioPRU.h @@ -26,7 +26,6 @@ class Linux::LinuxRCOutput_AioPRU : public AP_HAL::RCOutput { void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len); diff --git a/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp b/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp index 493992c483..607aad69e6 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp @@ -329,12 +329,6 @@ void LinuxRCOutput_Bebop::write(uint8_t ch, uint16_t period_us) } } -void LinuxRCOutput_Bebop::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - for (int i = 0; i < len; i++) - write(ch + i, period_us[i]); -} - uint16_t LinuxRCOutput_Bebop::read(uint8_t ch) { if (ch < BEBOP_BLDC_MOTORS_NUM) { diff --git a/libraries/AP_HAL_Linux/RCOutput_Bebop.h b/libraries/AP_HAL_Linux/RCOutput_Bebop.h index 1c39a95f67..c9e5c08849 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Bebop.h +++ b/libraries/AP_HAL_Linux/RCOutput_Bebop.h @@ -61,7 +61,6 @@ public: void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len); void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm); diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp index cb26ce43ce..a36daf1e96 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp @@ -203,12 +203,6 @@ void LinuxRCOutput_PCA9685::write(uint8_t ch, uint16_t period_us) _i2c_sem->give(); } -void LinuxRCOutput_PCA9685::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - for (int i = 0; i < len; i++) - write(ch + i, period_us[i]); -} - uint16_t LinuxRCOutput_PCA9685::read(uint8_t ch) { return _pulses_buffer[ch]; diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.h b/libraries/AP_HAL_Linux/RCOutput_PCA9685.h index 00f72496bd..7b7180dab9 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.h +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.h @@ -20,7 +20,6 @@ class Linux::LinuxRCOutput_PCA9685 : public AP_HAL::RCOutput { void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len); diff --git a/libraries/AP_HAL_Linux/RCOutput_PRU.cpp b/libraries/AP_HAL_Linux/RCOutput_PRU.cpp index f0800d233e..3d6f5801ff 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PRU.cpp @@ -75,17 +75,6 @@ void LinuxRCOutput_PRU::write(uint8_t ch, uint16_t period_us) sharedMem_cmd->periodhi[chan_pru_map[ch]][1] = TICK_PER_US*period_us; } -void LinuxRCOutput_PRU::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - uint8_t i; - if(len>PWM_CHAN_COUNT){ - len = PWM_CHAN_COUNT; - } - for(i=0;ihilo_read[chan_pru_map[ch]][1]/TICK_PER_US); diff --git a/libraries/AP_HAL_Linux/RCOutput_PRU.h b/libraries/AP_HAL_Linux/RCOutput_PRU.h index 06ca5e87fe..7b57999d94 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PRU.h +++ b/libraries/AP_HAL_Linux/RCOutput_PRU.h @@ -22,7 +22,6 @@ class Linux::LinuxRCOutput_PRU : public AP_HAL::RCOutput { void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len); diff --git a/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp b/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp index 05feeaf237..1608a4b8d7 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp @@ -81,12 +81,6 @@ void LinuxRCOutput_Raspilot::write(uint8_t ch, uint16_t period_us) _period_us[ch] = period_us; } -void LinuxRCOutput_Raspilot::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - for (int i = 0; i < len; i++) - write(ch + i, period_us[i]); -} - uint16_t LinuxRCOutput_Raspilot::read(uint8_t ch) { if(ch >= PWM_CHAN_COUNT){ diff --git a/libraries/AP_HAL_Linux/RCOutput_Raspilot.h b/libraries/AP_HAL_Linux/RCOutput_Raspilot.h index 5762cbbfd2..e791446489 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Raspilot.h +++ b/libraries/AP_HAL_Linux/RCOutput_Raspilot.h @@ -11,7 +11,6 @@ class Linux::LinuxRCOutput_Raspilot : public AP_HAL::RCOutput { void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len); diff --git a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp index bb71f0a60d..8b8d90ff2e 100644 --- a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp @@ -71,17 +71,6 @@ void LinuxRCOutput_ZYNQ::write(uint8_t ch, uint16_t period_us) sharedMem_cmd->periodhi[ch].hi = TICK_PER_US*period_us; } -void LinuxRCOutput_ZYNQ::write(uint8_t ch, uint16_t* period_us, uint8_t len) -{ - uint8_t i; - if(len>PWM_CHAN_COUNT){ - len = PWM_CHAN_COUNT; - } - for(i=0;iperiodhi[ch].hi/TICK_PER_US); diff --git a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.h b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.h index 986c0ab917..81cd4220c5 100644 --- a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.h +++ b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.h @@ -21,7 +21,6 @@ class Linux::LinuxRCOutput_ZYNQ : public AP_HAL::RCOutput { void enable_ch(uint8_t ch); void disable_ch(uint8_t ch); void write(uint8_t ch, uint16_t period_us); - void write(uint8_t ch, uint16_t* period_us, uint8_t len); uint16_t read(uint8_t ch); void read(uint16_t* period_us, uint8_t len);