forked from nuttx/nuttx-update
drivers/rf/dat-31r5-sp.c: dd support to the DAT-31R5-SP+ digital attenuator. Creates a the new device driver directory drivers/rf/ to support drivers related to RF peripherals. It also adds support for the DAT-31R5-SP+ digital attenuator.
This commit is contained in:
parent
822bb06967
commit
f08ab217b0
10 changed files with 627 additions and 3 deletions
|
@ -7237,12 +7237,15 @@ if [ -x "$WINELOADER" ]; then exec "$WINELOADER" "$appname" "$@"; fi
|
|||
<li>NuttX is a registered trademark of Gregory Nutt.</li>
|
||||
<li>ARM, ARM7 ARM7TDMI, ARM9, ARM920T, ARM926EJS, Cortex-M3 are trademarks of Advanced RISC Machines, Limited.</li>
|
||||
<li>Beaglebone is a trademark of GHI.</li>
|
||||
<li>BSD is a trademark of the University of California, Berkeley, USA.</li>
|
||||
<li>Cygwin is a trademark of Red Hat, Incorporated.</li>
|
||||
<li>Linux is a registered trademark of Linus Torvalds.</li>
|
||||
<li>Eagle-100 is a trademark of <a href=" http://www.micromint.com/">Micromint USA, LLC</a>.
|
||||
<li>EnergyLite is a trademark of STMicroelectronics.</li>
|
||||
<li>EFM32 is a trademark of Silicon Laboratories, Inc.</li>
|
||||
<li>LPC2148 is a trademark of NXP Semiconductors.</li>
|
||||
<li>POSIX is a trademark of the Institute of Electrical and Electronic Engineers, Inc.</li>
|
||||
<li>RISC-V is a registration pending trade mark of the RISC-V Foundation.</li>
|
||||
<li>Sitara is a trademark of Texas Instruments Incorporated.</li>
|
||||
<li>TI is a tradename of Texas Instruments Incorporated.</li>
|
||||
<li>Tiva is a trademark of Texas Instruments Incorporated.</li>
|
||||
|
|
|
@ -406,3 +406,13 @@ menuconfig SPECIFIC_DRIVERS
|
|||
if SPECIFIC_DRIVERS
|
||||
source drivers/platform/Kconfig
|
||||
endif # SPECIFIC_DRIVERS
|
||||
|
||||
menuconfig DRIVERS_RF
|
||||
bool "RF Device Support"
|
||||
default n
|
||||
---help---
|
||||
Drivers for various RF devices
|
||||
|
||||
if DRIVERS_RF
|
||||
source drivers/rf/Kconfig
|
||||
endif # DRIVERS_RF
|
||||
|
|
|
@ -81,6 +81,7 @@ include video$(DELIM)Make.defs
|
|||
include wireless$(DELIM)Make.defs
|
||||
include contactless$(DELIM)Make.defs
|
||||
include 1wire$(DELIM)Make.defs
|
||||
include rf$(DELIM)Make.defs
|
||||
|
||||
ifeq ($(CONFIG_SPECIFIC_DRIVERS),y)
|
||||
include platform$(DELIM)Make.defs
|
||||
|
|
12
drivers/rf/Kconfig
Normal file
12
drivers/rf/Kconfig
Normal file
|
@ -0,0 +1,12 @@
|
|||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see the file kconfig-language.txt in the NuttX tools repository.
|
||||
#
|
||||
|
||||
config RF_DAT31R5SP
|
||||
bool "Mini-Circuits DAT-31R5-SP digital attenuator support"
|
||||
default n
|
||||
select SPI
|
||||
---help---
|
||||
Enable driver support for the Mini-Circuits DAT-31R5-SP digital
|
||||
attenuator.
|
57
drivers/rf/Make.defs
Normal file
57
drivers/rf/Make.defs
Normal file
|
@ -0,0 +1,57 @@
|
|||
############################################################################
|
||||
# drivers/rf/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011-2012, 2015-2018 Gregory Nutt. All rights reserved.
|
||||
# Copyright (C) 2019 Augusto Fraga Giachero. All rights reserved.
|
||||
# Author: Augusto Fraga Giachero <afg@augustofg.net>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name NuttX nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Include rf drivers
|
||||
|
||||
RFDEPPATH =
|
||||
RFVPATH =
|
||||
|
||||
ifeq ($(CONFIG_DRIVERS_RF),y)
|
||||
|
||||
ifeq ($(CONFIG_SPI),y)
|
||||
|
||||
ifeq ($(CONFIG_RF_DAT31R5SP),y)
|
||||
CSRCS += dat-31r5-sp.c
|
||||
RFDEPPATH = --dep-path rf
|
||||
RFVPATH = :rf
|
||||
endif
|
||||
|
||||
endif # CONFIG_SPI
|
||||
|
||||
endif # CONFIG_DRIVERS_RF
|
||||
|
||||
DEPPATH += $(RFDEPPATH)
|
||||
VPATH += $(RFVPATH)
|
298
drivers/rf/dat-31r5-sp.c
Normal file
298
drivers/rf/dat-31r5-sp.c
Normal file
|
@ -0,0 +1,298 @@
|
|||
/****************************************************************************
|
||||
* drivers/rf/dat-31r5-sp.c
|
||||
* Character driver for the Mini-Circuits DAT-31R5-SP+ digital step
|
||||
* attenuator.
|
||||
*
|
||||
* Copyright (C) 2019, Augusto Fraga Giachero. All rights reserved.
|
||||
* Author: Augusto Fraga Giachero <afg@augustofg.net>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/rf/ioctl.h>
|
||||
#include <nuttx/rf/attenuator.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_SPI) && defined(CONFIG_RF_DAT31R5SP)
|
||||
|
||||
#ifndef CONFIG_DAT31R5SP_SPI_FREQUENCY
|
||||
# define CONFIG_DAT31R5SP_SPI_FREQUENCY 1000000
|
||||
#endif
|
||||
|
||||
#define DAT31R5SP_SPI_MODE (SPIDEV_MODE0) /* SPI Mode 0: CPOL=0,CPHA=0 */
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
struct dat31r5sp_dev_s
|
||||
{
|
||||
FAR struct spi_dev_s *spi; /* Saved SPI driver instance */
|
||||
int spidev;
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/* Character driver methods */
|
||||
|
||||
static int dat31r5sp_open(FAR struct file *filep);
|
||||
static int dat31r5sp_close(FAR struct file *filep);
|
||||
static ssize_t dat31r5sp_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen);
|
||||
static ssize_t dat31r5sp_write(FAR struct file *filep,
|
||||
FAR const char *buffer, size_t buflen);
|
||||
static int dat31r5sp_ioctl(FAR struct file *filep, int cmd,
|
||||
unsigned long arg);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const struct file_operations g_dat31r5sp_fops =
|
||||
{
|
||||
dat31r5sp_open,
|
||||
dat31r5sp_close,
|
||||
dat31r5sp_read,
|
||||
dat31r5sp_write,
|
||||
NULL,
|
||||
dat31r5sp_ioctl,
|
||||
NULL
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_configspi
|
||||
*
|
||||
* Description:
|
||||
* Configure the SPI instance for to match the DAT-31R5-SP+
|
||||
* specifications
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline void dat31r5sp_configspi(FAR struct spi_dev_s *spi)
|
||||
{
|
||||
SPI_SETMODE(spi, DAT31R5SP_SPI_MODE);
|
||||
SPI_SETBITS(spi, 8);
|
||||
SPI_HWFEATURES(spi, 0);
|
||||
SPI_SETFREQUENCY(spi, CONFIG_DAT31R5SP_SPI_FREQUENCY);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_set_attenuation
|
||||
*
|
||||
* Description:
|
||||
* Set the attenuation level in dB (16.16 bits fixed point).
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void dat31r5sp_set_attenuation(FAR struct dat31r5sp_dev_s *priv,
|
||||
b16_t attenuation)
|
||||
{
|
||||
SPI_LOCK(priv->spi, true);
|
||||
|
||||
dat31r5sp_configspi(priv->spi);
|
||||
|
||||
SPI_SELECT(priv->spi, priv->spidev, false);
|
||||
|
||||
/* Convert the attenuation value from 16.16 bits to 5.1 bits. */
|
||||
|
||||
SPI_SEND(priv->spi, (uint8_t)(attenuation >> 15));
|
||||
|
||||
/* Send a pulse to the LE pin */
|
||||
|
||||
SPI_SELECT(priv->spi, priv->spidev, true);
|
||||
up_udelay(1);
|
||||
SPI_SELECT(priv->spi, priv->spidev, false);
|
||||
|
||||
SPI_LOCK(priv->spi, false);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_open
|
||||
*
|
||||
* Description:
|
||||
* This function is called whenever the DAT-31R5-SP+ device is
|
||||
* opened.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int dat31r5sp_open(FAR struct file *filep)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_close
|
||||
*
|
||||
* Description:
|
||||
* This function is called whenever the DAT-31R5-SP+ device is
|
||||
* closed.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int dat31r5sp_close(FAR struct file *filep)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_write
|
||||
*
|
||||
* Description:
|
||||
* Write is not permited, only IOCTLs.
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t dat31r5sp_write(FAR struct file *filep, FAR const char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_read
|
||||
*
|
||||
* Description:
|
||||
* Read is ignored.
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t dat31r5sp_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_ioctl
|
||||
*
|
||||
* Description:
|
||||
* The only available ICTL is RFIOC_SETATT. It expects a struct
|
||||
* attenuator_control* as the argument to set the attenuation
|
||||
* level. The channel is ignored as the DAT-31R5-SP+ has just a
|
||||
* single attenuator.
|
||||
****************************************************************************/
|
||||
|
||||
static int dat31r5sp_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct dat31r5sp_dev_s *priv = inode->i_private;
|
||||
int ret = OK;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case RFIOC_SETATT:
|
||||
{
|
||||
FAR struct attenuator_control *att =
|
||||
(FAR struct attenuator_control *)((uintptr_t)arg);
|
||||
DEBUGASSERT(ptr != NULL);
|
||||
dat31r5sp_set_attenuation(priv, att->attenuation);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
sninfo("Unrecognized cmd: %d\n", cmd);
|
||||
ret = -ENOTTY;
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_register
|
||||
*
|
||||
* Description:
|
||||
* Register the dat31r5sp character device as 'devpath'.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int dat31r5sp_register(FAR const char *devpath,
|
||||
FAR struct spi_dev_s *spi,
|
||||
int spidev)
|
||||
{
|
||||
FAR struct dat31r5sp_dev_s *priv;
|
||||
int ret;
|
||||
|
||||
/* Sanity check */
|
||||
|
||||
DEBUGASSERT(spi != NULL);
|
||||
|
||||
/* Initialize the DAT-31R5-SP+ device structure */
|
||||
|
||||
priv = (FAR struct dat31r5sp_dev_s *)kmm_malloc(sizeof(struct dat31r5sp_dev_s));
|
||||
if (priv == NULL)
|
||||
{
|
||||
snerr("ERROR: Failed to allocate instance\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
priv->spi = spi;
|
||||
priv->spidev = spidev;
|
||||
|
||||
/* Clear the LE pin */
|
||||
|
||||
SPI_SELECT(priv->spi, priv->spidev, false);
|
||||
|
||||
/* Register the character driver */
|
||||
|
||||
ret = register_driver(devpath, &g_dat31r5sp_fops, 0666, priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("ERROR: Failed to register driver: %d\n", ret);
|
||||
kmm_free(priv);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -48,6 +48,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/* General ioctl definitions ************************************************/
|
||||
|
||||
/* Each NuttX ioctl commands are uint16_t's consisting of an 8-bit type
|
||||
* identifier and an 8-bit command number. All command type identifiers are
|
||||
* defined below:
|
||||
|
@ -94,6 +95,7 @@
|
|||
#define _PWRBASE (0x2700) /* Power-related ioctl commands */
|
||||
#define _FBIOCBASE (0x2800) /* Frame buffer character driver ioctl commands */
|
||||
#define _NXTERMBASE (0x2900) /* NxTerm character driver ioctl commands */
|
||||
#define _RFIOCBASE (0x2a00) /* RF devices ioctl commands */
|
||||
|
||||
/* boardctl() commands share the same number space */
|
||||
|
||||
|
@ -143,8 +145,8 @@
|
|||
*/
|
||||
#define FIOC_FILENAME _FIOC(0x0004) /* IN: FAR const char ** pointer
|
||||
* OUT: Pointer to a persistent file name
|
||||
* (Guaranteed to persist while the file
|
||||
* is open).
|
||||
* (Guaranteed to persist while the
|
||||
* file is open).
|
||||
*/
|
||||
#define FIOC_INTEGRITY _FIOC(0x0005) /* Run a consistency check on the
|
||||
* file system media.
|
||||
|
@ -197,7 +199,7 @@
|
|||
* IN: Pointer to pointer to void in
|
||||
* which to received the XIP base.
|
||||
* OUT: If media is directly accessible,
|
||||
* return (void*) base address
|
||||
* return (void *) base address
|
||||
* of device memory */
|
||||
#define BIOC_PROBE _BIOC(0x0002) /* Re-probe and interface; check for media
|
||||
* in the slot
|
||||
|
@ -269,6 +271,7 @@
|
|||
#define _MTDIOC(nr) _IOC(_MTDIOCBASE,nr)
|
||||
|
||||
/* Socket IOCTLs ************************************************************/
|
||||
|
||||
/* See include/nuttx/net/ioctl.h */
|
||||
|
||||
#define _SIOCVALID(c) (_IOC_TYPE(c)==_SIOCBASE)
|
||||
|
@ -306,6 +309,7 @@
|
|||
#define _CAIOC(nr) _IOC(_CAIOCBASE,nr)
|
||||
|
||||
/* NuttX USB CDC/ACM serial driver ioctl definitions ************************/
|
||||
|
||||
/* (see nuttx/power/battery.h) */
|
||||
|
||||
#define _BATIOCVALID(c) (_IOC_TYPE(c)==_BATIOCBASE)
|
||||
|
@ -318,24 +322,28 @@
|
|||
#define _QEIOC(nr) _IOC(_QEIOCBASE,nr)
|
||||
|
||||
/* NuttX Audio driver ioctl definitions *************************************/
|
||||
|
||||
/* (see nuttx/audio/audio.h) */
|
||||
|
||||
#define _AUDIOIOCVALID(c) (_IOC_TYPE(c)==_AUDIOIOCBASE)
|
||||
#define _AUDIOIOC(nr) _IOC(_AUDIOIOCBASE,nr)
|
||||
|
||||
/* LCD character driver ioctl definitions ***********************************/
|
||||
|
||||
/* (see nuttx/include/lcd/slcd_codec.h */
|
||||
|
||||
#define _LCDIOCVALID(c) (_IOC_TYPE(c)==_LCDIOCBASE)
|
||||
#define _LCDIOC(nr) _IOC(_LCDIOCBASE,nr)
|
||||
|
||||
/* Segment LCD driver ioctl definitions *************************************/
|
||||
|
||||
/* (see nuttx/include/lcd/slcd_codec.h */
|
||||
|
||||
#define _SLCDIOCVALID(c) (_IOC_TYPE(c)==_SLCDIOCBASE)
|
||||
#define _SLCDIOC(nr) _IOC(_SLCDIOCBASE,nr)
|
||||
|
||||
/* Wireless driver networki ioctl definitions *******************************/
|
||||
|
||||
/* (see nuttx/include/wireless/wireless.h */
|
||||
|
||||
#define _WLIOCVALID(c) (_IOC_TYPE(c)==_WLIOCBASE)
|
||||
|
@ -348,18 +356,21 @@
|
|||
#define _WLCIOC(nr) _IOC(_WLCIOCBASE,nr)
|
||||
|
||||
/* Application Config Data driver ioctl definitions *************************/
|
||||
|
||||
/* (see nuttx/include/configdata.h */
|
||||
|
||||
#define _CFGDIOCVALID(c) (_IOC_TYPE(c)==_CFGDIOCBASE)
|
||||
#define _CFGDIOC(nr) _IOC(_CFGDIOCBASE,nr)
|
||||
|
||||
/* Timer driver ioctl commands **********************************************/
|
||||
|
||||
/* (see nuttx/include/timer.h */
|
||||
|
||||
#define _TCIOCVALID(c) (_IOC_TYPE(c)==_TCIOCBASE)
|
||||
#define _TCIOC(nr) _IOC(_TCIOCBASE,nr)
|
||||
|
||||
/* Joystick driver ioctl definitions ***************************************/
|
||||
|
||||
/* Discrete Joystick (see nuttx/include/input/djoystick.h */
|
||||
|
||||
#define _JOYIOCVALID(c) (_IOC_SMASK(c)==_JOYBASE)
|
||||
|
@ -378,84 +389,98 @@
|
|||
* OUT: None */
|
||||
|
||||
/* RTC driver ioctl definitions *********************************************/
|
||||
|
||||
/* (see nuttx/include/rtc.h */
|
||||
|
||||
#define _RTCIOCVALID(c) (_IOC_TYPE(c)==_RTCBASE)
|
||||
#define _RTCIOC(nr) _IOC(_RTCBASE,nr)
|
||||
|
||||
/* Relay driver ioctl definitions *******************************************/
|
||||
|
||||
/* (see nuttx/power/relay.h */
|
||||
|
||||
#define _RELAYIOCVALID(c) (_IOC_TYPE(c)==_RELAYBASE)
|
||||
#define _RELAYIOC(nr) _IOC(_RELAYBASE,nr)
|
||||
|
||||
/* CAN driver ioctl definitions *********************************************/
|
||||
|
||||
/* (see nuttx/can/can.h */
|
||||
|
||||
#define _CANIOCVALID(c) (_IOC_TYPE(c)==_CANBASE)
|
||||
#define _CANIOC(nr) _IOC(_CANBASE,nr)
|
||||
|
||||
/* Button driver ioctl definitions ******************************************/
|
||||
|
||||
/* (see nuttx/input/buttons.h */
|
||||
|
||||
#define _BTNIOCVALID(c) (_IOC_TYPE(c)==_BTNBASE)
|
||||
#define _BTNIOC(nr) _IOC(_BTNBASE,nr)
|
||||
|
||||
/* User LED driver ioctl definitions ****************************************/
|
||||
|
||||
/* (see nuttx/leds/usersled.h */
|
||||
|
||||
#define _ULEDIOCVALID(c) (_IOC_TYPE(c)==_ULEDBASE)
|
||||
#define _ULEDIOC(nr) _IOC(_ULEDBASE,nr)
|
||||
|
||||
/* Zero Cross driver ioctl definitions **************************************/
|
||||
|
||||
/* (see nuttx/include/sensor/zerocross.h */
|
||||
|
||||
#define _ZCIOCVALID(c) (_IOC_TYPE(c)==_ZCBASE)
|
||||
#define _ZCIOC(nr) _IOC(_ZCBASE,nr)
|
||||
|
||||
/* Loop driver ioctl definitions ********************************************/
|
||||
|
||||
/* (see nuttx/include/fs/loop.h */
|
||||
|
||||
#define _LOOPIOCVALID(c) (_IOC_TYPE(c)==_LOOPBASE)
|
||||
#define _LOOPIOC(nr) _IOC(_LOOPBASE,nr)
|
||||
|
||||
/* Modem driver ioctl definitions *******************************************/
|
||||
|
||||
/* see nuttx/include/modem/ioctl.h */
|
||||
|
||||
#define _MODEMIOCVALID(c) (_IOC_TYPE(c)==_MODEMBASE)
|
||||
#define _MODEMIOC(nr) _IOC(_MODEMBASE,nr)
|
||||
|
||||
/* I2C driver ioctl definitions *********************************************/
|
||||
|
||||
/* see nuttx/include/i2c/i2c_master.h */
|
||||
|
||||
#define _I2CIOCVALID(c) (_IOC_TYPE(c)==_I2CBASE)
|
||||
#define _I2CIOC(nr) _IOC(_I2CBASE,nr)
|
||||
|
||||
/* SPI driver ioctl definitions *********************************************/
|
||||
|
||||
/* see nuttx/include/spi/spi_transfer.h */
|
||||
|
||||
#define _SPIIOCVALID(c) (_IOC_TYPE(c)==_SPIBASE)
|
||||
#define _SPIIOC(nr) _IOC(_SPIBASE,nr)
|
||||
|
||||
/* GPIO driver command definitions ******************************************/
|
||||
|
||||
/* see nuttx/include/ioexpander/gpio.h */
|
||||
|
||||
#define _GPIOCVALID(c) (_IOC_TYPE(c)==_GPIOBASE)
|
||||
#define _GPIOC(nr) _IOC(_GPIOBASE,nr)
|
||||
|
||||
/* Contactless driver ioctl definitions *************************************/
|
||||
|
||||
/* (see nuttx/include/contactless/ioctl.h */
|
||||
|
||||
#define _CLIOCVALID(c) (_IOC_TYPE(c)==_CLIOCBASE)
|
||||
#define _CLIOC(nr) _IOC(_CLIOCBASE,nr)
|
||||
|
||||
/* USB-C controller driver ioctl definitions ********************************/
|
||||
|
||||
/* (see nuttx/include/usb/xxx.h */
|
||||
|
||||
#define _USBCIOCVALID(c) (_IOC_TYPE(c)==_USBCBASE)
|
||||
#define _USBCIOC(nr) _IOC(_USBCBASE,nr)
|
||||
|
||||
/* 802.15.4 MAC driver ioctl definitions ************************************/
|
||||
|
||||
/* (see nuttx/include/wireless/ieee802154/ieee802154_mac.h */
|
||||
|
||||
#define _MAC802154IOCVALID(c) (_IOC_TYPE(c)==_MAC802154BASE)
|
||||
|
@ -476,6 +501,11 @@
|
|||
#define _NXTERMVALID(c) (_IOC_TYPE(c)==_NXTERMBASE)
|
||||
#define _NXTERMIOC(nr) _IOC(_NXTERMBASE,nr)
|
||||
|
||||
/* NuttX RF ioctl definitions (see nuttx/rf/ioctl.h) ************************/
|
||||
|
||||
#define _RFIOCVALID(c) (_IOC_TYPE(c)==_RFIOCBASE)
|
||||
#define _RFIOC(nr) _IOC(_RFIOCBASE,nr)
|
||||
|
||||
/* boardctl() command definitions *******************************************/
|
||||
|
||||
#define _BOARDIOCVALID(c) (_IOC_TYPE(c)==_BOARDBASE)
|
||||
|
|
68
include/nuttx/rf/attenuator.h
Normal file
68
include/nuttx/rf/attenuator.h
Normal file
|
@ -0,0 +1,68 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/rf/attenuator.h
|
||||
*
|
||||
* Copyright (C) 2019, Augusto Fraga Giachero. All rights reserved.
|
||||
* Author: Augusto Fraga Giachero <afg@augustofg.net>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __INCLUDE_NUTTX_RF_ATTENUATOR_H
|
||||
#define __INCLUDE_NUTTX_RF_ATTENUATOR_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <fixedmath.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Type Definitions
|
||||
****************************************************************************/
|
||||
|
||||
struct attenuator_control
|
||||
{
|
||||
b16_t attenuation;
|
||||
int channel;
|
||||
};
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __INCLUDE_NUTTX_RF_ATTENUATOR_H */
|
99
include/nuttx/rf/dat-31r5-sp.h
Normal file
99
include/nuttx/rf/dat-31r5-sp.h
Normal file
|
@ -0,0 +1,99 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/rf/dat-31r5-sp.h
|
||||
* Character driver for the Mini-Circuits DAT-31R5-SP+ digital step
|
||||
* attenuator.
|
||||
*
|
||||
* Copyright (C) 2019, Augusto Fraga Giachero. All rights reserved.
|
||||
* Author: Augusto Fraga Giachero <afg@augustofg.net>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __INCLUDE_NUTTX_RF_DAT_31R5_SP_H_
|
||||
#define __INCLUDE_NUTTX_RF_DAT_31R5_SP_H_
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/rf/ioctl.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: dat31r5sp_register
|
||||
*
|
||||
* Description:
|
||||
* Register the dat31r5sp character device as 'devpath'. WARNING:
|
||||
* the DAT-31R5-SP+ is not spi compatible because it hasn't a proper
|
||||
* chip-select input, but it can coexist with other devices on the
|
||||
* spi bus assuming that the LE (Latch Enable) is always 0 when the
|
||||
* device isn't selected. With LE=0 the internal shift-register will
|
||||
* store the last 6 bits sent through the bus, but it will only
|
||||
* change the attenuation level when LE=1. This driver sends the
|
||||
* attenuation bitstream and gives a small positive pulse to LE.
|
||||
*
|
||||
* Remember when implementing the corresponding spi select function
|
||||
* when selected == true LE should be 1, and when selected == false
|
||||
* LE should be 0.
|
||||
*
|
||||
* Input Parameters:
|
||||
* devpath - The full path to the driver to register. E.g., "/dev/att0"
|
||||
* spi - An instance of the SPI interface to use to communicate with
|
||||
* spidev - Number of the spi device (used to drive the Latch Enable pin).
|
||||
*
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno value on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int dat31r5sp_register(FAR const char *devpath,
|
||||
FAR struct spi_dev_s *spi,
|
||||
int spidev);
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __INCLUDE_NUTTX_RF_DAT_31R5_SP_H_ */
|
46
include/nuttx/rf/ioctl.h
Normal file
46
include/nuttx/rf/ioctl.h
Normal file
|
@ -0,0 +1,46 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/rf/ioctl.h
|
||||
*
|
||||
* Copyright (C) 2019, Augusto Fraga Giachero. All rights reserved.
|
||||
* Author: Augusto Fraga Giachero <afg@augustofg.net>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __INCLUDE_NUTTX_RF_IOCTL_H
|
||||
#define __INCLUDE_NUTTX_RF_IOCTL_H
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
|
||||
/* Generic IOCTLs commands used for digital attenuators */
|
||||
|
||||
#define RFIOC_SETATT _RFIOC(0x0001) /* Set the attenuation, Arg: struct attenuator_control* */
|
||||
|
||||
#endif
|
Loading…
Reference in a new issue