Browse Source

AP_HAL_Linux: remove unused write method

master
Lucas De Marchi 10 years ago committed by Randy Mackay
parent
commit
191ec10554
  1. 13
      libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp
  2. 1
      libraries/AP_HAL_Linux/RCOutput_AioPRU.h
  3. 6
      libraries/AP_HAL_Linux/RCOutput_Bebop.cpp
  4. 1
      libraries/AP_HAL_Linux/RCOutput_Bebop.h
  5. 6
      libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp
  6. 1
      libraries/AP_HAL_Linux/RCOutput_PCA9685.h
  7. 11
      libraries/AP_HAL_Linux/RCOutput_PRU.cpp
  8. 1
      libraries/AP_HAL_Linux/RCOutput_PRU.h
  9. 6
      libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp
  10. 1
      libraries/AP_HAL_Linux/RCOutput_Raspilot.h
  11. 11
      libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp
  12. 1
      libraries/AP_HAL_Linux/RCOutput_ZYNQ.h

13
libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp

@ -108,19 +108,6 @@ void LinuxRCOutput_AioPRU::write(uint8_t ch, uint16_t period_us) @@ -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;

1
libraries/AP_HAL_Linux/RCOutput_AioPRU.h

@ -26,7 +26,6 @@ class Linux::LinuxRCOutput_AioPRU : public AP_HAL::RCOutput { @@ -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);

6
libraries/AP_HAL_Linux/RCOutput_Bebop.cpp

@ -329,12 +329,6 @@ void LinuxRCOutput_Bebop::write(uint8_t ch, uint16_t period_us) @@ -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) {

1
libraries/AP_HAL_Linux/RCOutput_Bebop.h

@ -61,7 +61,6 @@ public: @@ -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);

6
libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp

@ -203,12 +203,6 @@ void LinuxRCOutput_PCA9685::write(uint8_t ch, uint16_t period_us) @@ -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];

1
libraries/AP_HAL_Linux/RCOutput_PCA9685.h

@ -20,7 +20,6 @@ class Linux::LinuxRCOutput_PCA9685 : public AP_HAL::RCOutput { @@ -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);

11
libraries/AP_HAL_Linux/RCOutput_PRU.cpp

@ -75,17 +75,6 @@ void LinuxRCOutput_PRU::write(uint8_t ch, uint16_t period_us) @@ -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;i<len;i++){
write(ch+i,period_us[i]);
}
}
uint16_t LinuxRCOutput_PRU::read(uint8_t ch)
{
return (sharedMem_cmd->hilo_read[chan_pru_map[ch]][1]/TICK_PER_US);

1
libraries/AP_HAL_Linux/RCOutput_PRU.h

@ -22,7 +22,6 @@ class Linux::LinuxRCOutput_PRU : public AP_HAL::RCOutput { @@ -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);

6
libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp

@ -81,12 +81,6 @@ void LinuxRCOutput_Raspilot::write(uint8_t ch, uint16_t period_us) @@ -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){

1
libraries/AP_HAL_Linux/RCOutput_Raspilot.h

@ -11,7 +11,6 @@ class Linux::LinuxRCOutput_Raspilot : public AP_HAL::RCOutput { @@ -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);

11
libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp

@ -71,17 +71,6 @@ void LinuxRCOutput_ZYNQ::write(uint8_t ch, uint16_t period_us) @@ -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;i<len;i++){
write(ch+i,period_us[i]);
}
}
uint16_t LinuxRCOutput_ZYNQ::read(uint8_t ch)
{
return (sharedMem_cmd->periodhi[ch].hi/TICK_PER_US);

1
libraries/AP_HAL_Linux/RCOutput_ZYNQ.h

@ -21,7 +21,6 @@ class Linux::LinuxRCOutput_ZYNQ : public AP_HAL::RCOutput { @@ -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);

Loading…
Cancel
Save