Browse Source

platforms/nuttx/src/px4/common/board_ctrl: Add handlers for vbus & shutdown lockout

Add kernel side ioctls and handlers for vbus state and managing shutdown lockout

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
v1.13.0-BW
Jukka Laitinen 3 years ago committed by Beat Küng
parent
commit
c43c71f4af
  1. 56
      platforms/nuttx/src/px4/common/board_ctrl.c
  2. 34
      platforms/nuttx/src/px4/common/include/px4_platform/board_ctrl.h

56
platforms/nuttx/src/px4/common/board_ctrl.c

@ -105,11 +105,8 @@ int board_ioctl(unsigned int cmd, uintptr_t arg) @@ -105,11 +105,8 @@ int board_ioctl(unsigned int cmd, uintptr_t arg)
*
************************************************************************************/
int launch_kernel_builtin(unsigned int cmd, unsigned long arg)
static int launch_kernel_builtin(int argc, char **argv)
{
builtinioclaunch_t *kcmd = (builtinioclaunch_t *)arg;
int argc = kcmd->argc;
char **argv = kcmd->argv;
int i;
FAR const struct builtin_s *builtin = NULL;
@ -123,13 +120,58 @@ int launch_kernel_builtin(unsigned int cmd, unsigned long arg) @@ -123,13 +120,58 @@ int launch_kernel_builtin(unsigned int cmd, unsigned long arg)
if (builtin) {
/* This is running in the userspace thread, created by nsh, and
called via boardctl. Call the main directly */
kcmd->ret = builtin->main(argc, argv);
return OK;
return builtin->main(argc, argv);
}
return ENOENT;
}
/************************************************************************************
* Name: platform_ioctl
*
* Description:
* handle all miscellaneous platform level ioctls
*
************************************************************************************/
static int platform_ioctl(unsigned int cmd, unsigned long arg)
{
int ret = PX4_OK;
switch (cmd) {
case PLATFORMIOCLAUNCH: {
platformioclaunch_t *data = (platformioclaunch_t *)arg;
data->ret = launch_kernel_builtin(data->argc, data->argv);
}
break;
case PLATFORMIOCVBUSSTATE: {
platformiocvbusstate_t *data = (platformiocvbusstate_t *)arg;
data->ret = px4_arch_gpioread(GPIO_OTGFS_VBUS) ? 0 : 1;
}
break;
case PLATFORMIOCINDICATELOCKOUT: {
platformioclockoutstate_t *data = (platformioclockoutstate_t *)arg;
px4_arch_configgpio(data->enabled ? GPIO_nARMED : GPIO_nARMED_INIT);
}
break;
case PLATFORMIOCGETLOCKOUT: {
platformioclockoutstate_t *data = (platformioclockoutstate_t *)arg;
data->enabled = px4_arch_gpioread(GPIO_nARMED);
}
break;
default:
ret = -ENOTTY;
break;
}
return ret;
}
/************************************************************************************
* Name: kernel_ioctl_initialize
*
@ -144,5 +186,5 @@ void kernel_ioctl_initialize(void) @@ -144,5 +186,5 @@ void kernel_ioctl_initialize(void)
ioctl_ptrs[i].ioctl_func = NULL;
}
px4_register_boardct_ioctl(_BUILTINIOCBASE, launch_kernel_builtin);
px4_register_boardct_ioctl(_PLATFORMIOCBASE, platform_ioctl);
}

34
platforms/nuttx/src/px4/common/include/px4_platform/board_ctrl.h

@ -34,6 +34,8 @@ @@ -34,6 +34,8 @@
#pragma once
#include <px4_platform_common/defines.h>
/* Encode the px4 boardctl ioctls in the following way:
* the highest 4-bits identifies the boardctl's used by this if
* the next 4-bits identifies the module which handles the ioctl
@ -48,20 +50,42 @@ @@ -48,20 +50,42 @@
#define _HRTIOCBASE IOCTL_IDX_TO_BASE(1)
#define _CRYPTOIOCBASE IOCTL_IDX_TO_BASE(2)
#define _PARAMIOCBASE IOCTL_IDX_TO_BASE(3)
#define _BUILTINIOCBASE IOCTL_IDX_TO_BASE(4)
#define _PLATFORMIOCBASE IOCTL_IDX_TO_BASE(4)
#define MAX_IOCTL_PTRS 5
/* The BUILTINIOCLAUNCH IOCTL is used to launch kernel side modules
/* The PLATFORMIOCLAUNCH IOCTL is used to launch kernel side modules
* from the user side code
*/
#define BUILTINIOCLAUNCH (_PX4_IOC(_BUILTINIOCBASE, 1))
#define PLATFORMIOCLAUNCH (_PX4_IOC(_PLATFORMIOCBASE, 1))
typedef struct builtinioclaunch {
typedef struct platformioclaunch {
int argc;
char **argv;
int ret;
} builtinioclaunch_t;
} platformioclaunch_t;
/* The PLATFORMIOCVBUSSTATE IOCTL is used to read USB VBUS state
* from the user side code
*/
#define PLATFORMIOCVBUSSTATE (_PX4_IOC(_PLATFORMIOCBASE, 2))
typedef struct platformiocvbusstate {
int ret;
} platformiocvbusstate_t;
/* These IOCTLs are used to set and read external lockout state
* from the user side code
*/
#define PLATFORMIOCINDICATELOCKOUT (_PX4_IOC(_PLATFORMIOCBASE, 3))
#define PLATFORMIOCGETLOCKOUT (_PX4_IOC(_PLATFORMIOCBASE, 4))
typedef struct platformioclockoutstate {
bool enabled;
} platformioclockoutstate_t;
typedef int (*ioctl_ptr_t)(unsigned int, unsigned long);

Loading…
Cancel
Save