mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
AP_HAL_Linux: change define and members visibility
Make some member variables protected to follow what we do in other places (and there's no reason to be private). Move defines to .cpp to reduce their visibility.
This commit is contained in:
parent
f36e8d9c05
commit
e8f71a5bd2
@ -35,11 +35,10 @@ public:
|
||||
void add_sbus_input(const uint8_t *bytes, size_t nbytes);
|
||||
|
||||
|
||||
protected:
|
||||
protected:
|
||||
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);
|
||||
void _update_periods(uint16_t *periods, uint8_t len);
|
||||
|
||||
private:
|
||||
volatile bool new_rc_input;
|
||||
|
||||
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS];
|
||||
|
@ -29,7 +29,7 @@ public:
|
||||
void init();
|
||||
void _timer_tick(void);
|
||||
|
||||
private:
|
||||
protected:
|
||||
static const uint32_t TICK_PER_US = 200;
|
||||
static const uint32_t NUM_RING_ENTRIES = 300;
|
||||
// shared ring buffer with the PRU which records pin transitions
|
||||
|
@ -18,7 +18,8 @@
|
||||
#include <unistd.h>
|
||||
|
||||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
#define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -7,7 +7,6 @@
|
||||
|
||||
#include "RCInput.h"
|
||||
|
||||
#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
|
||||
|
||||
|
@ -16,6 +16,8 @@
|
||||
|
||||
#include "GPIO.h"
|
||||
|
||||
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43c10000
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
|
@ -7,9 +7,6 @@
|
||||
|
||||
#include "RCInput.h"
|
||||
|
||||
// FIXME A puppie dies when you hard code an address
|
||||
#define RCIN_ZYNQ_PULSE_INPUT_BASE 0x43c10000
|
||||
|
||||
namespace Linux {
|
||||
|
||||
class RCInput_ZYNQ : public RCInput {
|
||||
|
@ -18,7 +18,16 @@
|
||||
|
||||
using namespace Linux;
|
||||
|
||||
#define PWM_CHAN_COUNT 8 // FIXME
|
||||
#define PWM_CHAN_COUNT 8
|
||||
#define RCOUT_ZYNQ_PWM_BASE 0x43c00000
|
||||
#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 */
|
||||
#define PWM_CMD_MODIFY 3 /* modify a pwm */
|
||||
#define PWM_CMD_SET 4 /* set a pwm output explicitly */
|
||||
#define PWM_CMD_CLR 5 /* clr a pwm output explicitly */
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
|
||||
static void catch_sigbus(int sig)
|
||||
{
|
||||
|
@ -1,20 +1,10 @@
|
||||
#pragma once
|
||||
|
||||
#include "AP_HAL_Linux.h"
|
||||
#define RCOUT_ZYNQ_PWM_BASE 0x43c00000 //FIXME hardcoding is the devil's work
|
||||
#define MAX_ZYNQ_PWMS 8 /* number of pwm channels */
|
||||
#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 */
|
||||
#define PWM_CMD_MODIFY 3 /* modify a pwm */
|
||||
#define PWM_CMD_SET 4 /* set a pwm output explicitly */
|
||||
#define PWM_CMD_CLR 5 /* clr a pwm output explicitly */
|
||||
#define PWM_CMD_TEST 6 /* various crap */
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
namespace Linux {
|
||||
|
||||
#define MAX_ZYNQ_PWMS 8 /* number of pwm channels */
|
||||
|
||||
class RCOutput_ZYNQ : public AP_HAL::RCOutput {
|
||||
public:
|
||||
|
Loading…
Reference in New Issue
Block a user