AP_HAL_Linux: rename RCOutput_Navio to RCOutput_PCA9685
The RCOutput_Navio is now generic enough to be used by other boards. Rename it to use the name of the chip, PCA9685.
This commit is contained in:
parent
e1f0284df2
commit
18321a77c4
@ -28,7 +28,7 @@ namespace Linux {
|
||||
class LinuxRCInput_ZYNQ;
|
||||
class LinuxRCOutput_PRU;
|
||||
class LinuxRCOutput_AioPRU;
|
||||
class LinuxRCOutput_Navio;
|
||||
class LinuxRCOutput_PCA9685;
|
||||
class LinuxRCOutput_ZYNQ;
|
||||
class LinuxRCOutput_Bebop;
|
||||
class LinuxSemaphore;
|
||||
|
@ -19,7 +19,7 @@
|
||||
#include "RCInput_Navio.h"
|
||||
#include "RCOutput_PRU.h"
|
||||
#include "RCOutput_AioPRU.h"
|
||||
#include "RCOutput_Navio.h"
|
||||
#include "RCOutput_PCA9685.h"
|
||||
#include "RCOutput_ZYNQ.h"
|
||||
#include "RCOutput_Bebop.h"
|
||||
#include "Semaphores.h"
|
||||
|
@ -94,7 +94,7 @@ static LinuxRCOutput_AioPRU rcoutDriver;
|
||||
use the PCA9685 based RCOutput driver on Navio
|
||||
*/
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
|
||||
static LinuxRCOutput_Navio rcoutDriver(true, 3, RPI_GPIO_27);
|
||||
static LinuxRCOutput_PCA9685 rcoutDriver(true, 3, RPI_GPIO_27);
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
||||
static LinuxRCOutput_ZYNQ rcoutDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include "RCOutput_Navio.h"
|
||||
#include "RCOutput_PCA9685.h"
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
@ -58,9 +58,9 @@ using namespace Linux;
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
LinuxRCOutput_Navio::LinuxRCOutput_Navio(bool external_clock,
|
||||
uint8_t channel_offset,
|
||||
uint8_t oe_pin_number) :
|
||||
LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(bool external_clock,
|
||||
uint8_t channel_offset,
|
||||
uint8_t oe_pin_number) :
|
||||
_i2c_sem(NULL),
|
||||
_enable_pin(NULL),
|
||||
_frequency(50),
|
||||
@ -75,16 +75,16 @@ LinuxRCOutput_Navio::LinuxRCOutput_Navio(bool external_clock,
|
||||
_osc_clock = PCA9685_INTERNAL_CLOCK;
|
||||
}
|
||||
|
||||
LinuxRCOutput_Navio::~LinuxRCOutput_Navio()
|
||||
LinuxRCOutput_PCA9685::~LinuxRCOutput_PCA9685()
|
||||
{
|
||||
delete [] _pulses_buffer;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::init(void* machtnicht)
|
||||
void LinuxRCOutput_PCA9685::init(void* machtnicht)
|
||||
{
|
||||
_i2c_sem = hal.i2c->get_semaphore();
|
||||
if (_i2c_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("PANIC: RCOutput_Navio did not get "
|
||||
hal.scheduler->panic(PSTR("PANIC: RCOutput_PCA9685 did not get "
|
||||
"valid I2C semaphore!"));
|
||||
return; /* never reached */
|
||||
}
|
||||
@ -100,7 +100,7 @@ void LinuxRCOutput_Navio::init(void* machtnicht)
|
||||
_enable_pin->write(0);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::reset_all_channels()
|
||||
void LinuxRCOutput_PCA9685::reset_all_channels()
|
||||
{
|
||||
if (!_i2c_sem->take(10)) {
|
||||
return;
|
||||
@ -115,7 +115,7 @@ void LinuxRCOutput_Navio::reset_all_channels()
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
void LinuxRCOutput_PCA9685::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
{
|
||||
|
||||
/* Correctly finish last pulses */
|
||||
@ -158,22 +158,22 @@ void LinuxRCOutput_Navio::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput_Navio::get_freq(uint8_t ch)
|
||||
uint16_t LinuxRCOutput_PCA9685::get_freq(uint8_t ch)
|
||||
{
|
||||
return _frequency;
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::enable_ch(uint8_t ch)
|
||||
void LinuxRCOutput_PCA9685::enable_ch(uint8_t ch)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::disable_ch(uint8_t ch)
|
||||
void LinuxRCOutput_PCA9685::disable_ch(uint8_t ch)
|
||||
{
|
||||
write(ch, 0);
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::write(uint8_t ch, uint16_t period_us)
|
||||
void LinuxRCOutput_PCA9685::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if(ch >= PWM_CHAN_COUNT){
|
||||
return;
|
||||
@ -201,18 +201,18 @@ void LinuxRCOutput_Navio::write(uint8_t ch, uint16_t period_us)
|
||||
_i2c_sem->give();
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
||||
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_Navio::read(uint8_t ch)
|
||||
uint16_t LinuxRCOutput_PCA9685::read(uint8_t ch)
|
||||
{
|
||||
return _pulses_buffer[ch];
|
||||
}
|
||||
|
||||
void LinuxRCOutput_Navio::read(uint16_t* period_us, uint8_t len)
|
||||
void LinuxRCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
for (int i = 0; i < len; i++)
|
||||
period_us[i] = read(0 + i);
|
@ -1,14 +1,14 @@
|
||||
|
||||
#ifndef __AP_HAL_LINUX_RCOUTPUT_NAVIO_H__
|
||||
#define __AP_HAL_LINUX_RCOUTPUT_NAVIO_H__
|
||||
#ifndef __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__
|
||||
#define __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
|
||||
class Linux::LinuxRCOutput_Navio : public AP_HAL::RCOutput {
|
||||
class Linux::LinuxRCOutput_PCA9685 : public AP_HAL::RCOutput {
|
||||
public:
|
||||
LinuxRCOutput_Navio(bool external_clock, uint8_t channel_offset,
|
||||
uint8_t oe_pin_number);
|
||||
~LinuxRCOutput_Navio();
|
||||
LinuxRCOutput_PCA9685(bool external_clock, uint8_t channel_offset,
|
||||
uint8_t oe_pin_number);
|
||||
~LinuxRCOutput_PCA9685();
|
||||
void init(void* machtnichts);
|
||||
void reset_all_channels();
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
@ -35,4 +35,4 @@ private:
|
||||
uint8_t _oe_pin_number;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_LINUX_RCOUTPUT_NAVIO_H__
|
||||
#endif // __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__
|
Loading…
Reference in New Issue
Block a user