AP_HAL_Linux: removed assert calls
these waste flash space and do not do us any good
This commit is contained in:
parent
ebc1f9acf6
commit
0601259d20
@ -198,7 +198,6 @@ void GPIO_RPI::pinMode(uint8_t pin, uint8_t output)
|
||||
|
||||
void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
|
||||
{
|
||||
assert(alt < 6);
|
||||
if (output == HAL_GPIO_INPUT) {
|
||||
set_gpio_mode_in(pin);
|
||||
} else if (output == HAL_GPIO_ALT) {
|
||||
|
@ -296,8 +296,6 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
|
||||
const char *module_path = AP_MODULE_DEFAULT_DIRECTORY;
|
||||
#endif
|
||||
|
||||
assert(callbacks);
|
||||
|
||||
int opt;
|
||||
const struct GetOptLong::option options[] = {
|
||||
{"uartA", true, 0, 'A'},
|
||||
|
@ -162,8 +162,6 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
struct i2c_msg msgs[2] = { };
|
||||
unsigned nmsgs = 0;
|
||||
|
||||
assert(_bus.fd >= 0);
|
||||
|
||||
if (send && send_len != 0) {
|
||||
msgs[nmsgs].addr = _address;
|
||||
msgs[nmsgs].flags = 0;
|
||||
@ -389,8 +387,6 @@ I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const
|
||||
|
||||
void I2CDeviceManager::_unregister(I2CBus &b)
|
||||
{
|
||||
assert(b.ref > 0);
|
||||
|
||||
if (--b.ref > 0) {
|
||||
return;
|
||||
}
|
||||
|
@ -274,8 +274,6 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
unsigned nmsgs = 0;
|
||||
int fd = _bus.fd[_desc.subdev];
|
||||
|
||||
assert(fd >= 0);
|
||||
|
||||
if (send && send_len != 0) {
|
||||
msgs[nmsgs].tx_buf = (uint64_t) send;
|
||||
msgs[nmsgs].rx_buf = 0;
|
||||
@ -355,8 +353,6 @@ bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv,
|
||||
struct spi_ioc_transfer msgs[1] = { };
|
||||
int fd = _bus.fd[_desc.subdev];
|
||||
|
||||
assert(fd >= 0);
|
||||
|
||||
if (!send || !recv || len == 0) {
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user