mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_Linux: split off RCOutput class to be specific to PXF and ERLE
this fixes the Replay tool
This commit is contained in:
parent
2ce219aeb8
commit
94e14f5dcb
@ -19,7 +19,7 @@ namespace Linux {
|
||||
class LinuxDigitalSource;
|
||||
class LinuxRCInput;
|
||||
class LinuxRCInput_PRU;
|
||||
class LinuxRCOutput;
|
||||
class LinuxRCOutput_PRU;
|
||||
class LinuxSemaphore;
|
||||
class LinuxScheduler;
|
||||
class LinuxUtil;
|
||||
|
@ -13,7 +13,7 @@
|
||||
#include "Storage.h"
|
||||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
#include "RCOutput.h"
|
||||
#include "RCOutput_PRU.h"
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
#include "Util.h"
|
||||
|
@ -9,6 +9,9 @@
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_Empty_Private.h>
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
// 3 serial ports on Linux for now
|
||||
@ -22,12 +25,24 @@ static LinuxSPIDeviceManager spiDeviceManager;
|
||||
static LinuxAnalogIn analogIn;
|
||||
static LinuxStorage storageDriver;
|
||||
static LinuxGPIO gpioDriver;
|
||||
|
||||
/*
|
||||
use the PRU based RCInput driver on ERLE and PXF
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
|
||||
static LinuxRCInput_PRU rcinDriver;
|
||||
#else
|
||||
static LinuxRCInput rcinDriver;
|
||||
#endif
|
||||
static LinuxRCOutput rcoutDriver;
|
||||
|
||||
/*
|
||||
use the PRU based RCOutput driver on ERLE and PXF
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
|
||||
static LinuxRCOutput_PRU rcoutDriver;
|
||||
#else
|
||||
static Empty::EmptyRCOutput rcoutDriver;
|
||||
#endif
|
||||
static LinuxScheduler schedulerInstance;
|
||||
static LinuxUtil utilInstance;
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
#include "RCOutput.h"
|
||||
#include "RCOutput_PRU.h"
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
@ -29,7 +29,7 @@ static void catch_sigbus(int sig)
|
||||
{
|
||||
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
||||
}
|
||||
void LinuxRCOutput::init(void* machtnicht)
|
||||
void LinuxRCOutput_PRU::init(void* machtnicht)
|
||||
{
|
||||
uint32_t mem_fd;
|
||||
signal(SIGBUS,catch_sigbus);
|
||||
@ -43,7 +43,7 @@ void LinuxRCOutput::init(void* machtnicht)
|
||||
set_freq(0xFFFFFFFF, 50);
|
||||
}
|
||||
|
||||
void LinuxRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
||||
void LinuxRCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
|
||||
{
|
||||
uint8_t i;
|
||||
unsigned long tick=TICK_PER_S/(unsigned long)freq_hz;
|
||||
@ -55,27 +55,27 @@ void LinuxRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput::get_freq(uint8_t ch)
|
||||
uint16_t LinuxRCOutput_PRU::get_freq(uint8_t ch)
|
||||
{
|
||||
return TICK_PER_S/sharedMem_cmd->periodhi[chan_pru_map[ch]][0];
|
||||
}
|
||||
|
||||
void LinuxRCOutput::enable_ch(uint8_t ch)
|
||||
void LinuxRCOutput_PRU::enable_ch(uint8_t ch)
|
||||
{
|
||||
sharedMem_cmd->enmask |= 1U<<chan_pru_map[ch];
|
||||
}
|
||||
|
||||
void LinuxRCOutput::disable_ch(uint8_t ch)
|
||||
void LinuxRCOutput_PRU::disable_ch(uint8_t ch)
|
||||
{
|
||||
sharedMem_cmd->enmask &= !(1U<<chan_pru_map[ch]);
|
||||
}
|
||||
|
||||
void LinuxRCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
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::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
||||
void LinuxRCOutput_PRU::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
if(len>PWM_CHAN_COUNT){
|
||||
@ -86,12 +86,12 @@ void LinuxRCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t LinuxRCOutput::read(uint8_t ch)
|
||||
uint16_t LinuxRCOutput_PRU::read(uint8_t ch)
|
||||
{
|
||||
return (sharedMem_cmd->hilo_read[chan_pru_map[ch]][1]/TICK_PER_US);
|
||||
}
|
||||
|
||||
void LinuxRCOutput::read(uint16_t* period_us, uint8_t len)
|
||||
void LinuxRCOutput_PRU::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
uint8_t i;
|
||||
if(len>PWM_CHAN_COUNT){
|
@ -1,6 +1,6 @@
|
||||
|
||||
#ifndef __AP_HAL_LINUX_RCOUTPUT_H__
|
||||
#define __AP_HAL_LINUX_RCOUTPUT_H__
|
||||
#ifndef __AP_HAL_LINUX_RCOUTPUT_PRU_H__
|
||||
#define __AP_HAL_LINUX_RCOUTPUT_PRU_H__
|
||||
|
||||
#include <AP_HAL_Linux.h>
|
||||
#define RCOUT_PRUSS_SHAREDRAM_BASE 0x4a310000
|
||||
@ -17,7 +17,7 @@
|
||||
#define PWM_CMD_CLR 5 /* clr a pwm output explicitly */
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
class Linux::LinuxRCOutput : public AP_HAL::RCOutput {
|
||||
class Linux::LinuxRCOutput_PRU : public AP_HAL::RCOutput {
|
||||
void init(void* machtnichts);
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz);
|
||||
uint16_t get_freq(uint8_t ch);
|
||||
@ -41,4 +41,4 @@ private:
|
||||
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_LINUX_RCOUTPUT_H__
|
||||
#endif // __AP_HAL_LINUX_RCOUTPUT_PRU_H__
|
Loading…
Reference in New Issue
Block a user