mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Linux: Fix typos
This commit is contained in:
parent
267a74ebb2
commit
2236640f66
libraries/AP_HAL_Linux
@ -42,7 +42,7 @@ void AnalogSource_IIO::init_pins(void)
|
||||
}
|
||||
|
||||
/*
|
||||
selects a diferent file descriptor among in the fd_analog_sources array
|
||||
selects a different file descriptor among in the fd_analog_sources array
|
||||
*/
|
||||
void AnalogSource_IIO::select_pin(void)
|
||||
{
|
||||
|
@ -281,7 +281,7 @@ uint8_t Flow_PX4::compute_flow(uint8_t *image1, uint8_t *image2,
|
||||
}
|
||||
}
|
||||
|
||||
/* acceptance SAD distance threshhold */
|
||||
/* acceptance SAD distance threshold */
|
||||
if (dist < _bottom_flow_value_threshold) {
|
||||
meanflowx += (float)sumx;
|
||||
meanflowy += (float) sumy;
|
||||
|
@ -21,7 +21,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);
|
||||
|
||||
@ -31,7 +31,7 @@ public:
|
||||
* 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);
|
||||
|
@ -472,7 +472,7 @@ void RCInput_RPI::_timer_tick()
|
||||
break;}
|
||||
}
|
||||
|
||||
//How many bytes have DMA transfered (and we can process)?
|
||||
//How many bytes have DMA transferred (and we can process)?
|
||||
counter = circle_buffer->bytes_available(curr_pointer, circle_buffer->get_offset(circle_buffer->_virt_pages, (uintptr_t)x));
|
||||
//We can't stay in method for a long time, because it may lead to delays
|
||||
if (counter > RCIN_RPI_MAX_COUNTER) {
|
||||
|
@ -73,7 +73,7 @@ void RCInput_UART::_timer_tick()
|
||||
|
||||
if (_data.magic != MAGIC) {
|
||||
/* try to find the magic number and move
|
||||
* it to the beggining of our buffer */
|
||||
* it to the beginning of our buffer */
|
||||
uint16_t magic = MAGIC;
|
||||
|
||||
_pdata = (uint8_t *)memmem(&_data, sizeof(_data), &magic, sizeof(magic));
|
||||
|
@ -175,7 +175,7 @@ sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
|
||||
*
|
||||
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
|
||||
* condition as fail-safe greatly reduces the reliability and range of the radio link,
|
||||
* e.g. by prematurely issueing return-to-launch!!! */
|
||||
* e.g. by prematurely issuing return-to-launch!!! */
|
||||
|
||||
*sbus_failsafe = false;
|
||||
*sbus_frame_drop = true;
|
||||
|
Loading…
Reference in New Issue
Block a user