mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: removed unused enable_mask and disable_mask functions
This commit is contained in:
parent
b7eab7ea22
commit
87cc95dd7f
|
@ -32,10 +32,7 @@ public:
|
|||
/* Output active/highZ control, either by single channel at a time
|
||||
* or a mask of channels */
|
||||
virtual void enable_ch(uint8_t ch) = 0;
|
||||
virtual void enable_mask(uint32_t chmask) = 0;
|
||||
|
||||
virtual void disable_ch(uint8_t ch) = 0;
|
||||
virtual void disable_mask(uint32_t chmask) = 0;
|
||||
|
||||
/* Output, either single channel or bulk array of channels */
|
||||
virtual void write(uint8_t ch, uint16_t period_us) = 0;
|
||||
|
|
|
@ -17,10 +17,7 @@ public:
|
|||
/* Output active/highZ control, either by single channel at a time
|
||||
* or a mask of channels */
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
|
||||
/* Output, either single channel or bulk array of channels */
|
||||
void write(uint8_t ch, uint16_t period_ms);
|
||||
|
@ -47,10 +44,7 @@ public:
|
|||
/* Output active/highZ control, either by single channel at a time
|
||||
* or a mask of channels */
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
|
||||
/* Output, either single channel or bulk array of channels */
|
||||
void write(uint8_t ch, uint16_t period_us);
|
||||
|
|
|
@ -130,14 +130,6 @@ void APM1RCOutput::enable_ch(uint8_t ch) {
|
|||
}
|
||||
}
|
||||
|
||||
void APM1RCOutput::enable_mask(uint32_t chmask) {
|
||||
for (int i = 0; i < 32; i++) {
|
||||
if ((chmask >> i) & 1) {
|
||||
enable_ch(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void APM1RCOutput::disable_ch(uint8_t ch) {
|
||||
switch(ch) {
|
||||
case 0: TCCR5A &= ~(1<<COM5B1); break; // CH_1 : OC5B
|
||||
|
|
|
@ -123,15 +123,6 @@ void APM2RCOutput::enable_ch(uint8_t ch) {
|
|||
}
|
||||
}
|
||||
|
||||
void APM2RCOutput::enable_mask(uint32_t chmask) {
|
||||
for (int i = 0; i < 32; i++) {
|
||||
uint32_t c = chmask >> i;
|
||||
if (c & 1) {
|
||||
enable_ch(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void APM2RCOutput::disable_ch(uint8_t ch) {
|
||||
switch(ch) {
|
||||
case 0: TCCR1A &= ~(1<<COM1B1); break; // CH_1 : OC1B
|
||||
|
|
|
@ -83,7 +83,9 @@ void loop (void) {
|
|||
void setup (void) {
|
||||
hal.gpio->pinMode(27, GPIO_OUTPUT);
|
||||
hal.gpio->write(27, 0);
|
||||
hal.rcout->enable_mask(0x000000FF);
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
hal.rcout->enable_ch(i);
|
||||
}
|
||||
|
||||
/* Bottom 4 channels at 400hz (like on a quad) */
|
||||
hal.rcout->set_freq(0x0000000F, 400);
|
||||
|
|
|
@ -18,15 +18,9 @@ uint16_t SITLRCOutput::get_freq(uint8_t ch) {
|
|||
void SITLRCOutput::enable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void SITLRCOutput::enable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void SITLRCOutput::disable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void SITLRCOutput::disable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void SITLRCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
_sitlState->pwm_output[ch] = period_us;
|
||||
|
|
|
@ -16,9 +16,7 @@ public:
|
|||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
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);
|
||||
|
|
|
@ -14,15 +14,9 @@ uint16_t EmptyRCOutput::get_freq(uint8_t ch) {
|
|||
void EmptyRCOutput::enable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::enable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::disable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::disable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void EmptyRCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{}
|
||||
|
||||
|
|
|
@ -9,9 +9,7 @@ class Empty::EmptyRCOutput : public AP_HAL::RCOutput {
|
|||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
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);
|
||||
|
|
|
@ -71,15 +71,6 @@ void FLYMAPLERCOutput::enable_ch(uint8_t ch)
|
|||
write(ch, 0);
|
||||
}
|
||||
|
||||
void FLYMAPLERCOutput::enable_mask(uint32_t chmask)
|
||||
{
|
||||
for (int i = 0; i < 32; i++) {
|
||||
if ((chmask >> i) & 1) {
|
||||
enable_ch(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void FLYMAPLERCOutput::disable_ch(uint8_t ch)
|
||||
{
|
||||
if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
|
||||
|
@ -87,15 +78,6 @@ void FLYMAPLERCOutput::disable_ch(uint8_t ch)
|
|||
// TODO
|
||||
}
|
||||
|
||||
void FLYMAPLERCOutput::disable_mask(uint32_t chmask)
|
||||
{
|
||||
for (int i = 0; i < 32; i++) {
|
||||
if ((chmask >> i) & 1) {
|
||||
disable_ch(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
|
||||
|
|
|
@ -28,9 +28,7 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLERCOutput : public AP_HAL::RCOutput {
|
|||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
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);
|
||||
|
|
|
@ -80,7 +80,9 @@ void setup (void) {
|
|||
// hal.scheduler->delay(5000);
|
||||
hal.gpio->pinMode(13, GPIO_OUTPUT);
|
||||
hal.gpio->write(13, 0);
|
||||
hal.rcout->enable_mask(0x000000FF);
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
hal.rcout->enable_ch(i);
|
||||
}
|
||||
|
||||
/* Bottom 4 channels at 400hz (like on a quad) */
|
||||
hal.rcout->set_freq(0x0000000F, 400);
|
||||
|
|
|
@ -17,15 +17,9 @@ uint16_t LinuxRCOutput::get_freq(uint8_t ch) {
|
|||
void LinuxRCOutput::enable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void LinuxRCOutput::enable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void LinuxRCOutput::disable_ch(uint8_t ch)
|
||||
{}
|
||||
|
||||
void LinuxRCOutput::disable_mask(uint32_t chmask)
|
||||
{}
|
||||
|
||||
void LinuxRCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{}
|
||||
|
||||
|
|
|
@ -9,9 +9,7 @@ class Linux::LinuxRCOutput : public AP_HAL::RCOutput {
|
|||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
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);
|
||||
|
|
|
@ -133,21 +133,11 @@ void PX4RCOutput::enable_ch(uint8_t ch)
|
|||
// channels are always enabled ...
|
||||
}
|
||||
|
||||
void PX4RCOutput::enable_mask(uint32_t chmask)
|
||||
{
|
||||
// channels are always enabled ...
|
||||
}
|
||||
|
||||
void PX4RCOutput::disable_ch(uint8_t ch)
|
||||
{
|
||||
// channels are always enabled ...
|
||||
}
|
||||
|
||||
void PX4RCOutput::disable_mask(uint32_t chmask)
|
||||
{
|
||||
// channels are always enabled ...
|
||||
}
|
||||
|
||||
void PX4RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
|
||||
{
|
||||
struct pwm_output_values pwm_values;
|
||||
|
|
|
@ -14,9 +14,7 @@ public:
|
|||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
void enable_ch(uint8_t ch);
|
||||
void enable_mask(uint32_t chmask);
|
||||
void disable_ch(uint8_t ch);
|
||||
void disable_mask(uint32_t chmask);
|
||||
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);
|
||||
|
|
Loading…
Reference in New Issue