diff --git a/libraries/AP_HAL_Linux/RCInput_AioPRU.h b/libraries/AP_HAL_Linux/RCInput_AioPRU.h index c387f3f585..cb9e9f95c3 100644 --- a/libraries/AP_HAL_Linux/RCInput_AioPRU.h +++ b/libraries/AP_HAL_Linux/RCInput_AioPRU.h @@ -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 diff --git a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp index 066601a322..6b21ce1eca 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp @@ -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 diff --git a/libraries/AP_HAL_Linux/RCOutput_AioPRU.h b/libraries/AP_HAL_Linux/RCOutput_AioPRU.h index d61e178f80..2845f49724 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AioPRU.h +++ b/libraries/AP_HAL_Linux/RCOutput_AioPRU.h @@ -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 {