mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_PX4: Fix typos
This commit is contained in:
parent
1efa4a4115
commit
892cc2ea6f
@ -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;
|
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 PX4I2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data)
|
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;
|
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 */
|
* register, then reads back multiple bytes */
|
||||||
uint8_t PX4I2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
uint8_t PX4I2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data)
|
uint8_t len, uint8_t* data)
|
||||||
|
@ -22,7 +22,7 @@ public:
|
|||||||
/* writeRegister: write a single 8-bit value to a register */
|
/* writeRegister: write a single 8-bit value to a register */
|
||||||
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) override;
|
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;
|
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 */
|
/* read: for i2c devices which do not obey register conventions */
|
||||||
@ -32,7 +32,7 @@ public:
|
|||||||
* then reads back an 8-bit value. */
|
* then reads back an 8-bit value. */
|
||||||
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) override;
|
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 */
|
* register, then reads back multiple bytes */
|
||||||
uint8_t readRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data) override;
|
uint8_t readRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data) override;
|
||||||
|
|
||||||
|
@ -204,7 +204,7 @@ void PX4RCOutput::enable_ch(uint8_t ch)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (ch >= 8 && !(_enabled_channels & (1U<<ch))) {
|
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
|
// aux channels now. This delayed setup makes it possible to
|
||||||
// use BRD_PWM_COUNT to setup the number of PWM channels.
|
// use BRD_PWM_COUNT to setup the number of PWM channels.
|
||||||
_init_alt_channels();
|
_init_alt_channels();
|
||||||
|
@ -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
|
APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
|
||||||
microseconds when the time completes. This significantly improves
|
microseconds when the time completes. This significantly improves
|
||||||
the regularity of timing of the main loop as it takes
|
the regularity of timing of the main loop as it takes
|
||||||
|
Loading…
Reference in New Issue
Block a user