mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: move function definitions to cpp to save flash
This commit is contained in:
parent
76d6170ec9
commit
1934b4a738
|
@ -54,6 +54,26 @@ bool AP_HAL::Device::setup_checked_registers(uint8_t nregs, uint8_t frequency)
|
|||
return true;
|
||||
}
|
||||
|
||||
void AP_HAL::Device::set_device_type(uint8_t devtype) {
|
||||
_bus_id.devid_s.devtype = devtype;
|
||||
}
|
||||
|
||||
|
||||
bool AP_HAL::Device::read_bank_registers(uint8_t bank, uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
first_reg |= _read_flag;
|
||||
return transfer_bank(bank, &first_reg, 1, recv, recv_len);
|
||||
}
|
||||
|
||||
bool AP_HAL::Device::write_bank_register(uint8_t bank, uint8_t reg, uint8_t val, bool checked)
|
||||
{
|
||||
uint8_t buf[2] = { reg, val };
|
||||
if (checked) {
|
||||
set_checked_register(bank, reg, val);
|
||||
}
|
||||
return transfer_bank(bank, buf, sizeof(buf), nullptr, 0);
|
||||
}
|
||||
|
||||
/*
|
||||
set value of one checked register
|
||||
*/
|
||||
|
@ -143,3 +163,111 @@ bool AP_HAL::Device::check_next_register(struct checkreg &fail)
|
|||
fail = _checked.last_reg_fail;
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
bool AP_HAL::Device::write_register(uint8_t reg, uint8_t val, bool checked)
|
||||
{
|
||||
uint8_t buf[2] = { reg, val };
|
||||
if (checked) {
|
||||
set_checked_register(reg, val);
|
||||
}
|
||||
bool result = transfer(buf, sizeof(buf), nullptr, 0);
|
||||
if (_register_rw_callback && result) {
|
||||
_register_rw_callback(reg, &val, 1, true);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
bool AP_HAL::Device::read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
uint8_t read_reg = first_reg;
|
||||
first_reg |= _read_flag;
|
||||
bool result = transfer(&first_reg, 1, recv, recv_len);
|
||||
if (_register_rw_callback != nullptr && result) {
|
||||
_register_rw_callback(read_reg, recv, recv_len, false);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
bool AP_HAL::Device::transfer_bank(uint8_t bank, const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
if (_bank_select) {
|
||||
if (!_bank_select(bank)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return transfer(send, send_len, recv, recv_len);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Some devices connected on the I2C or SPI bus require a bit to be set on
|
||||
* the register address in order to perform a read operation. This sets a
|
||||
* flag to be used by #read_registers(). The flag's default value is zero.
|
||||
*/
|
||||
void AP_HAL::Device::set_read_flag(uint8_t flag)
|
||||
{
|
||||
_read_flag = flag;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* make a bus id given bus type, bus number, bus address and
|
||||
* device type This is for use by devices that do not use one of
|
||||
* the standard HAL Device types, such as UAVCAN devices
|
||||
*/
|
||||
uint32_t AP_HAL::Device::make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype) {
|
||||
union DeviceId d {};
|
||||
d.devid_s.bus_type = bus_type;
|
||||
d.devid_s.bus = bus;
|
||||
d.devid_s.address = address;
|
||||
d.devid_s.devtype = devtype;
|
||||
return d.devid;
|
||||
}
|
||||
|
||||
/**
|
||||
* return a new bus ID for the same bus connection but a new device type.
|
||||
* This is used for auxiliary bus connections
|
||||
*/
|
||||
uint32_t AP_HAL::Device::change_bus_id(uint32_t old_id, uint8_t devtype) {
|
||||
union DeviceId d;
|
||||
d.devid = old_id;
|
||||
d.devid_s.devtype = devtype;
|
||||
return d.devid;
|
||||
}
|
||||
|
||||
/**
|
||||
* return bus ID with a new devtype
|
||||
*/
|
||||
uint32_t AP_HAL::Device::get_bus_id_devtype(uint8_t devtype) const {
|
||||
return change_bus_id(get_bus_id(), devtype);
|
||||
}
|
||||
|
||||
/**
|
||||
* get bus type
|
||||
*/
|
||||
enum AP_HAL::Device::BusType AP_HAL::Device::devid_get_bus_type(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.bus_type;
|
||||
}
|
||||
|
||||
uint8_t AP_HAL::Device::devid_get_bus(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.bus;
|
||||
}
|
||||
|
||||
uint8_t AP_HAL::Device::devid_get_address(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.address;
|
||||
}
|
||||
|
||||
uint8_t AP_HAL::Device::devid_get_devtype(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.devtype;
|
||||
}
|
||||
|
|
|
@ -88,10 +88,7 @@ public:
|
|||
}
|
||||
|
||||
// set device type within a device class (eg. AP_COMPASS_TYPE_LSM303D)
|
||||
void set_device_type(uint8_t devtype) {
|
||||
_bus_id.devid_s.devtype = devtype;
|
||||
}
|
||||
|
||||
void set_device_type(uint8_t devtype);
|
||||
|
||||
virtual ~Device() {
|
||||
delete[] _checked.regs;
|
||||
|
@ -144,16 +141,7 @@ public:
|
|||
*
|
||||
* Return: true on a successful transfer, false on failure.
|
||||
*/
|
||||
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
uint8_t read_reg = first_reg;
|
||||
first_reg |= _read_flag;
|
||||
bool result = transfer(&first_reg, 1, recv, recv_len);
|
||||
if (_register_rw_callback != nullptr && result) {
|
||||
_register_rw_callback(read_reg, recv, recv_len, false);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len);
|
||||
|
||||
/**
|
||||
* Wrapper function over #transfer() to write a byte to the register reg.
|
||||
|
@ -161,19 +149,7 @@ public:
|
|||
*
|
||||
* Return: true on a successful transfer, false on failure.
|
||||
*/
|
||||
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
|
||||
{
|
||||
uint8_t buf[2] = { reg, val };
|
||||
if (checked) {
|
||||
set_checked_register(reg, val);
|
||||
}
|
||||
bool result = transfer(buf, sizeof(buf), nullptr, 0);
|
||||
if (_register_rw_callback && result) {
|
||||
_register_rw_callback(reg, &val, 1, true);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
bool write_register(uint8_t reg, uint8_t val, bool checked=false);
|
||||
|
||||
/*
|
||||
* Sets a callback to be called when a register is read or written.
|
||||
|
@ -189,14 +165,7 @@ public:
|
|||
* Return: true on a successful transfer, false on failure.
|
||||
*/
|
||||
bool transfer_bank(uint8_t bank, const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len) {
|
||||
if (_bank_select) {
|
||||
if (!_bank_select(bank)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return transfer(send, send_len, recv, recv_len);
|
||||
}
|
||||
uint8_t *recv, uint32_t recv_len);
|
||||
|
||||
/**
|
||||
* Wrapper function over #transfer_bank() to read recv_len registers, starting
|
||||
|
@ -206,11 +175,7 @@ public:
|
|||
*
|
||||
* Return: true on a successful transfer, false on failure.
|
||||
*/
|
||||
bool read_bank_registers(uint8_t bank, uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
first_reg |= _read_flag;
|
||||
return transfer_bank(bank, &first_reg, 1, recv, recv_len);
|
||||
}
|
||||
bool read_bank_registers(uint8_t bank, uint8_t first_reg, uint8_t *recv, uint32_t recv_len);
|
||||
|
||||
/**
|
||||
* Wrapper function over #transfer_bank() to write a byte to the register reg.
|
||||
|
@ -218,14 +183,7 @@ public:
|
|||
*
|
||||
* Return: true on a successful transfer, false on failure.
|
||||
*/
|
||||
bool write_bank_register(uint8_t bank, uint8_t reg, uint8_t val, bool checked=false)
|
||||
{
|
||||
uint8_t buf[2] = { reg, val };
|
||||
if (checked) {
|
||||
set_checked_register(bank, reg, val);
|
||||
}
|
||||
return transfer_bank(bank, buf, sizeof(buf), nullptr, 0);
|
||||
}
|
||||
bool write_bank_register(uint8_t bank, uint8_t reg, uint8_t val, bool checked=false);
|
||||
|
||||
/**
|
||||
* set a value for a checked register in a bank
|
||||
|
@ -347,70 +305,36 @@ public:
|
|||
* the register address in order to perform a read operation. This sets a
|
||||
* flag to be used by #read_registers(). The flag's default value is zero.
|
||||
*/
|
||||
void set_read_flag(uint8_t flag)
|
||||
{
|
||||
_read_flag = flag;
|
||||
}
|
||||
|
||||
void set_read_flag(uint8_t flag);
|
||||
|
||||
/**
|
||||
* make a bus id given bus type, bus number, bus address and
|
||||
* device type This is for use by devices that do not use one of
|
||||
* the standard HAL Device types, such as UAVCAN devices
|
||||
*/
|
||||
static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype) {
|
||||
union DeviceId d {};
|
||||
d.devid_s.bus_type = bus_type;
|
||||
d.devid_s.bus = bus;
|
||||
d.devid_s.address = address;
|
||||
d.devid_s.devtype = devtype;
|
||||
return d.devid;
|
||||
}
|
||||
static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype);
|
||||
|
||||
/**
|
||||
* return a new bus ID for the same bus connection but a new device type.
|
||||
* This is used for auxiliary bus connections
|
||||
*/
|
||||
static uint32_t change_bus_id(uint32_t old_id, uint8_t devtype) {
|
||||
union DeviceId d;
|
||||
d.devid = old_id;
|
||||
d.devid_s.devtype = devtype;
|
||||
return d.devid;
|
||||
}
|
||||
static uint32_t change_bus_id(uint32_t old_id, uint8_t devtype);
|
||||
|
||||
/**
|
||||
* return bus ID with a new devtype
|
||||
*/
|
||||
uint32_t get_bus_id_devtype(uint8_t devtype) const {
|
||||
return change_bus_id(get_bus_id(), devtype);
|
||||
}
|
||||
uint32_t get_bus_id_devtype(uint8_t devtype) const;
|
||||
|
||||
/**
|
||||
* get bus type
|
||||
*/
|
||||
static enum BusType devid_get_bus_type(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.bus_type;
|
||||
}
|
||||
static enum BusType devid_get_bus_type(uint32_t dev_id);
|
||||
|
||||
static uint8_t devid_get_bus(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.bus;
|
||||
}
|
||||
static uint8_t devid_get_bus(uint32_t dev_id);
|
||||
|
||||
static uint8_t devid_get_address(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.address;
|
||||
}
|
||||
static uint8_t devid_get_address(uint32_t dev_id);
|
||||
|
||||
static uint8_t devid_get_devtype(uint32_t dev_id) {
|
||||
union DeviceId d;
|
||||
d.devid = dev_id;
|
||||
return d.devid_s.devtype;
|
||||
}
|
||||
static uint8_t devid_get_devtype(uint32_t dev_id);
|
||||
|
||||
|
||||
/* set number of retries on transfers */
|
||||
|
|
Loading…
Reference in New Issue