mirror of https://github.com/ArduPilot/ardupilot
59 lines
2.2 KiB
C
59 lines
2.2 KiB
C
|
/*
|
||
|
This program is free software: you can redistribute it and/or modify
|
||
|
it under the terms of the GNU General Public License as published by
|
||
|
the Free Software Foundation, either version 3 of the License, or
|
||
|
(at your option) any later version.
|
||
|
|
||
|
This program is distributed in the hope that it will be useful,
|
||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||
|
GNU General Public License for more details.
|
||
|
|
||
|
You should have received a copy of the GNU General Public License
|
||
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||
|
*/
|
||
|
/*
|
||
|
Flymaple port by Mike McCauley
|
||
|
*/
|
||
|
|
||
|
#ifndef __AP_HAL_FLYMAPLE_I2CDRIVER_H__
|
||
|
#define __AP_HAL_FLYMAPLE_I2CDRIVER_H__
|
||
|
|
||
|
#include <AP_HAL_FLYMAPLE.h>
|
||
|
|
||
|
class AP_HAL_FLYMAPLE_NS::FLYMAPLEI2CDriver : public AP_HAL::I2CDriver {
|
||
|
public:
|
||
|
FLYMAPLEI2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {}
|
||
|
void begin();
|
||
|
void end();
|
||
|
void setTimeout(uint16_t ms);
|
||
|
void setHighSpeed(bool active);
|
||
|
|
||
|
/* write: for i2c devices which do not obey register conventions */
|
||
|
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 */
|
||
|
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
||
|
uint8_t len, uint8_t* data);
|
||
|
|
||
|
/* read: for i2c devices which do not obey register conventions */
|
||
|
uint8_t read(uint8_t addr, uint8_t len, uint8_t* data);
|
||
|
/* readRegister: read from a device register - writes the register,
|
||
|
* 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
|
||
|
* register, then reads back multiple bytes */
|
||
|
uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
||
|
uint8_t len, uint8_t* data);
|
||
|
|
||
|
uint8_t lockup_count();
|
||
|
|
||
|
AP_HAL::Semaphore* get_semaphore() { return _semaphore; }
|
||
|
|
||
|
private:
|
||
|
AP_HAL::Semaphore* _semaphore;
|
||
|
};
|
||
|
|
||
|
#endif // __AP_HAL_FLYMAPLE_I2CDRIVER_H__
|