AP_HAL_Linux: PocketPilot: change pru to final design

This commit is contained in:
mirkix 2018-04-11 22:37:41 +02:00 committed by Andrew Tridgell
parent f4a38d6f2a
commit 598ae5c3f7
3 changed files with 12 additions and 2 deletions

View File

@ -17,7 +17,11 @@
#include "AP_HAL_Linux.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
#define RCIN_PRUSS_RAM_BASE 0x4a301000
#else
#define RCIN_PRUSS_RAM_BASE 0x4a303000
#endif
// we use 300 ring buffer entries to guarantee that a full 25 byte
// frame of 12 bits per byte

View File

@ -50,13 +50,13 @@ void RCOutput_AioPRU::init()
close(mem_fd);
// Reset PRU 1
// Reset PRU
*ctrl = 0;
// Load firmware
memcpy(iram, PRUcode, sizeof(PRUcode));
// Start PRU 1
// Start PRU
*ctrl |= 2;
// all outputs default to 50Hz, the top level vehicle code

View File

@ -11,9 +11,15 @@
#pragma once
#include "AP_HAL_Linux.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
#define RCOUT_PRUSS_RAM_BASE 0x4a300000
#define RCOUT_PRUSS_CTRL_BASE 0x4a322000
#define RCOUT_PRUSS_IRAM_BASE 0x4a334000
#else
#define RCOUT_PRUSS_RAM_BASE 0x4a302000
#define RCOUT_PRUSS_CTRL_BASE 0x4a324000
#define RCOUT_PRUSS_IRAM_BASE 0x4a338000
#endif
#define PWM_CHAN_COUNT 12
namespace Linux {