summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-20 15:19:44 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-20 15:19:44 +0000
commit2d795267b97ca49c544ca4a38dbf3771d3cd4697 (patch)
tree84c0f2def09c2c2e7712cc448ed152cb3652ad4b
parent2beb149e9bbba41c18ec8b3d83c2ba81c39b35a0 (diff)
downloadpx4-nuttx-2d795267b97ca49c544ca4a38dbf3771d3cd4697.tar.gz
px4-nuttx-2d795267b97ca49c544ca4a38dbf3771d3cd4697.tar.bz2
px4-nuttx-2d795267b97ca49c544ca4a38dbf3771d3cd4697.zip
Add m9s12 serial logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3305 42af7a65-404d-4744-a932-0658087f49c3
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_lowputc.S107
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_serial.h94
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_start.S5
-rwxr-xr-xnuttx/configs/demo9s12ne64/include/board.h21
-rw-r--r--nuttx/drivers/usbhost/hid_parser.c22
-rw-r--r--nuttx/include/nuttx/usb/hid_parser.h98
6 files changed, 287 insertions, 60 deletions
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S b/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S
index e4bc7858c..a04d6a1d8 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S
+++ b/nuttx/arch/hc/src/m9s12/m9s12_lowputc.S
@@ -41,12 +41,65 @@
#include "up_internal.h"
#include "m9s12_internal.h"
-#include "m9s12_flash.h"
+#include "m9s12_sci.h"
+#include "m9s12_serial.h"
+
+#ifdef CONFIG_HCS12_SERIALMON
+# include "m9s12_flash.h"
+#endif
/**************************************************************************
* Private Definitions
**************************************************************************/
+/* Select SCI parameters for the selected console */
+
+#if defined(CONFIG_SCI0_SERIAL_CONSOLE)
+# define HCS12_CONSOLE_BASE HCS12_SCI0_BASE
+# define HCS12_CONSOLE_BAUD CONFIG_SCI0_BAUD
+# define HCS12_CONSOLE_BITS CONFIG_SCI0_BITS
+# define HCS12_CONSOLE_PARITY CONFIG_SCI0_PARITY
+# define HCS12_CONSOLE_2STOP CONFIG_SCI0_2STOP
+#elif defined(CONFIG_SCI1_SERIAL_CONSOLE)
+# define HCS12_CONSOLE_BASE HCS12_SCI1_BASE
+# define HCS12_CONSOLE_BAUD CONFIG_SCI1_BAUD
+# define HCS12_CONSOLE_BITS CONFIG_SCI1_BITS
+# define HCS12_CONSOLE_PARITY CONFIG_SCI1_PARITY
+# define HCS12_CONSOLE_2STOP CONFIG_SCI1_2STOP
+#else
+# warning "No CONFIG_SCIn_SERIAL_CONSOLE Setting"
+#endif
+
+/* Selete the SCIBR register value */
+
+#define CONSOLE_SCIBR_VALUE SCIBR_VALUE(HCS12_CONSOLE_BAUD)
+
+/* Select the SCICR1 register settings */
+
+#if HCS12_CONSOLE_BITS == 9
+# define UART_SCICR1_NBITS SCI_CR1_M
+#elif HCS12_CONSOLE_BITS == 8
+# define UART_SCICR1_NBITS 0
+#else
+# warning "Number of bits not supported"
+#endif
+
+#if HCS12_CONSOLE_PARITY == 0
+# define UART_SCICR1_PARITY 0
+#elif HCS12_CONSOLE_PARITY == 1
+# define UART_SCICR1_PARITY SCI_CR1_PE
+#elif HCS12_CONSOLE_PARITY == 2
+# define UART_SCICR1_PARITY (SCI_CR1_PE|SCI_CR1_PT)
+#else
+# error "ERROR: Invalid parity selection"
+#endif
+
+#if HCS12_CONSOLE_2STOP != 0
+# warning "Only a single stop bit supported"
+#endif
+
+#define CONSOLE_SCICR_VALUE (UART_SCICR1_NBITS|UART_SCICR1_PARITY)
+
/**************************************************************************
* Private Types
**************************************************************************/
@@ -82,7 +135,31 @@ up_lowsetup:
#ifdef CONFIG_HCS12_SERIALMON
rts
#else
-# error "up_lowsetup not implemented"
+ /* Disable the console */
+
+ ldab #0
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR1_OFFSET)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR2_OFFSET)
+
+ /* Set the BAUD pre-scaler value */
+
+ ldab #(CONSOLE_SCIBR_VALUE >> 8)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_BDH_OFFSET)
+
+ ldab #(CONSOLE_SCIBR_VALUE & 0xff)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_BDL_OFFSET)
+
+ /* Set number of bits, parity, stop bits, etc. */
+
+ ldab #CONSOLE_SCICR_VALUE
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR1_OFFSET)
+
+ /* Enable transmitter and receiver */
+
+ ldab #(SCI_CR2_RE|SCI_CR2_TE)
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_CR2_OFFSET)
+ rts
+
#endif
.size up_lowsetup, . - up_lowsetup
@@ -97,7 +174,31 @@ up_lowputc:
#ifdef CONFIG_HCS12_SERIALMON
jmp PutChar
#else
-# error "up_lowputc not implemented"
+# if HCS12_CONSOLE_BITS == 9
+ staa 1, -sp
+# endif
+
+ /* Wait for the transmit data register to be available (TRDE==1) */
+
+.Lwait:
+ ldaa (HCS12_CONSOLE_BASE+HCS12_SCI_SR1_OFFSET)
+ bita #SCI_SR1_TDRE
+ bne .Lwait
+
+ /* Then write the byte to the transmit data register */
+
+# if HCS12_CONSOLE_BITS == 9
+ ldaa 1, sp+
+ bita #(0x01)
+ bne .L8bit
+ ldaa #SCI_DRH_T8
+ bra .Lwrdrh
+.L8bit:
+ ldaa #0
+.Lwrdrh:
+ staa (HCS12_CONSOLE_BASE+HCS12_SCI_DRH_OFFSET)
+# endif
+ stab (HCS12_CONSOLE_BASE+HCS12_SCI_DRL_OFFSET)
rts
#endif
.size up_lowputc, . - up_lowputc
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_serial.h b/nuttx/arch/hc/src/m9s12/m9s12_serial.h
new file mode 100755
index 000000000..107440616
--- /dev/null
+++ b/nuttx/arch/hc/src/m9s12/m9s12_serial.h
@@ -0,0 +1,94 @@
+/************************************************************************************
+ * arch/hc/src/m9s12/serial.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 __ARCH_HC_SRC_M9S12_CHIP_H
+#define __ARCH_HC_SRC_M9S12_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/board/board.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+/* Is there a SCI enabled? */
+
+#if defined(CONFIG_SCI0_DISABLE) && defined(CONFIG_SCI1_DISABLE)
+# error "No SCIs enabled"
+#endif
+
+/* Is there a serial console? */
+
+#if defined(CONFIG_SCI0_SERIAL_CONSOLE) && !defined(CONFIG_SCI0_DISABLE)
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#elif defined(CONFIG_SCI1_SERIAL_CONSOLE) && !defined(CONFIG_SCI1_DISABLE)
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#else
+# warning "No valid CONFIG_SCIn_SERIAL_CONSOLE Setting"
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# undef HAVE_CONSOLE
+#endif
+
+/* BAUD *****************************************************************************/
+/* Baud calculations. The SCI module is driven by the BUSCLK. The SCIBR
+ * register value divides down the BUSCLK to accomplish the required BAUD.
+ *
+ * BAUD = HCS12_BUSCLK / (16 * SCIBR)
+ * SCIBR = HCS12_BUSCLK / (16 * BAUD)
+ */
+
+#define SCIBR_VALUE(b) ((HCS12_BUSCLK * (b) + ((b) << 3))/((b) << 4))
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_HC_SRC_M9S12_CHIP_H */
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_start.S b/nuttx/arch/hc/src/m9s12/m9s12_start.S
index b7585d75b..ad5a39c0d 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_start.S
+++ b/nuttx/arch/hc/src/m9s12/m9s12_start.S
@@ -40,6 +40,8 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
+
#include "m9s12_internal.h"
#include "m9s12_mmc.h"
#include "m9s12_crg.h"
@@ -118,8 +120,9 @@
/* Set the multipler and divider and enable the PLL */
bclr *HCS12_CRG_PLLCTL #CRG_PLLCTL_PLLON
- ldab #15
+ ldab #HCS12_SYNR_VALUE
stab HCS12_CRG_SYNR
+ ldab #HCS12_REFDV_VALUE
stab HCS12_CRG_REFDV
bset *HCS12_CRG_PLLCTL #CRG_PLLCTL_PLLON
diff --git a/nuttx/configs/demo9s12ne64/include/board.h b/nuttx/configs/demo9s12ne64/include/board.h
index 9420b67dd..ee190731c 100755
--- a/nuttx/configs/demo9s12ne64/include/board.h
+++ b/nuttx/configs/demo9s12ne64/include/board.h
@@ -51,9 +51,30 @@
************************************************************************************/
/* Clocking *************************************************************************/
+/* Frequency of the crystal oscillator */
#define HCS12_OSCCLK 16000000 /* 16MHz */
+/* PLL Settings
+ *
+ * SYNR register controls the multiplication factor of the PLL. If the PLL is on, the
+ * count in the loop divider (SYNR) register effectively multiplies up the PLL clock
+ * (PLLCLK) from the reference frequency by 2 x (SYNR+1). PLLCLK will not be below
+ * the minimum VCO frequency (fSCM).
+ *
+ * The REFDV register provides a finer granularity for the PLL multiplier steps. The
+ * count in the reference divider divides OSCCLK frequency by REFDV + 1.
+ *
+ * PLLCLK = 2 * OSCCLK * (SYNR + 1) / (REFDV + 1)
+ *
+ * If (PLLSEL = 1), Bus Clock = PLLCLK / 2
+ */
+
+#define HCS12_SYNR_VALUE 0x15
+#define HCS12_REFDV_VALUE 0x15
+#define HCS12_PLLCLK (2*HCS12_OSCCLK*(HCS12_SYNR+1)/(HCS12_REFDV+1))
+#define HCS12_BUSCLK (HSC12_PLLCLK/2)
+
/* LED definitions ******************************************************************/
/* The DEMO9S12NE64 board has 2 LEDs that we will encode as: */
diff --git a/nuttx/drivers/usbhost/hid_parser.c b/nuttx/drivers/usbhost/hid_parser.c
index 269aa73de..a0ca6066b 100644
--- a/nuttx/drivers/usbhost/hid_parser.c
+++ b/nuttx/drivers/usbhost/hid_parser.c
@@ -80,11 +80,11 @@ struct hid_state_s
int hid_parsereport(FAR const uint8_t *report, int rptlen,
hid_rptfilter_t filter, FAR struct hid_rptinfo_s *rptinfo)
{
- struct hid_state_s state[HID_STATETABLE_STACK_DEPTH];
+ struct hid_state_s state[CONFIG_HID_STATEDEPTH];
struct hid_state_s *currstate = &state[0];
struct hid_collectionpath_s *collectionpath = NULL;
struct hid_rptsizeinfo_s *rptidinfo = &rptinfo->rptsize[0];
- uint16_t usage[HID_USAGE_STACK_DEPTH];
+ uint16_t usage[CONFIG_HID_USAGEDEPTH];
uint8_t nusage = 0;
struct hid_range_s usage_range = { 0, 0 };
int i;
@@ -134,7 +134,7 @@ int hid_parsereport(FAR const uint8_t *report, int rptlen,
switch (item & ~USBHID_RPTITEM_SIZE_MASK)
{
case USBHID_GLOBAL_PUSH_PREFIX:
- if (currstate == &state[HID_STATETABLE_STACK_DEPTH - 1])
+ if (currstate == &state[CONFIG_HID_STATEDEPTH - 1])
{
return -E2BIG;
}
@@ -213,7 +213,7 @@ int hid_parsereport(FAR const uint8_t *report, int rptlen,
if (rptidinfo == NULL)
{
- if (rptinfo->nreports == HID_MAX_REPORT_IDS)
+ if (rptinfo->nreports == CONFIG_HID_MAXIDS)
{
return -EINVAL;
}
@@ -229,7 +229,7 @@ int hid_parsereport(FAR const uint8_t *report, int rptlen,
break;
case USBHID_LOCAL_USAGE_PREFIX:
- if (nusage == HID_USAGE_STACK_DEPTH)
+ if (nusage == CONFIG_HID_USAGEDEPTH)
{
return -E2BIG;
}
@@ -258,7 +258,7 @@ int hid_parsereport(FAR const uint8_t *report, int rptlen,
while (collectionpath->parent != NULL)
{
- if (collectionpath == &rptinfo->collectionpaths[HID_MAX_COLLECTIONS - 1])
+ if (collectionpath == &rptinfo->collectionpaths[CONFIG_HID_MAXCOLLECTIONS - 1])
{
return -EINVAL;
}
@@ -332,15 +332,15 @@ int hid_parsereport(FAR const uint8_t *report, int rptlen,
tag = (item & ~USBHID_RPTITEM_SIZE_MASK);
if (tag == USBHID_MAIN_INPUT_PREFIX)
{
- newitem.type = USBHID_REPORTTYPE_INPUT;
+ newitem.type = HID_REPORT_ITEM_IN;
}
else if (tag == USBHID_MAIN_OUTPUT_PREFIX)
{
- newitem.type = USBHID_REPORTTYPE_OUTPUT;
+ newitem.type = HID_REPORT_ITEM_OUT;
}
else
{
- newitem.type = USBHID_REPORTTYPE_FEATURE;
+ newitem.type = HID_REPORT_ITEM_FEATURE;
}
newitem.bitoffset = rptidinfo->size[newitem.type];
@@ -355,7 +355,7 @@ int hid_parsereport(FAR const uint8_t *report, int rptlen,
if ((data & USBHID_MAIN_CONSTANT) == 0 && filter(&newitem))
{
- if (rptinfo->nitems == HID_MAX_REPORTITEMS)
+ if (rptinfo->nitems == CONFIG_HID_MAXITEMS)
{
return -EINVAL;
}
@@ -515,7 +515,7 @@ void hid_putitem(FAR uint8_t *report, struct hid_rptitem_s *item)
size_t hid_reportsize(FAR struct hid_rptinfo_s *rptinfo, uint8_t id, uint8_t rpttype)
{
int i;
- for (i = 0; i < HID_MAX_REPORT_IDS; i++)
+ for (i = 0; i < CONFIG_HID_MAXIDS; i++)
{
size_t size = rptinfo->rptsize[i].size[rpttype];
diff --git a/nuttx/include/nuttx/usb/hid_parser.h b/nuttx/include/nuttx/usb/hid_parser.h
index 23cbf390c..07e1e5765 100644
--- a/nuttx/include/nuttx/usb/hid_parser.h
+++ b/nuttx/include/nuttx/usb/hid_parser.h
@@ -44,64 +44,72 @@
/* Configuration ************************************************************/
-/* HID_STATETABLE_STACK_DEPTH
+/* CONFIG_HID_STATEDEPTH
* Constant indicating the maximum stack depth of the state table. A larger
* state table allows for more PUSH/POP report items to be nested, but
* consumes more memory. By default this is set to 2 levels (allowing non-
* nested PUSH items) but this can be overridden by defining
- * HID_STATETABLE_STACK_DEPTH in the Nuttx config file.
+ * CONFIG_HID_STATEDEPTH in the Nuttx config file.
*
- * HID_USAGE_STACK_DEPTH
+ * CONFIG_HID_USAGEDEPTH
* Constant indicating the maximum stack depth of the usage table. A larger
* usage table allows for more USAGE items to be indicated sequentially for
* REPORT COUNT entries of more than one, but requires more stack space. By
* default this is set to 8 levels (allowing for a report item with a count
- * of 8) but this can be overridden by defining HID_USAGE_STACK_DEPTH to
+ * of 8) but this can be overridden by defining CONFIG_HID_USAGEDEPTH to
* in the Nuttx config file.
*
- * HID_MAX_COLLECTIONS
+ * CONFIG_HID_MAXCOLLECTIONS
* Constant indicating the maximum number of COLLECTION items (nested or
* unnested) that can be processed in the report item descriptor. A large
* value allows for more COLLECTION items to be processed, but consumes
* more memory. By default this is set to 10 collections, but this can be
- * overridden by defining HID_MAX_COLLECTIONS in the Nuttx config file.
+ * overridden by defining CONFIG_HID_MAXCOLLECTIONS in the Nuttx config file.
*
+ * CONFIG_HID_MAXITEMS
* Constant indicating the maximum number of report items (IN, OUT or
* FEATURE) that can be processed in the report item descriptor and stored
* in the user HID Report Info structure. A large value allows
* for more report items to be stored, but consumes more memory. By default
* this is set to 20 items, but this can be overridden by defining
- * HID_MAX_REPORTITEMS in the Nuttx config file.
+ * CONFIG_HID_MAXITEMS in the Nuttx config file.
*
+ * CONFIG_HID_MAXIDS
* Constant indicating the maximum number of unique report IDs that can be
* processed in the report item descriptor for the report size information
* array in the user HID Report Info structure. A large value allows for
* more report ID report sizes to be stored, but consumes more memory. By
* default this is set to 10 items, but this can be overridden by defining
- * HID_MAX_REPORT_IDS in the Nuttx config file. Note that IN, OUT and FEATURE
+ * CONFIG_HID_MAXIDS in the Nuttx config file. Note that IN, OUT and FEATURE
* items sharing the same report ID consume only one size item in the array.
*/
-#ifndef HID_STATETABLE_STACK_DEPTH
-# define HID_STATETABLE_STACK_DEPTH 2
+#ifndef CONFIG_HID_STATEDEPTH
+# define CONFIG_HID_STATEDEPTH 2
#endif
-#ifndef HID_USAGE_STACK_DEPTH
-# define HID_USAGE_STACK_DEPTH 8
+#ifndef CONFIG_HID_USAGEDEPTH
+# define CONFIG_HID_USAGEDEPTH 8
#endif
-#ifndef HID_MAX_COLLECTIONS
-# define HID_MAX_COLLECTIONS 10
+#ifndef CONFIG_HID_MAXCOLLECTIONS
+# define CONFIG_HID_MAXCOLLECTIONS 10
#endif
-#ifndef HID_MAX_REPORTITEMS
-# define HID_MAX_REPORTITEMS 20
+#ifndef CONFIG_HID_MAXITEMS
+# define CONFIG_HID_MAXITEMS 20
#endif
-#ifndef HID_MAX_REPORT_IDS
-# define HID_MAX_REPORT_IDS 10
+#ifndef CONFIG_HID_MAXIDS
+# define CONFIG_HID_MAXIDS 10
#endif
+/* HID report type indices */
+
+#define HID_REPORT_ITEM_IN 0
+#define HID_REPORT_ITEM_OUT 1
+#define HID_REPORT_ITEM_FEATURE 2
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -112,8 +120,8 @@
struct hid_range_s
{
- uint32_t min; /* Minimum value for the attribute. */
- uint32_t max; /* Maximum value for the attribute. */
+ uint32_t min; /* Minimum value for the attribute */
+ uint32_t max; /* Maximum value for the attribute */
};
/* HID Parser Report Item Unit Structure. Type define for the Unit attributes
@@ -122,8 +130,8 @@ struct hid_range_s
struct hid_unit_t
{
- uint32_t type; /* Unit type (refer to HID specifications for details). */
- uint8_t exponent; /* Unit exponent (refer to HID specifications for details). */
+ uint32_t type; /* Unit type (refer to HID spec for details) */
+ uint8_t exponent; /* Unit exponent (refer to HID spec for details) */
};
/* HID Parser Report Item Usage Structure. Type define for the Usage
@@ -132,8 +140,8 @@ struct hid_unit_t
struct hid_usage_t
{
- uint16_t page; /* Usage page of the report item. */
- uint16_t usage; /* Usage of the report item. */
+ uint16_t page; /* Usage page of the report item */
+ uint16_t usage; /* Usage of the report item */
};
/* HID Parser Report Item Collection Path Structure. Type define for a
@@ -143,9 +151,9 @@ struct hid_usage_t
struct hid_collectionpath_s
{
- uint8_t type; /* Collection type (e.g. "Generic Desktop"). */
- struct hid_usage_t usage; /* Collection usage. */
- struct hid_collectionpath_s *parent; /* Reference to parent collection, or NULL if root collection. */
+ uint8_t type; /* Collection type (e.g. "Generic Desktop") */
+ struct hid_usage_t usage; /* Collection usage */
+ struct hid_collectionpath_s *parent; /* Reference to parent collection (NULL if root) */
};
/* HID Parser Report Item Attributes Structure. Type define for all the data
@@ -154,11 +162,11 @@ struct hid_collectionpath_s
struct hid_rptitem_attributes_s
{
- uint8_t bitsize; /* Size in bits of the report item's data. */
- struct hid_usage_t usage; /* Usage of the report item. */
- struct hid_unit_t unit; /* Unit type and exponent of the report item. */
- struct hid_range_s logical; /* Logical minimum and maximum of the report item. */
- struct hid_range_s physical; /* Physical minimum and maximum of the report item. */
+ uint8_t bitsize; /* Size in bits of the report item's data */
+ struct hid_usage_t usage; /* Usage of the report item */
+ struct hid_unit_t unit; /* Unit type and exponent of the report item */
+ struct hid_range_s logical; /* Logical minimum and maximum of the report item */
+ struct hid_range_s physical; /* Physical minimum and maximum of the report item */
};
/* HID Parser Report Item Details Structure. Type define for a report item
@@ -167,14 +175,14 @@ struct hid_rptitem_attributes_s
struct hid_rptitem_s
{
- uint16_t bitoffset; /* Bit offset in the IN, OUT or FEATURE report of the item. */
- uint8_t type; /* Report item type, a value in HID_ReportItemTypes_t. */
- uint16_t flags; /* Item data flags, a mask of HID_IOF_* constants. */
- uint8_t id; /* Report ID this item belongs to, or 0x00 if device has only one report */
- struct hid_collectionpath_s *collectionpath; /* Collection path of the item. */
- struct hid_rptitem_attributes_s attrib; /* Report item attributes. */
+ uint16_t bitoffset; /* Bit offset in IN, OUT or FEATURE report of the item */
+ uint8_t type; /* Report item type */
+ uint16_t flags; /* Item data flags */
+ uint8_t id; /* Report ID this item belongs to (0 if only one report) */
+ struct hid_collectionpath_s *collectionpath; /* Collection path of the item */
+ struct hid_rptitem_attributes_s attrib; /* Report item attributes */
uint32_t value; /* Current value of the report item */
- uint32_t previous; /* Previous value of the report item. */
+ uint32_t previous; /* Previous value of the report item */
};
/* HID Parser Report Size Structure. Type define for a report item size
@@ -183,8 +191,8 @@ struct hid_rptitem_s
struct hid_rptsizeinfo_s
{
- uint8_t id; /* Report ID of the report within the HID interface. */
- uint16_t size[3]; /* Number of bits in each report type for the given Report ID */
+ uint8_t id; /* Report ID of the report within the HID interface */
+ uint16_t size[3]; /* Number of bits in report type for the Report ID */
};
/* HID Parser State Structure. Type define for a complete processed HID
@@ -196,16 +204,16 @@ struct hid_rptinfo_s
/* nitems is the number of report items stored in the report items array (rptitems[]). */
uint8_t nitems;
- struct hid_rptitem_s items[HID_MAX_REPORTITEMS];
+ struct hid_rptitem_s items[CONFIG_HID_MAXITEMS];
/* All collection items, referenced by the report items. */
- struct hid_collectionpath_s collectionpaths[HID_MAX_COLLECTIONS];
+ struct hid_collectionpath_s collectionpaths[CONFIG_HID_MAXCOLLECTIONS];
uint8_t nreports; /* Number of reports within the HID interface */
- struct hid_rptsizeinfo_s rptsize[HID_MAX_REPORT_IDS]; /* Report sizes for each report in the interface */
+ struct hid_rptsizeinfo_s rptsize[CONFIG_HID_MAXIDS]; /* Report sizes for each report in the interface */
uint16_t maxrptsize; /* Largest report that the attached device will generate, in bits */
- bool haverptid; /* Device has at least one REPORT ID in its HID report. */
+ bool haverptid; /* Device has at least one REPORT ID in its HID report */
};
/* Callback routine for the HID Report Parser. This callback must be