mirror of https://github.com/ArduPilot/ardupilot
hal_ap_linux: Make PRU constants private to reduce #define namespace pollution.
Forthcoming Zynq port AP_HAL_Linux uses similar constants with different values - move these as private member constants to avoid collisions. Signed-off-by: John Williams <john@whelanwilliams.net>
This commit is contained in:
parent
81de994fef
commit
b9f0310b82
|
@ -12,7 +12,6 @@
|
|||
#define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
|
||||
// we use 300 ring buffer entries to guarantee that a full 25 byte
|
||||
// frame of 12 bits per byte
|
||||
#define NUM_RING_ENTRIES 300
|
||||
|
||||
class Linux::LinuxRCInput_PRU : public Linux::LinuxRCInput
|
||||
{
|
||||
|
@ -21,6 +20,7 @@ public:
|
|||
void _timer_tick(void);
|
||||
|
||||
private:
|
||||
static const unsigned int NUM_RING_ENTRIES=300;
|
||||
// shared ring buffer with the PRU which records pin transitions
|
||||
struct ring_buffer {
|
||||
volatile uint16_t ring_head; // owned by ARM CPU
|
||||
|
|
|
@ -7,8 +7,6 @@
|
|||
#define MAX_PWMS 12
|
||||
#define PWM_CMD_MAGIC 0xf00fbaaf
|
||||
#define PWM_REPLY_MAGIC 0xbaaff00f
|
||||
#define TICK_PER_US 200
|
||||
#define TICK_PER_S 200000000
|
||||
#define PWM_CMD_CONFIG 0 /* full configuration in one go */
|
||||
#define PWM_CMD_ENABLE 1 /* enable a pwm */
|
||||
#define PWM_CMD_DISABLE 2 /* disable a pwm */
|
||||
|
@ -29,6 +27,8 @@ class Linux::LinuxRCOutput_PRU : public AP_HAL::RCOutput {
|
|||
void read(uint16_t* period_us, uint8_t len);
|
||||
|
||||
private:
|
||||
static const int TICK_PER_US=200;
|
||||
static const int TICK_PER_S=200000000;
|
||||
struct pwm_cmd {
|
||||
uint32_t magic;
|
||||
uint32_t enmask; /* enable mask */
|
||||
|
|
Loading…
Reference in New Issue