mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_HAL: Fix typos
This commit is contained in:
parent
aa4b66509f
commit
eb418f54ee
@ -39,7 +39,7 @@ public:
|
|||||||
* Set the speed of future transfers. Depending on the bus the speed may
|
* Set the speed of future transfers. Depending on the bus the speed may
|
||||||
* be shared for all devices on the same bus.
|
* be shared for all devices on the same bus.
|
||||||
*
|
*
|
||||||
* Return: true if speed was succesfully set or platform doesn't implement
|
* Return: true if speed was successfully set or platform doesn't implement
|
||||||
* it; false otherwise.
|
* it; false otherwise.
|
||||||
*/
|
*/
|
||||||
virtual bool set_speed(Speed speed) = 0;
|
virtual bool set_speed(Speed speed) = 0;
|
||||||
|
@ -15,7 +15,7 @@ public:
|
|||||||
virtual uint8_t write(uint8_t addr, uint8_t len, uint8_t* data) = 0;
|
virtual uint8_t write(uint8_t addr, uint8_t len, uint8_t* data) = 0;
|
||||||
/* writeRegister: write a single 8-bit value to a register */
|
/* writeRegister: write a single 8-bit value to a register */
|
||||||
virtual uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) = 0;
|
virtual uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) = 0;
|
||||||
/* writeRegisters: write bytes to contigious registers */
|
/* writeRegisters: write bytes to contiguous registers */
|
||||||
virtual uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
virtual uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data) = 0;
|
uint8_t len, uint8_t* data) = 0;
|
||||||
|
|
||||||
@ -25,13 +25,13 @@ public:
|
|||||||
* then reads back an 8-bit value. */
|
* then reads back an 8-bit value. */
|
||||||
virtual uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) = 0;
|
virtual uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) = 0;
|
||||||
|
|
||||||
/* readRegisters: read contigious device registers - writes the first
|
/* readRegisters: read contiguous device registers - writes the first
|
||||||
* register, then reads back multiple bytes */
|
* register, then reads back multiple bytes */
|
||||||
virtual uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
virtual uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data) = 0;
|
uint8_t len, uint8_t* data) = 0;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
/* readRegistersMultiple: read contigious device registers.
|
/* readRegistersMultiple: read contiguous device registers.
|
||||||
Equivalent to count calls to readRegisters() */
|
Equivalent to count calls to readRegisters() */
|
||||||
virtual uint8_t readRegistersMultiple(uint8_t addr, uint8_t reg,
|
virtual uint8_t readRegistersMultiple(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t count,
|
uint8_t len, uint8_t count,
|
||||||
|
@ -48,7 +48,7 @@ public:
|
|||||||
virtual bool set_overrides(int16_t *overrides, uint8_t len) = 0;
|
virtual bool set_overrides(int16_t *overrides, uint8_t len) = 0;
|
||||||
/* set_override: set just a specific channel */
|
/* set_override: set just a specific channel */
|
||||||
virtual bool set_override(uint8_t channel, int16_t override) = 0;
|
virtual bool set_override(uint8_t channel, int16_t override) = 0;
|
||||||
/* clear_overrides: equivelant to setting all overrides to 0 */
|
/* clear_overrides: equivalent to setting all overrides to 0 */
|
||||||
virtual void clear_overrides() = 0;
|
virtual void clear_overrides() = 0;
|
||||||
|
|
||||||
/* execute receiver bind */
|
/* execute receiver bind */
|
||||||
|
Loading…
Reference in New Issue
Block a user