Browse Source

AP_HAL_ChibiOS: add support for CAN/I2C switch

gps-1.3.1
Nathan Costa 3 years ago committed by Andrew Tridgell
parent
commit
9f7aa715b1
  1. 39
      libraries/AP_HAL_ChibiOS/I2CDevice.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/I2CDevice.h
  3. 6
      libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat

39
libraries/AP_HAL_ChibiOS/I2CDevice.cpp

@ -105,6 +105,45 @@ void I2CBus::clear_all() @@ -105,6 +105,45 @@ void I2CBus::clear_all()
}
}
/*
If bus exists, set its data and clock lines to floating
*/
void I2CBus::set_bus_to_floating(uint8_t busidx)
{
if (busidx < ARRAY_SIZE(I2CD)) {
const struct I2CInfo &info = I2CD[busidx];
const ioline_t sda_line = GPIO::resolve_alt_config(info.sda_line, PERIPH_TYPE::I2C_SDA, info.instance);
const ioline_t scl_line = GPIO::resolve_alt_config(info.scl_line, PERIPH_TYPE::I2C_SCL, info.instance);
palSetLineMode(sda_line, PAL_MODE_INPUT);
palSetLineMode(scl_line, PAL_MODE_INPUT);
}
}
/*
Check enabled I2C/CAN select pins against check_pins bitmask
*/
bool I2CBus::check_select_pins(uint8_t check_pins)
{
uint8_t enabled_pins = 0;
#ifdef HAL_GPIO_PIN_GPIO_CAN_I2C1_SEL
enabled_pins |= palReadLine(HAL_GPIO_PIN_GPIO_CAN_I2C1_SEL) << 0;
#endif
#ifdef HAL_GPIO_PIN_GPIO_CAN_I2C2_SEL
enabled_pins |= palReadLine(HAL_GPIO_PIN_GPIO_CAN_I2C2_SEL) << 1;
#endif
#ifdef HAL_GPIO_PIN_GPIO_CAN_I2C3_SEL
enabled_pins |= palReadLine(HAL_GPIO_PIN_GPIO_CAN_I2C3_SEL) << 2;
#endif
#ifdef HAL_GPIO_PIN_GPIO_CAN_I2C4_SEL
enabled_pins |= palReadLine(HAL_GPIO_PIN_GPIO_CAN_I2C4_SEL) << 3;
#endif
return (enabled_pins & check_pins) == check_pins;
}
/*
clear a stuck bus (bus held by a device that is holding SDA low) by
clocking out pulses on SCL to let the device complete its

2
libraries/AP_HAL_ChibiOS/I2CDevice.h

@ -52,6 +52,8 @@ public: @@ -52,6 +52,8 @@ public:
static void clear_all(void);
static void clear_bus(uint8_t busidx);
static uint8_t read_sda(uint8_t busidx);
static bool check_select_pins(uint8_t check_pins);
static void set_bus_to_floating(uint8_t busidx);
};
class I2CDevice : public AP_HAL::I2CDevice {

6
libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat

@ -39,6 +39,9 @@ PB7 USART1_RX USART1 SPEED_HIGH @@ -39,6 +39,9 @@ PB7 USART1_RX USART1 SPEED_HIGH
# LEDs
PA10 LED OUTPUT LOW
# a CAN/I2C selection LED
PA5 LED_CAN_I2C OUTPUT LOW
# a fault LED
PA6 LED_FAULT OUTPUT LOW
@ -70,6 +73,9 @@ define HAL_DISABLE_LOOP_DELAY @@ -70,6 +73,9 @@ define HAL_DISABLE_LOOP_DELAY
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
# GPIO for CAN/I2C selection
PB5 GPIO_CAN_I2C1_SEL INPUT PUSHPULL FLOATING
# only one I2C bus in normal config
PA15 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

Loading…
Cancel
Save