mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 11:43:56 -04:00
AP_HAL_FLYMAPLE: Fix typos
This commit is contained in:
parent
2236640f66
commit
2f88e32657
@ -42,7 +42,7 @@ public:
|
||||
|
||||
/* implementation specific interface: */
|
||||
|
||||
/* new_sample(): called with value of ADC measurments, from interrput */
|
||||
/* new_sample(): called with value of ADC measurments, from interrupt */
|
||||
void new_sample(uint16_t);
|
||||
|
||||
/* setup_read(): called to setup ADC registers for next measurment,
|
||||
|
@ -299,12 +299,12 @@ when on Auto, but will be OK on Manual.
|
||||
|
||||
GPS notes
|
||||
|
||||
I tested intially with an EM-405A GPS (This is a 5Hz, 5V GPS, and therefore I
|
||||
I tested initially with an EM-405A GPS (This is a 5Hz, 5V GPS, and therefore I
|
||||
also needed a voltage divider to make the received data compatible with the
|
||||
Flymaple 3.3V GPS input on pin D0). This GPS was unsatisfactory due to long
|
||||
time lags in changing ground track and speed, and also due to large random
|
||||
ground speeds up to 1.0 m/s when stationary. I was able to get ok behaviour
|
||||
with very large values for NAVL1_PERIOD of around 40. Dont use this GPS.
|
||||
with very large values for NAVL1_PERIOD of around 40. Don't use this GPS.
|
||||
|
||||
I also tested with a Eagle Tree GPS$v, which is a 10Hz, 3.3V GPS board
|
||||
containing a GTPA010 GPS. This GPS worked much better with the suggested
|
||||
|
@ -33,7 +33,7 @@ public:
|
||||
uint8_t write(uint8_t addr, uint8_t len, uint8_t* data);
|
||||
/* writeRegister: write a single 8-bit value to a register */
|
||||
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val);
|
||||
/* writeRegisters: write bytes to contigious registers */
|
||||
/* writeRegisters: write bytes to contiguous registers */
|
||||
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data);
|
||||
|
||||
@ -42,7 +42,7 @@ public:
|
||||
/* readRegister: read from a device register - writes the register,
|
||||
* then reads back an 8-bit value. */
|
||||
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data);
|
||||
/* readRegister: read contigious device registers - writes the first
|
||||
/* readRegister: read contiguous device registers - writes the first
|
||||
* register, then reads back multiple bytes */
|
||||
uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data);
|
||||
|
@ -42,7 +42,7 @@ volatile uint32_t FLYMAPLERCInput::_last_input_interrupt_time = 0; // Last time
|
||||
|
||||
// This is the rollover count of the timer
|
||||
// each count is 0.5us, so 600000 = 30ms
|
||||
// We cant reliably measure intervals that exceed this time.
|
||||
// We can't reliably measure intervals that exceed this time.
|
||||
#define FLYMAPLE_TIMER_RELOAD 60000
|
||||
|
||||
FLYMAPLERCInput::FLYMAPLERCInput()
|
||||
|
@ -118,7 +118,7 @@ uint8_t FLYMAPLERCOutput::_channel_to_flymaple_pin(uint8_t ch)
|
||||
// Channels on the same timer ALWAYS use the same frequency (the last one set)
|
||||
// 28, 27, 11, 12 use Timer 3 OK
|
||||
// 24, 14, 5, 9 use Timer 4 BREAKS I2C on pins 5 and 9
|
||||
// 35, 36, 37, 38 use Timer 8 DONT USE: CRASHES. WHY?
|
||||
// 35, 36, 37, 38 use Timer 8 DON'T USE: CRASHES. WHY?
|
||||
// 0 1, 2, 3 use Timer 2 OK
|
||||
static uint8_t ch_to_pin[FLYMAPLE_RC_OUTPUT_NUM_CHANNELS] = { 28, 27, 11, 12, 24, 14 };
|
||||
if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
|
||||
|
@ -3,7 +3,7 @@
|
||||
// Flymaple Scheduler.
|
||||
// We use systick interrupt for the 1kHz ordinary timers.
|
||||
// We use a slightly higher priority HardwareTimer 2 for the failsafe callbacks
|
||||
// so a hung timer wont prevent the failsafe timer interrupt running
|
||||
// so a hung timer won't prevent the failsafe timer interrupt running
|
||||
//
|
||||
// Use of noInterrupts()/interrupts() on FLymaple ARM processor.
|
||||
// Please see the notes in FlymaplePortingNotes.txt in this directory for
|
||||
|
@ -39,7 +39,7 @@ extern const AP_HAL::HAL& hal;
|
||||
// This is the number of 1k EEPROM blocks we need
|
||||
const uint8_t num_eeprom_blocks = 4;
|
||||
|
||||
// This is the addres of the LAST 2k FLASH ROM page to be used to implement the EEPROM
|
||||
// This is the address of the LAST 2k FLASH ROM page to be used to implement the EEPROM
|
||||
// FLASH ROM page use grows downwards from here
|
||||
// It is in fact the lat page in the available FLASH ROM
|
||||
const uint32_t last_flash_page = 0x0807F800;
|
||||
|
@ -42,7 +42,7 @@ FLYMAPLEUARTDriver::FLYMAPLEUARTDriver(HardwareSerial* hws):
|
||||
|
||||
void FLYMAPLEUARTDriver::begin(uint32_t b)
|
||||
{
|
||||
// Dont let the ISRs access the ring buffers until we are fully set up:
|
||||
// Don't let the ISRs access the ring buffers until we are fully set up:
|
||||
nvic_irq_disable(_hws->c_dev()->irq_num);
|
||||
_hws->begin(b);
|
||||
if (_txBuf)
|
||||
@ -73,7 +73,7 @@ void FLYMAPLEUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
_rxBufSize = rxS;
|
||||
}
|
||||
|
||||
// Dont let the IRs access the ring buffers until we are fully set up:
|
||||
// Don't let the IRs access the ring buffers until we are fully set up:
|
||||
nvic_irq_disable(_hws->c_dev()->irq_num);
|
||||
begin(b); // libmaple internal ring buffer reinitialised to defaults here
|
||||
if (_txBuf)
|
||||
|
@ -242,7 +242,7 @@ uint16 EEPROMClass::EE_VerifyPageFullWriteVariable(uint16 Address, uint16 Data)
|
||||
}
|
||||
}
|
||||
|
||||
// Check each active page address starting from begining
|
||||
// Check each active page address starting from beginning
|
||||
for (idx = pageBase + 4; idx < pageEnd; idx += 4)
|
||||
if ((*(__io uint32*)idx) == 0xFFFFFFFF) // Verify if element
|
||||
{ // contents are 0xFFFFFFFF
|
||||
|
Loading…
Reference in New Issue
Block a user