Skip to content

Commit

Permalink
Driver: Refactor MCP23009 GPIO expander into uORB driver
Browse files Browse the repository at this point in the history
  • Loading branch information
niklaut authored and bkueng committed Jun 19, 2023
1 parent 3303323 commit 8fe65c6
Show file tree
Hide file tree
Showing 19 changed files with 681 additions and 284 deletions.
1 change: 1 addition & 0 deletions boards/px4/fmu-v5x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPIO_MCP23009=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
Expand Down
11 changes: 11 additions & 0 deletions boards/px4/fmu-v5x/init/rc.board_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -19,3 +19,14 @@ param set-default SENS_EN_INA226 1
param set-default SYS_USE_IO 1

safety_button start

# GPIO Expander driver on external I2C3
if ver hwtypecmp V5X009000 V5X009001
then
# No USB
mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10
fi
if ver hwtypecmp V5X00a000 V5X00a001 V5X008000 V5X008001
then
mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10
fi
4 changes: 2 additions & 2 deletions boards/px4/fmu-v5x/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,8 +250,8 @@
#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)

/* MCP23009 GPIO expander */
#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpin4"
#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpin5"
#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4"
#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5"

/* Spare GPIO */

Expand Down
32 changes: 7 additions & 25 deletions boards/px4/fmu-v5x/src/init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,8 +264,9 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}

int ret;
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
ret = stm32_sdio_initialize();

if (ret != OK) {
led_on(LED_RED);
Expand All @@ -274,30 +275,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)

#endif /* CONFIG_MMCSD */

int hw_version = board_get_hw_version();

if (hw_version == 0x9 || hw_version == 0xa) {
static MCP23009 mcp23009{3, 0x25};

// No USB
if (hw_version == 0x9) {
// < P8
ret = mcp23009.init(0xf0, 0xf0, 0x0f);
// >= P8
//ret = mcp23009.init(0xf1, 0xf0, 0x0f);
}

if (hw_version == 0xa) {
// < P6
//ret = mcp23009.init(0xf0, 0xf0, 0x0f);
// >= P6
ret = mcp23009.init(0xf1, 0xf0, 0x0f);
}

if (ret != OK) {
led_on(LED_RED);
return ret;
}
ret = mcp23009_register_gpios(3, 0x25);

if (ret != OK) {
led_on(LED_RED);
return ret;
}

return OK;
Expand Down
6 changes: 5 additions & 1 deletion msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -90,16 +90,20 @@ set(msg_files
FollowTargetStatus.msg
GeneratorStatus.msg
GeofenceResult.msg
GimbalControls.msg
GimbalDeviceAttitudeStatus.msg
GimbalDeviceInformation.msg
GimbalDeviceSetAttitude.msg
GimbalManagerInformation.msg
GimbalManagerSetAttitude.msg
GimbalManagerSetManualControl.msg
GimbalManagerStatus.msg
GpioConfig.msg
GpioIn.msg
GpioOut.msg
GpioRequest.msg
GpsDump.msg
GpsInjectData.msg
GimbalControls.msg
Gripper.msg
HealthReport.msg
HeaterStatus.msg
Expand Down
28 changes: 28 additions & 0 deletions msg/GpioConfig.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# GPIO configuration

uint64 timestamp # time since system start (microseconds)
uint32 device_id # Device id

uint32 mask # Pin mask
uint32 state # Initial pin output state

# Configuration Mask
# Bit 0-3: Direction: 0=Input, 1=Output
# Bit 4-7: Input Config: 0=Floating, 1=PullUp, 2=PullDown
# Bit 8-12: Output Config: 0=PushPull, 1=OpenDrain
# Bit 13-31: Reserved
uint32 INPUT = 0 # 0x0000
uint32 OUTPUT = 1 # 0x0001
uint32 PULLUP = 16 # 0x0010
uint32 PULLDOWN = 32 # 0x0020
uint32 OPENDRAIN = 256 # 0x0100

uint32 INPUT_FLOATING = 0 # 0x0000
uint32 INPUT_PULLUP = 16 # 0x0010
uint32 INPUT_PULLDOWN = 32 # 0x0020

uint32 OUTPUT_PUSHPULL = 0 # 0x0000
uint32 OUTPUT_OPENDRAIN = 256 # 0x0100
uint32 OUTPUT_OPENDRAIN_PULLUP = 272 # 0x0110

uint32 config
6 changes: 6 additions & 0 deletions msg/GpioIn.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# GPIO mask and state

uint64 timestamp # time since system start (microseconds)
uint32 device_id # Device id

uint32 state # pin state mask
7 changes: 7 additions & 0 deletions msg/GpioOut.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# GPIO mask and state

uint64 timestamp # time since system start (microseconds)
uint32 device_id # Device id

uint32 mask # pin mask
uint32 state # pin state mask
4 changes: 4 additions & 0 deletions msg/GpioRequest.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Request GPIO mask to be read

uint64 timestamp # time since system start (microseconds)
uint32 device_id # Device id
Loading

0 comments on commit 8fe65c6

Please sign in to comment.