From 892cc2ea6f5cc39b2bf47e275722f4420239d7fc Mon Sep 17 00:00:00 2001 From: Ricardo de Almeida Gonzaga Date: Thu, 12 May 2016 14:01:14 -0300 Subject: [PATCH] AP_HAL_PX4: Fix typos --- libraries/AP_HAL_PX4/I2CDriver.cpp | 4 ++-- libraries/AP_HAL_PX4/I2CDriver.h | 4 ++-- libraries/AP_HAL_PX4/RCOutput.cpp | 2 +- libraries/AP_HAL_PX4/Scheduler.cpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_PX4/I2CDriver.cpp b/libraries/AP_HAL_PX4/I2CDriver.cpp index 6813620a9c..50449f15ba 100644 --- a/libraries/AP_HAL_PX4/I2CDriver.cpp +++ b/libraries/AP_HAL_PX4/I2CDriver.cpp @@ -69,7 +69,7 @@ uint8_t PX4I2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val) return do_transfer(addr, d, sizeof(d), nullptr, 0) ? 0:1; } -/* writeRegisters: write bytes to contigious registers */ +/* writeRegisters: write bytes to contiguous registers */ uint8_t PX4I2CDriver::writeRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data) { @@ -89,7 +89,7 @@ uint8_t PX4I2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data) return do_transfer(addr, ®, 1, data, 1) ? 0:1; } -/* readRegister: read contigious device registers - writes the first +/* readRegister: read contiguous device registers - writes the first * register, then reads back multiple bytes */ uint8_t PX4I2CDriver::readRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data) diff --git a/libraries/AP_HAL_PX4/I2CDriver.h b/libraries/AP_HAL_PX4/I2CDriver.h index f7039e5434..fcfcca7f78 100644 --- a/libraries/AP_HAL_PX4/I2CDriver.h +++ b/libraries/AP_HAL_PX4/I2CDriver.h @@ -22,7 +22,7 @@ public: /* writeRegister: write a single 8-bit value to a register */ uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) override; - /* 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) override; /* read: for i2c devices which do not obey register conventions */ @@ -32,7 +32,7 @@ public: * then reads back an 8-bit value. */ uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) override; - /* 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) override; diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 66d812998f..62cd69a079 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -204,7 +204,7 @@ void PX4RCOutput::enable_ch(uint8_t ch) return; } if (ch >= 8 && !(_enabled_channels & (1U<