AP_HAL_PX4: Fix typos

This commit is contained in:
Ricardo de Almeida Gonzaga 2016-05-12 14:01:14 -03:00 committed by Lucas De Marchi
parent 1efa4a4115
commit 892cc2ea6f
4 changed files with 6 additions and 6 deletions

View File

@ -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, &reg, 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)

View File

@ -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;

View File

@ -204,7 +204,7 @@ void PX4RCOutput::enable_ch(uint8_t ch)
return;
}
if (ch >= 8 && !(_enabled_channels & (1U<<ch))) {
// this is the first enable of an auxillary channel - setup
// this is the first enable of an auxiliary channel - setup
// aux channels now. This delayed setup makes it possible to
// use BRD_PWM_COUNT to setup the number of PWM channels.
_init_alt_channels();

View File

@ -123,7 +123,7 @@ static void set_normal_priority(void *sem)
}
/*
a varient of delay_microseconds that boosts priority to
a variant of delay_microseconds that boosts priority to
APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
microseconds when the time completes. This significantly improves
the regularity of timing of the main loop as it takes