Add driver eg25-g sources

This commit is contained in:
dchvs 2021-01-21 22:34:57 -06:00
parent 4aa621754e
commit 480df7a9f4
28 changed files with 21910 additions and 0 deletions

70
README.md Normal file
View File

@ -0,0 +1,70 @@
# Quectel EG25-G GSM Modem
## Kernel Changes
This package requires the Spiri Mu kernel and modifications to the following files:
* drivers/usb/serial/option.c
* drivers/usb/serial/usb_wwan.c
* drivers/net/usb/qmi_wwan.c
* drivers/net/usb/Makefile
It also requires these new files:
* drivers/net/usb/GobiUSBNet.c
* drivers/net/usb/QMI.c
* drivers/net/usb/QMI.h
* drivers/net/usb/QMIDevice.c
* drivers/net/usb/QMIDevice.h
* drivers/net/usb/Structs.h
All these modifications and additions are part of the Spiri Mu kernel. The files are represented in https://git.spirirobotics.com/Spiri/mu_kernel_sources as symlinks from this repository.
## Installation
Clone the repository:
```
cd ~/git
git clone https://git.spirirobotics.com/Spiri/mu_packages.git
```
Create a udhcpc symbolic link:
```
cd /bin
sudo ln -s busybox udhcpc
```
Create udhcpc directories, copy in the script, and give it execution permission:
```
sudo mkdir -p /usr/share/udhcpc
sudo mkdir -p /etc/udhcpc/
sudo cp ~/git/mu_packages/eg25-g/default.script /usr/share/udhcpc
sudo cp ~/git/mu_packages/eg25-g/default.script /etc/udhcpc
sudo chmod +x /usr/share/default.script
sudo chmod +x /etc/udhcpc/default.script
```
Build the application:
```
cd ~/git/mu_packages/eg25-g/quectel-CM
make
```
## Running
The following command launches the package, with [apn-name] being substituted with the APN of the wireless provider. For BICS, the APN is bicsapn. To run this in the background, add & to the end of the command.
```
sudo ./git/mu_packages/eg25-g/quectel-CM/quectel -s [apn-name]
```
## Troubleshooting
If the modem is correctly connected to the system, the following command will show the GSM modem attaching to ttyUSB0, ttyUSB1, ttyUSB2, and ttyUSB3:
```
dmesg | grep GSM
```
If the modem has successfully connected to a tower and is being served an IP address, then the following command will show an IP address being served:
```
ifconfig eth1
```
## Documentation
* <a href="https://nextcloud.spirirobotics.com/f/3971">Cellular modem hardware design</a>
* <a href="https://nextcloud.spirirobotics.com/f/3970">Cellular modem PPP</a>
* <a href="https://nextcloud.spirirobotics.com/f/3968">Cellular modem AT commands</a>
* <a href="https://nextcloud.spirirobotics.com/f/3969">Cellular modem GNSS AT commands</a>

1437
drivers/net/usb/GobiUSBNet.c Normal file

File diff suppressed because it is too large Load Diff

43
drivers/net/usb/Makefile Normal file
View File

@ -0,0 +1,43 @@
#
# Makefile for USB Network drivers
#
obj-$(CONFIG_USB_CATC) += catc.o
obj-$(CONFIG_USB_KAWETH) += kaweth.o
obj-$(CONFIG_USB_PEGASUS) += pegasus.o
obj-$(CONFIG_USB_RTL8150) += rtl8150.o
obj-$(CONFIG_USB_RTL8152) += r8152.o
obj-$(CONFIG_USB_HSO) += hso.o
obj-$(CONFIG_USB_LAN78XX) += lan78xx.o
obj-$(CONFIG_USB_NET_AX8817X) += asix.o
asix-y := asix_devices.o asix_common.o ax88172a.o
obj-$(CONFIG_USB_NET_AX88179_178A) += ax88179_178a.o
obj-$(CONFIG_USB_NET_CDCETHER) += cdc_ether.o
obj-$(CONFIG_USB_NET_CDC_EEM) += cdc_eem.o
obj-$(CONFIG_USB_NET_DM9601) += dm9601.o
obj-$(CONFIG_USB_NET_SR9700) += sr9700.o
obj-$(CONFIG_USB_NET_SR9800) += sr9800.o
obj-$(CONFIG_USB_NET_SMSC75XX) += smsc75xx.o
obj-$(CONFIG_USB_NET_SMSC95XX) += smsc95xx.o
obj-$(CONFIG_USB_NET_GL620A) += gl620a.o
obj-$(CONFIG_USB_NET_NET1080) += net1080.o
obj-$(CONFIG_USB_NET_PLUSB) += plusb.o
obj-$(CONFIG_USB_NET_RNDIS_HOST) += rndis_host.o
obj-$(CONFIG_USB_NET_CDC_SUBSET_ENABLE) += cdc_subset.o
obj-$(CONFIG_USB_NET_ZAURUS) += zaurus.o
obj-$(CONFIG_USB_NET_MCS7830) += mcs7830.o
obj-$(CONFIG_USB_USBNET) += usbnet.o
obj-$(CONFIG_USB_NET_INT51X1) += int51x1.o
obj-$(CONFIG_USB_CDC_PHONET) += cdc-phonet.o
obj-$(CONFIG_USB_NET_KALMIA) += kalmia.o
obj-$(CONFIG_USB_IPHETH) += ipheth.o
obj-$(CONFIG_USB_SIERRA_NET) += sierra_net.o
obj-$(CONFIG_USB_NET_CX82310_ETH) += cx82310_eth.o
obj-$(CONFIG_USB_NET_CDC_NCM) += cdc_ncm.o
obj-$(CONFIG_USB_NET_HUAWEI_CDC_NCM) += huawei_cdc_ncm.o
obj-$(CONFIG_USB_VL600) += lg-vl600.o
obj-$(CONFIG_USB_NET_QMI_WWAN) += qmi_wwan.o
obj-$(CONFIG_USB_NET_CDC_MBIM) += cdc_mbim.o
obj-$(CONFIG_USB_NET_CH9200) += ch9200.o
obj-y += GobiNet.o
GobiNet-objs := GobiUSBNet.o QMIDevice.o QMI.o

1343
drivers/net/usb/QMI.c Normal file

File diff suppressed because it is too large Load Diff

314
drivers/net/usb/QMI.h Normal file
View File

@ -0,0 +1,314 @@
/*===========================================================================
FILE:
QMI.h
DESCRIPTION:
Qualcomm QMI driver header
FUNCTIONS:
Generic QMUX functions
ParseQMUX
FillQMUX
Generic QMI functions
GetTLV
ValidQMIMessage
GetQMIMessageID
Get sizes of buffers needed by QMI requests
QMUXHeaderSize
QMICTLGetClientIDReqSize
QMICTLReleaseClientIDReqSize
QMICTLReadyReqSize
QMIWDSSetEventReportReqSize
QMIWDSGetPKGSRVCStatusReqSize
QMIDMSGetMEIDReqSize
QMICTLSyncReqSize
Fill Buffers with QMI requests
QMICTLGetClientIDReq
QMICTLReleaseClientIDReq
QMICTLReadyReq
QMIWDSSetEventReportReq
QMIWDSGetPKGSRVCStatusReq
QMIDMSGetMEIDReq
QMICTLSetDataFormatReq
QMICTLSyncReq
Parse data from QMI responses
QMICTLGetClientIDResp
QMICTLReleaseClientIDResp
QMIWDSEventResp
QMIDMSGetMEIDResp
Copyright (c) 2011, Code Aurora Forum. All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* 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.
* Neither the name of Code Aurora Forum 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.
===========================================================================*/
#pragma once
/*=========================================================================*/
// Definitions
/*=========================================================================*/
extern int debug;
// DBG macro
#define DBG( format, arg... ) do { \
if (debug == 1)\
{ \
printk( KERN_INFO "GobiNet::%s " format, __FUNCTION__, ## arg ); \
} }while(0)
#if 0
#define VDBG( format, arg... ) do { \
if (debug == 1)\
{ \
printk( KERN_INFO "GobiNet::%s " format, __FUNCTION__, ## arg ); \
} } while(0)
#else
#define VDBG( format, arg... ) do { } while(0)
#endif
// QMI Service Types
#define QMICTL 0
#define QMIWDS 1
#define QMIDMS 2
#define QMIWDA 0x1A
#define u8 unsigned char
#define u16 unsigned short
#define u32 unsigned int
#define u64 unsigned long long
#define bool u8
#define true 1
#define false 0
#define ENOMEM 12
#define EFAULT 14
#define EINVAL 22
#ifndef ENOMSG
#define ENOMSG 42
#endif
#define ENODATA 61
#define TLV_TYPE_LINK_PROTO 0x10
/*=========================================================================*/
// Struct sQMUX
//
// Structure that defines a QMUX header
/*=========================================================================*/
typedef struct sQMUX
{
/* T\F, always 1 */
u8 mTF;
/* Size of message */
u16 mLength;
/* Control flag */
u8 mCtrlFlag;
/* Service Type */
u8 mQMIService;
/* Client ID */
u8 mQMIClientID;
}__attribute__((__packed__)) sQMUX;
/*=========================================================================*/
// Generic QMUX functions
/*=========================================================================*/
// Remove QMUX headers from a buffer
int ParseQMUX(
u16 * pClientID,
void * pBuffer,
u16 buffSize );
// Fill buffer with QMUX headers
int FillQMUX(
u16 clientID,
void * pBuffer,
u16 buffSize );
/*=========================================================================*/
// Generic QMI functions
/*=========================================================================*/
// Get data buffer of a specified TLV from a QMI message
int GetTLV(
void * pQMIMessage,
u16 messageLen,
u8 type,
void * pOutDataBuf,
u16 bufferLen );
// Check mandatory TLV in a QMI message
int ValidQMIMessage(
void * pQMIMessage,
u16 messageLen );
// Get the message ID of a QMI message
int GetQMIMessageID(
void * pQMIMessage,
u16 messageLen );
/*=========================================================================*/
// Get sizes of buffers needed by QMI requests
/*=========================================================================*/
// Get size of buffer needed for QMUX
u16 QMUXHeaderSize( void );
// Get size of buffer needed for QMUX + QMICTLGetClientIDReq
u16 QMICTLGetClientIDReqSize( void );
// Get size of buffer needed for QMUX + QMICTLReleaseClientIDReq
u16 QMICTLReleaseClientIDReqSize( void );
// Get size of buffer needed for QMUX + QMICTLReadyReq
u16 QMICTLReadyReqSize( void );
// Get size of buffer needed for QMUX + QMIWDSSetEventReportReq
u16 QMIWDSSetEventReportReqSize( void );
// Get size of buffer needed for QMUX + QMIWDSGetPKGSRVCStatusReq
u16 QMIWDSGetPKGSRVCStatusReqSize( void );
// Get size of buffer needed for QMUX + QMIDMSGetMEIDReq
u16 QMIDMSGetMEIDReqSize( void );
// Get size of buffer needed for QMUX + QMIWDASetDataFormatReq
u16 QMIWDASetDataFormatReqSize( void );
// Get size of buffer needed for QMUX + QMICTLSyncReq
u16 QMICTLSyncReqSize( void );
/*=========================================================================*/
// Fill Buffers with QMI requests
/*=========================================================================*/
// Fill buffer with QMI CTL Get Client ID Request
int QMICTLGetClientIDReq(
void * pBuffer,
u16 buffSize,
u8 transactionID,
u8 serviceType );
// Fill buffer with QMI CTL Release Client ID Request
int QMICTLReleaseClientIDReq(
void * pBuffer,
u16 buffSize,
u8 transactionID,
u16 clientID );
// Fill buffer with QMI CTL Get Version Info Request
int QMICTLReadyReq(
void * pBuffer,
u16 buffSize,
u8 transactionID );
// Fill buffer with QMI WDS Set Event Report Request
int QMIWDSSetEventReportReq(
void * pBuffer,
u16 buffSize,
u16 transactionID );
// Fill buffer with QMI WDS Get PKG SRVC Status Request
int QMIWDSGetPKGSRVCStatusReq(
void * pBuffer,
u16 buffSize,
u16 transactionID );
// Fill buffer with QMI DMS Get Serial Numbers Request
int QMIDMSGetMEIDReq(
void * pBuffer,
u16 buffSize,
u16 transactionID );
// Fill buffer with QMI WDA Set Data Format Request
int QMIWDASetDataFormatReq(
void * pBuffer,
u16 buffSize,
u16 transactionID );
int QMICTLSyncReq(
void * pBuffer,
u16 buffSize,
u16 transactionID );
/*=========================================================================*/
// Parse data from QMI responses
/*=========================================================================*/
// Parse the QMI CTL Get Client ID Resp
int QMICTLGetClientIDResp(
void * pBuffer,
u16 buffSize,
u16 * pClientID );
// Verify the QMI CTL Release Client ID Resp is valid
int QMICTLReleaseClientIDResp(
void * pBuffer,
u16 buffSize );
// Parse the QMI WDS Set Event Report Resp/Indication or
// QMI WDS Get PKG SRVC Status Resp/Indication
int QMIWDSEventResp(
void * pBuffer,
u16 buffSize,
u32 * pTXOk,
u32 * pRXOk,
u32 * pTXErr,
u32 * pRXErr,
u32 * pTXOfl,
u32 * pRXOfl,
u64 * pTXBytesOk,
u64 * pRXBytesOk,
bool * pbLinkState,
bool * pbReconfigure );
// Parse the QMI DMS Get Serial Numbers Resp
int QMIDMSGetMEIDResp(
void * pBuffer,
u16 buffSize,
char * pMEID,
int meidSize );
// Parse the QMI DMS Get Serial Numbers Resp
int QMIWDASetDataFormatResp(
void * pBuffer,
u16 buffSize );
// Pasre the QMI CTL Sync Response
int QMICTLSyncResp(
void *pBuffer,
u16 buffSize );

3994
drivers/net/usb/QMIDevice.c Normal file

File diff suppressed because it is too large Load Diff

345
drivers/net/usb/QMIDevice.h Normal file
View File

@ -0,0 +1,345 @@
/*===========================================================================
FILE:
QMIDevice.h
DESCRIPTION:
Functions related to the QMI interface device
FUNCTIONS:
Generic functions
IsDeviceValid
PrintHex
GobiSetDownReason
GobiClearDownReason
GobiTestDownReason
Driver level asynchronous read functions
ResubmitIntURB
ReadCallback
IntCallback
StartRead
KillRead
Internal read/write functions
ReadAsync
UpSem
ReadSync
WriteSyncCallback
WriteSync
Internal memory management functions
GetClientID
ReleaseClientID
FindClientMem
AddToReadMemList
PopFromReadMemList
AddToNotifyList
NotifyAndPopNotifyList
AddToURBList
PopFromURBList
Internal userspace wrapper functions
UserspaceunlockedIOCTL
Userspace wrappers
UserspaceOpen
UserspaceIOCTL
UserspaceClose
UserspaceRead
UserspaceWrite
UserspacePoll
Initializer and destructor
RegisterQMIDevice
DeregisterQMIDevice
Driver level client management
QMIReady
QMIWDSCallback
SetupQMIWDSCallback
QMIDMSGetMEID
Copyright (c) 2011, Code Aurora Forum. All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* 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.
* Neither the name of Code Aurora Forum 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.
===========================================================================*/
//---------------------------------------------------------------------------
// Pragmas
//---------------------------------------------------------------------------
#pragma once
//---------------------------------------------------------------------------
// Include Files
//---------------------------------------------------------------------------
#include "Structs.h"
#include "QMI.h"
/*=========================================================================*/
// Generic functions
/*=========================================================================*/
// Basic test to see if device memory is valid
bool IsDeviceValid( sGobiUSBNet * pDev );
// Print Hex data, for debug purposes
void PrintHex(
void * pBuffer,
u16 bufSize );
// Sets mDownReason and turns carrier off
void GobiSetDownReason(
sGobiUSBNet * pDev,
u8 reason );
// Clear mDownReason and may turn carrier on
void GobiClearDownReason(
sGobiUSBNet * pDev,
u8 reason );
// Tests mDownReason and returns whether reason is set
bool GobiTestDownReason(
sGobiUSBNet * pDev,
u8 reason );
/*=========================================================================*/
// Driver level asynchronous read functions
/*=========================================================================*/
// Resubmit interrupt URB, re-using same values
int ResubmitIntURB( struct urb * pIntURB );
// Read callback
// Put the data in storage and notify anyone waiting for data
#if (LINUX_VERSION_CODE > KERNEL_VERSION( 2,6,14 ))
void ReadCallback( struct urb * pReadURB );
#else
void ReadCallback(struct urb *pReadURB, struct pt_regs *regs);
#endif
// Inturrupt callback
// Data is available, start a read URB
#if (LINUX_VERSION_CODE > KERNEL_VERSION( 2,6,14 ))
void IntCallback( struct urb * pIntURB );
#else
void IntCallback(struct urb *pIntURB, struct pt_regs *regs);
#endif
// Start continuous read "thread"
int StartRead( sGobiUSBNet * pDev );
// Kill continuous read "thread"
void KillRead( sGobiUSBNet * pDev );
/*=========================================================================*/
// Internal read/write functions
/*=========================================================================*/
// Start asynchronous read
// Reading client's data store, not device
int ReadAsync(
sGobiUSBNet * pDev,
u16 clientID,
u16 transactionID,
void (*pCallback)(sGobiUSBNet *, u16, void *),
void * pData );
// Notification function for synchronous read
void UpSem(
sGobiUSBNet * pDev,
u16 clientID,
void * pData );
// Start synchronous read
// Reading client's data store, not device
int ReadSync(
sGobiUSBNet * pDev,
void ** ppOutBuffer,
u16 clientID,
u16 transactionID );
// Write callback
#if (LINUX_VERSION_CODE > KERNEL_VERSION( 2,6,14 ))
void WriteSyncCallback( struct urb * pWriteURB );
#else
void WriteSyncCallback(struct urb *pWriteURB, struct pt_regs *regs);
#endif
// Start synchronous write
int WriteSync(
sGobiUSBNet * pDev,
char * pInWriteBuffer,
int size,
u16 clientID );
/*=========================================================================*/
// Internal memory management functions
/*=========================================================================*/
// Create client and allocate memory
int GetClientID(
sGobiUSBNet * pDev,
u8 serviceType );
// Release client and free memory
void ReleaseClientID(
sGobiUSBNet * pDev,
u16 clientID );
// Find this client's memory
sClientMemList * FindClientMem(
sGobiUSBNet * pDev,
u16 clientID );
// Add Data to this client's ReadMem list
bool AddToReadMemList(
sGobiUSBNet * pDev,
u16 clientID,
u16 transactionID,
void * pData,
u16 dataSize );
// Remove data from this client's ReadMem list if it matches
// the specified transaction ID.
bool PopFromReadMemList(
sGobiUSBNet * pDev,
u16 clientID,
u16 transactionID,
void ** ppData,
u16 * pDataSize );
// Add Notify entry to this client's notify List
bool AddToNotifyList(
sGobiUSBNet * pDev,
u16 clientID,
u16 transactionID,
void (* pNotifyFunct)(sGobiUSBNet *, u16, void *),
void * pData );
// Remove first Notify entry from this client's notify list
// and Run function
bool NotifyAndPopNotifyList(
sGobiUSBNet * pDev,
u16 clientID,
u16 transactionID );
// Add URB to this client's URB list
bool AddToURBList(
sGobiUSBNet * pDev,
u16 clientID,
struct urb * pURB );
// Remove URB from this client's URB list
struct urb * PopFromURBList(
sGobiUSBNet * pDev,
u16 clientID );
/*=========================================================================*/
// Internal userspace wrappers
/*=========================================================================*/
// Userspace unlocked ioctl
long UserspaceunlockedIOCTL(
struct file * pFilp,
unsigned int cmd,
unsigned long arg );
/*=========================================================================*/
// Userspace wrappers
/*=========================================================================*/
// Userspace open
int UserspaceOpen(
struct inode * pInode,
struct file * pFilp );
// Userspace ioctl
int UserspaceIOCTL(
struct inode * pUnusedInode,
struct file * pFilp,
unsigned int cmd,
unsigned long arg );
// Userspace close
#if (LINUX_VERSION_CODE > KERNEL_VERSION( 2,6,14 ))
int UserspaceClose(
struct file * pFilp,
fl_owner_t unusedFileTable );
#else
int UserspaceClose( struct file * pFilp );
#endif
// Userspace read (synchronous)
ssize_t UserspaceRead(
struct file * pFilp,
char __user * pBuf,
size_t size,
loff_t * pUnusedFpos );
// Userspace write (synchronous)
ssize_t UserspaceWrite(
struct file * pFilp,
const char __user * pBuf,
size_t size,
loff_t * pUnusedFpos );
unsigned int UserspacePoll(
struct file * pFilp,
struct poll_table_struct * pPollTable );
/*=========================================================================*/
// Initializer and destructor
/*=========================================================================*/
// QMI Device initialization function
int RegisterQMIDevice( sGobiUSBNet * pDev );
// QMI Device cleanup function
void DeregisterQMIDevice( sGobiUSBNet * pDev );
/*=========================================================================*/
// Driver level client management
/*=========================================================================*/
// Check if QMI is ready for use
bool QMIReady(
sGobiUSBNet * pDev,
u16 timeout );
// QMI WDS callback function
void QMIWDSCallback(
sGobiUSBNet * pDev,
u16 clientID,
void * pData );
// Fire off reqests and start async read for QMI WDS callback
int SetupQMIWDSCallback( sGobiUSBNet * pDev );
// Register client, send req and parse MEID response, release client
int QMIDMSGetMEID( sGobiUSBNet * pDev );
// Register client, send req and parse Data format response, release client
int QMIWDASetDataFormat( sGobiUSBNet * pDev );

423
drivers/net/usb/Structs.h Normal file
View File

@ -0,0 +1,423 @@
/*===========================================================================
FILE:
Structs.h
DESCRIPTION:
Declaration of structures used by the Qualcomm Linux USB Network driver
FUNCTIONS:
none
Copyright (c) 2011, Code Aurora Forum. All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* 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.
* Neither the name of Code Aurora Forum 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.
===========================================================================*/
//---------------------------------------------------------------------------
// Pragmas
//---------------------------------------------------------------------------
#pragma once
//---------------------------------------------------------------------------
// Include Files
//---------------------------------------------------------------------------
#include <linux/etherdevice.h>
#include <linux/ethtool.h>
#include <linux/mii.h>
#include <linux/usb.h>
#include <linux/version.h>
#include <linux/cdev.h>
#include <linux/kthread.h>
#include <linux/poll.h>
#include <linux/completion.h>
#if (LINUX_VERSION_CODE <= KERNEL_VERSION( 2,6,22 ))
#define bool u8
#define URB_FREE_BUFFER 0x0100 /* Free transfer buffer with the URB */
/**
* usb_endpoint_type - get the endpoint's transfer type
* @epd: endpoint to be checked
*
* Returns one of USB_ENDPOINT_XFER_{CONTROL, ISOC, BULK, INT} according
* to @epd's transfer type.
*/
static inline int usb_endpoint_type(const struct usb_endpoint_descriptor *epd)
{
return epd->bmAttributes & USB_ENDPOINT_XFERTYPE_MASK;
}
#endif
#if (LINUX_VERSION_CODE <= KERNEL_VERSION( 2,6,14 ))
/**
* usb_endpoint_dir_in - check if the endpoint has IN direction
* @epd: endpoint to be checked
*
* Returns true if the endpoint is of type IN, otherwise it returns false.
*/
static inline int usb_endpoint_dir_in(const struct usb_endpoint_descriptor *epd)
{
return ((epd->bEndpointAddress & USB_ENDPOINT_DIR_MASK) == USB_DIR_IN);
}
/**
* usb_endpoint_dir_out - check if the endpoint has OUT direction
* @epd: endpoint to be checked
*
* Returns true if the endpoint is of type OUT, otherwise it returns false.
*/
static inline int usb_endpoint_dir_out(
const struct usb_endpoint_descriptor *epd)
{
return ((epd->bEndpointAddress & USB_ENDPOINT_DIR_MASK) == USB_DIR_OUT);
}
/**
* usb_endpoint_xfer_int - check if the endpoint has interrupt transfer type
* @epd: endpoint to be checked
*
* Returns true if the endpoint is of type interrupt, otherwise it returns
* false.
*/
static inline int usb_endpoint_xfer_int(
const struct usb_endpoint_descriptor *epd)
{
return ((epd->bmAttributes & USB_ENDPOINT_XFERTYPE_MASK) ==
USB_ENDPOINT_XFER_INT);
}
static inline int usb_autopm_set_interface(struct usb_interface *intf)
{ return 0; }
static inline int usb_autopm_get_interface(struct usb_interface *intf)
{ return 0; }
static inline int usb_autopm_get_interface_async(struct usb_interface *intf)
{ return 0; }
static inline void usb_autopm_put_interface(struct usb_interface *intf)
{ }
static inline void usb_autopm_put_interface_async(struct usb_interface *intf)
{ }
static inline void usb_autopm_enable(struct usb_interface *intf)
{ }
static inline void usb_autopm_disable(struct usb_interface *intf)
{ }
static inline void usb_mark_last_busy(struct usb_device *udev)
{ }
#endif
#if (LINUX_VERSION_CODE <= KERNEL_VERSION( 2,6,24 ))
#include "usbnet.h"
#else
#include <linux/usb/usbnet.h>
#endif
#if (LINUX_VERSION_CODE > KERNEL_VERSION( 2,6,25 ))
#include <linux/fdtable.h>
#else
#include <linux/file.h>
#endif
// Used in recursion, defined later below
struct sGobiUSBNet;
/*=========================================================================*/
// Struct sReadMemList
//
// Structure that defines an entry in a Read Memory linked list
/*=========================================================================*/
typedef struct sReadMemList
{
/* Data buffer */
void * mpData;
/* Transaction ID */
u16 mTransactionID;
/* Size of data buffer */
u16 mDataSize;
/* Next entry in linked list */
struct sReadMemList * mpNext;
} sReadMemList;
/*=========================================================================*/
// Struct sNotifyList
//
// Structure that defines an entry in a Notification linked list
/*=========================================================================*/
typedef struct sNotifyList
{
/* Function to be run when data becomes available */
void (* mpNotifyFunct)(struct sGobiUSBNet *, u16, void *);
/* Transaction ID */
u16 mTransactionID;
/* Data to provide as parameter to mpNotifyFunct */
void * mpData;
/* Next entry in linked list */
struct sNotifyList * mpNext;
} sNotifyList;
/*=========================================================================*/
// Struct sURBList
//
// Structure that defines an entry in a URB linked list
/*=========================================================================*/
typedef struct sURBList
{
/* The current URB */
struct urb * mpURB;
/* Next entry in linked list */
struct sURBList * mpNext;
} sURBList;
/*=========================================================================*/
// Struct sClientMemList
//
// Structure that defines an entry in a Client Memory linked list
// Stores data specific to a Service Type and Client ID
/*=========================================================================*/
typedef struct sClientMemList
{
/* Client ID for this Client */
u16 mClientID;
/* Linked list of Read entries */
/* Stores data read from device before sending to client */
sReadMemList * mpList;
/* Linked list of Notification entries */
/* Stores notification functions to be run as data becomes
available or the device is removed */
sNotifyList * mpReadNotifyList;
/* Linked list of URB entries */
/* Stores pointers to outstanding URBs which need canceled
when the client is deregistered or the device is removed */
sURBList * mpURBList;
/* Next entry in linked list */
struct sClientMemList * mpNext;
/* Wait queue object for poll() */
wait_queue_head_t mWaitQueue;
} sClientMemList;
/*=========================================================================*/
// Struct sURBSetupPacket
//
// Structure that defines a USB Setup packet for Control URBs
// Taken from USB CDC specifications
/*=========================================================================*/
typedef struct sURBSetupPacket
{
/* Request type */
u8 mRequestType;
/* Request code */
u8 mRequestCode;
/* Value */
u16 mValue;
/* Index */
u16 mIndex;
/* Length of Control URB */
u16 mLength;
} sURBSetupPacket;
// Common value for sURBSetupPacket.mLength
#define DEFAULT_READ_URB_LENGTH 0x1000
#ifdef CONFIG_PM
#if (LINUX_VERSION_CODE < KERNEL_VERSION( 2,6,29 ))
/*=========================================================================*/
// Struct sAutoPM
//
// Structure used to manage AutoPM thread which determines whether the
// device is in use or may enter autosuspend. Also submits net
// transmissions asynchronously.
/*=========================================================================*/
typedef struct sAutoPM
{
/* Thread for atomic autopm function */
struct task_struct * mpThread;
/* Signal for completion when it's time for the thread to work */
struct completion mThreadDoWork;
/* Time to exit? */
bool mbExit;
/* List of URB's queued to be sent to the device */
sURBList * mpURBList;
/* URB list lock (for adding and removing elements) */
spinlock_t mURBListLock;
/* Length of the URB list */
atomic_t mURBListLen;
/* Active URB */
struct urb * mpActiveURB;
/* Active URB lock (for adding and removing elements) */
spinlock_t mActiveURBLock;
/* Duplicate pointer to USB device interface */
struct usb_interface * mpIntf;
} sAutoPM;
#endif
#endif /* CONFIG_PM */
/*=========================================================================*/
// Struct sQMIDev
//
// Structure that defines the data for the QMI device
/*=========================================================================*/
typedef struct sQMIDev
{
/* Device number */
dev_t mDevNum;
/* Device class */
struct class * mpDevClass;
/* cdev struct */
struct cdev mCdev;
/* is mCdev initialized? */
bool mbCdevIsInitialized;
/* Pointer to read URB */
struct urb * mpReadURB;
/* Read setup packet */
sURBSetupPacket * mpReadSetupPacket;
/* Read buffer attached to current read URB */
void * mpReadBuffer;
/* Inturrupt URB */
/* Used to asynchronously notify when read data is available */
struct urb * mpIntURB;
/* Buffer used by Inturrupt URB */
void * mpIntBuffer;
/* Pointer to memory linked list for all clients */
sClientMemList * mpClientMemList;
/* Spinlock for client Memory entries */
spinlock_t mClientMemLock;
/* Transaction ID associated with QMICTL "client" */
atomic_t mQMICTLTransactionID;
} sQMIDev;
/*=========================================================================*/
// Struct sGobiUSBNet
//
// Structure that defines the data associated with the Qualcomm USB device
/*=========================================================================*/
typedef struct sGobiUSBNet
{
atomic_t refcount;
/* Net device structure */
struct usbnet * mpNetDev;
#if 1 //def DATA_MODE_RP
/* QMI "device" work in IP Mode or ETH Mode */
bool mbRawIPMode;
#endif
struct completion mQMIReadyCompletion;
bool mbQMIReady;
/* Usb device interface */
struct usb_interface * mpIntf;
/* Pointers to usbnet_open and usbnet_stop functions */
int (* mpUSBNetOpen)(struct net_device *);
int (* mpUSBNetStop)(struct net_device *);
/* Reason(s) why interface is down */
/* Used by Gobi*DownReason */
unsigned long mDownReason;
#define NO_NDIS_CONNECTION 0
#define CDC_CONNECTION_SPEED 1
#define DRIVER_SUSPENDED 2
#define NET_IFACE_STOPPED 3
/* QMI "device" status */
bool mbQMIValid;
bool mbDeregisterQMIDevice;
/* QMI "device" memory */
sQMIDev mQMIDev;
/* Device MEID */
char mMEID[14];
#ifdef CONFIG_PM
#if (LINUX_VERSION_CODE < KERNEL_VERSION( 2,6,29 ))
/* AutoPM thread */
sAutoPM mAutoPM;
#endif
#endif /* CONFIG_PM */
} sGobiUSBNet;
/*=========================================================================*/
// Struct sQMIFilpStorage
//
// Structure that defines the storage each file handle contains
// Relates the file handle to a client
/*=========================================================================*/
typedef struct sQMIFilpStorage
{
/* Client ID */
u16 mClientID;
/* Device pointer */
sGobiUSBNet * mpDev;
} sQMIFilpStorage;

1142
drivers/net/usb/qmi_wwan.c Normal file

File diff suppressed because it is too large Load Diff

2127
drivers/usb/serial/option.c Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,742 @@
/*
USB Driver layer for GSM modems
Copyright (C) 2005 Matthias Urlichs <smurf@smurf.noris.de>
This driver is free software; you can redistribute it and/or modify
it under the terms of Version 2 of the GNU General Public License as
published by the Free Software Foundation.
Portions copied from the Keyspan driver by Hugh Blemings <hugh@blemings.org>
History: see the git log.
Work sponsored by: Sigos GmbH, Germany <info@sigos.de>
This driver exists because the "normal" serial driver doesn't work too well
with GSM modems. Issues:
- data loss -- one single Receive URB is not nearly enough
- controlling the baud rate doesn't make sense
*/
#define DRIVER_AUTHOR "Matthias Urlichs <smurf@smurf.noris.de>"
#define DRIVER_DESC "USB Driver for GSM modems"
#include <linux/kernel.h>
#include <linux/jiffies.h>
#include <linux/errno.h>
#include <linux/slab.h>
#include <linux/tty.h>
#include <linux/tty_flip.h>
#include <linux/module.h>
#include <linux/bitops.h>
#include <linux/uaccess.h>
#include <linux/usb.h>
#include <linux/usb/serial.h>
#include <linux/serial.h>
#include "usb-wwan.h"
/*
* Generate DTR/RTS signals on the port using the SET_CONTROL_LINE_STATE request
* in CDC ACM.
*/
static int usb_wwan_send_setup(struct usb_serial_port *port)
{
struct usb_serial *serial = port->serial;
struct usb_wwan_port_private *portdata;
int val = 0;
int ifnum;
int res;
portdata = usb_get_serial_port_data(port);
if (portdata->dtr_state)
val |= 0x01;
if (portdata->rts_state)
val |= 0x02;
ifnum = serial->interface->cur_altsetting->desc.bInterfaceNumber;
res = usb_autopm_get_interface(serial->interface);
if (res)
return res;
res = usb_control_msg(serial->dev, usb_sndctrlpipe(serial->dev, 0),
0x22, 0x21, val, ifnum, NULL, 0,
USB_CTRL_SET_TIMEOUT);
usb_autopm_put_interface(port->serial->interface);
return res;
}
void usb_wwan_dtr_rts(struct usb_serial_port *port, int on)
{
struct usb_wwan_port_private *portdata;
struct usb_wwan_intf_private *intfdata;
intfdata = usb_get_serial_data(port->serial);
if (!intfdata->use_send_setup)
return;
portdata = usb_get_serial_port_data(port);
/* FIXME: locking */
portdata->rts_state = on;
portdata->dtr_state = on;
usb_wwan_send_setup(port);
}
EXPORT_SYMBOL(usb_wwan_dtr_rts);
int usb_wwan_tiocmget(struct tty_struct *tty)
{
struct usb_serial_port *port = tty->driver_data;
unsigned int value;
struct usb_wwan_port_private *portdata;
portdata = usb_get_serial_port_data(port);
value = ((portdata->rts_state) ? TIOCM_RTS : 0) |
((portdata->dtr_state) ? TIOCM_DTR : 0) |
((portdata->cts_state) ? TIOCM_CTS : 0) |
((portdata->dsr_state) ? TIOCM_DSR : 0) |
((portdata->dcd_state) ? TIOCM_CAR : 0) |
((portdata->ri_state) ? TIOCM_RNG : 0);
return value;
}
EXPORT_SYMBOL(usb_wwan_tiocmget);
int usb_wwan_tiocmset(struct tty_struct *tty,
unsigned int set, unsigned int clear)
{
struct usb_serial_port *port = tty->driver_data;
struct usb_wwan_port_private *portdata;
struct usb_wwan_intf_private *intfdata;
portdata = usb_get_serial_port_data(port);
intfdata = usb_get_serial_data(port->serial);
if (!intfdata->use_send_setup)
return -EINVAL;
/* FIXME: what locks portdata fields ? */
if (set & TIOCM_RTS)
portdata->rts_state = 1;
if (set & TIOCM_DTR)
portdata->dtr_state = 1;
if (clear & TIOCM_RTS)
portdata->rts_state = 0;
if (clear & TIOCM_DTR)
portdata->dtr_state = 0;
return usb_wwan_send_setup(port);
}
EXPORT_SYMBOL(usb_wwan_tiocmset);
static int get_serial_info(struct usb_serial_port *port,
struct serial_struct __user *retinfo)
{
struct serial_struct tmp;
if (!retinfo)
return -EFAULT;
memset(&tmp, 0, sizeof(tmp));
tmp.line = port->minor;
tmp.port = port->port_number;
tmp.baud_base = tty_get_baud_rate(port->port.tty);
tmp.close_delay = port->port.close_delay / 10;
tmp.closing_wait = port->port.closing_wait == ASYNC_CLOSING_WAIT_NONE ?
ASYNC_CLOSING_WAIT_NONE :
port->port.closing_wait / 10;
if (copy_to_user(retinfo, &tmp, sizeof(*retinfo)))
return -EFAULT;
return 0;
}
static int set_serial_info(struct usb_serial_port *port,
struct serial_struct __user *newinfo)
{
struct serial_struct new_serial;
unsigned int closing_wait, close_delay;
int retval = 0;
if (copy_from_user(&new_serial, newinfo, sizeof(new_serial)))
return -EFAULT;
close_delay = new_serial.close_delay * 10;
closing_wait = new_serial.closing_wait == ASYNC_CLOSING_WAIT_NONE ?
ASYNC_CLOSING_WAIT_NONE : new_serial.closing_wait * 10;
mutex_lock(&port->port.mutex);
if (!capable(CAP_SYS_ADMIN)) {
if ((close_delay != port->port.close_delay) ||
(closing_wait != port->port.closing_wait))
retval = -EPERM;
else
retval = -EOPNOTSUPP;
} else {
port->port.close_delay = close_delay;
port->port.closing_wait = closing_wait;
}
mutex_unlock(&port->port.mutex);
return retval;
}
int usb_wwan_ioctl(struct tty_struct *tty,
unsigned int cmd, unsigned long arg)
{
struct usb_serial_port *port = tty->driver_data;
dev_dbg(&port->dev, "%s cmd 0x%04x\n", __func__, cmd);
switch (cmd) {
case TIOCGSERIAL:
return get_serial_info(port,
(struct serial_struct __user *) arg);
case TIOCSSERIAL:
return set_serial_info(port,
(struct serial_struct __user *) arg);
default:
break;
}
dev_dbg(&port->dev, "%s arg not supported\n", __func__);
return -ENOIOCTLCMD;
}
EXPORT_SYMBOL(usb_wwan_ioctl);
int usb_wwan_write(struct tty_struct *tty, struct usb_serial_port *port,
const unsigned char *buf, int count)
{
struct usb_wwan_port_private *portdata;
struct usb_wwan_intf_private *intfdata;
int i;
int left, todo;
struct urb *this_urb = NULL; /* spurious */
int err;
unsigned long flags;
portdata = usb_get_serial_port_data(port);
intfdata = usb_get_serial_data(port->serial);
dev_dbg(&port->dev, "%s: write (%d chars)\n", __func__, count);
i = 0;
left = count;
for (i = 0; left > 0 && i < N_OUT_URB; i++) {
todo = left;
if (todo > OUT_BUFLEN)
todo = OUT_BUFLEN;
this_urb = portdata->out_urbs[i];
if (test_and_set_bit(i, &portdata->out_busy)) {
if (time_before(jiffies,
portdata->tx_start_time[i] + 10 * HZ))
continue;
usb_unlink_urb(this_urb);
continue;
}
dev_dbg(&port->dev, "%s: endpoint %d buf %d\n", __func__,
usb_pipeendpoint(this_urb->pipe), i);
err = usb_autopm_get_interface_async(port->serial->interface);
if (err < 0) {
clear_bit(i, &portdata->out_busy);
break;
}
/* send the data */
memcpy(this_urb->transfer_buffer, buf, todo);
this_urb->transfer_buffer_length = todo;
spin_lock_irqsave(&intfdata->susp_lock, flags);
if (intfdata->suspended) {
usb_anchor_urb(this_urb, &portdata->delayed);
spin_unlock_irqrestore(&intfdata->susp_lock, flags);
} else {
intfdata->in_flight++;
spin_unlock_irqrestore(&intfdata->susp_lock, flags);
err = usb_submit_urb(this_urb, GFP_ATOMIC);
if (err) {
dev_err(&port->dev,
"%s: submit urb %d failed: %d\n",
__func__, i, err);
clear_bit(i, &portdata->out_busy);
spin_lock_irqsave(&intfdata->susp_lock, flags);
intfdata->in_flight--;
spin_unlock_irqrestore(&intfdata->susp_lock,
flags);
usb_autopm_put_interface_async(port->serial->interface);
break;
}
}
portdata->tx_start_time[i] = jiffies;
buf += todo;
left -= todo;
}
count -= left;
dev_dbg(&port->dev, "%s: wrote (did %d)\n", __func__, count);
return count;
}
EXPORT_SYMBOL(usb_wwan_write);
static void usb_wwan_indat_callback(struct urb *urb)
{
int err;
int endpoint;
struct usb_serial_port *port;
struct device *dev;
unsigned char *data = urb->transfer_buffer;
int status = urb->status;
endpoint = usb_pipeendpoint(urb->pipe);
port = urb->context;
dev = &port->dev;
if (status) {
dev_dbg(dev, "%s: nonzero status: %d on endpoint %02x.\n",
__func__, status, endpoint);
} else {
if (urb->actual_length) {
tty_insert_flip_string(&port->port, data,
urb->actual_length);
tty_flip_buffer_push(&port->port);
} else
dev_dbg(dev, "%s: empty read urb received\n", __func__);
}
/* Resubmit urb so we continue receiving */
err = usb_submit_urb(urb, GFP_ATOMIC);
if (err) {
if (err != -EPERM && err != -ENODEV) {
dev_err(dev, "%s: resubmit read urb failed. (%d)\n",
__func__, err);
/* busy also in error unless we are killed */
usb_mark_last_busy(port->serial->dev);
}
} else {
usb_mark_last_busy(port->serial->dev);
}
}
static void usb_wwan_outdat_callback(struct urb *urb)
{
struct usb_serial_port *port;
struct usb_wwan_port_private *portdata;
struct usb_wwan_intf_private *intfdata;
int i;
port = urb->context;
intfdata = usb_get_serial_data(port->serial);
usb_serial_port_softint(port);
usb_autopm_put_interface_async(port->serial->interface);
portdata = usb_get_serial_port_data(port);
spin_lock(&intfdata->susp_lock);
intfdata->in_flight--;
spin_unlock(&intfdata->susp_lock);
for (i = 0; i < N_OUT_URB; ++i) {
if (portdata->out_urbs[i] == urb) {
smp_mb__before_atomic();
clear_bit(i, &portdata->out_busy);
break;
}
}
}
int usb_wwan_write_room(struct tty_struct *tty)
{
struct usb_serial_port *port = tty->driver_data;
struct usb_wwan_port_private *portdata;
int i;
int data_len = 0;
struct urb *this_urb;
portdata = usb_get_serial_port_data(port);
for (i = 0; i < N_OUT_URB; i++) {
this_urb = portdata->out_urbs[i];
if (this_urb && !test_bit(i, &portdata->out_busy))
data_len += OUT_BUFLEN;
}
dev_dbg(&port->dev, "%s: %d\n", __func__, data_len);
return data_len;
}
EXPORT_SYMBOL(usb_wwan_write_room);
int usb_wwan_chars_in_buffer(struct tty_struct *tty)
{
struct usb_serial_port *port = tty->driver_data;
struct usb_wwan_port_private *portdata;
int i;
int data_len = 0;
struct urb *this_urb;
portdata = usb_get_serial_port_data(port);
for (i = 0; i < N_OUT_URB; i++) {
this_urb = portdata->out_urbs[i];
/* FIXME: This locking is insufficient as this_urb may
go unused during the test */
if (this_urb && test_bit(i, &portdata->out_busy))
data_len += this_urb->transfer_buffer_length;
}
dev_dbg(&port->dev, "%s: %d\n", __func__, data_len);
return data_len;
}
EXPORT_SYMBOL(usb_wwan_chars_in_buffer);
int usb_wwan_open(struct tty_struct *tty, struct usb_serial_port *port)
{
struct usb_wwan_port_private *portdata;
struct usb_wwan_intf_private *intfdata;
struct usb_serial *serial = port->serial;
int i, err;
struct urb *urb;
portdata = usb_get_serial_port_data(port);
intfdata = usb_get_serial_data(serial);
if (port->interrupt_in_urb) {
err = usb_submit_urb(port->interrupt_in_urb, GFP_KERNEL);
if (err) {
dev_err(&port->dev, "%s: submit int urb failed: %d\n",
__func__, err);
}
}
/* Start reading from the IN endpoint */
for (i = 0; i < N_IN_URB; i++) {
urb = portdata->in_urbs[i];
if (!urb)
continue;
err = usb_submit_urb(urb, GFP_KERNEL);
if (err) {
dev_err(&port->dev,
"%s: submit read urb %d failed: %d\n",
__func__, i, err);
}
}
spin_lock_irq(&intfdata->susp_lock);
if (++intfdata->open_ports == 1)
serial->interface->needs_remote_wakeup = 1;
spin_unlock_irq(&intfdata->susp_lock);
/* this balances a get in the generic USB serial code */
usb_autopm_put_interface(serial->interface);
return 0;
}
EXPORT_SYMBOL(usb_wwan_open);
static void unbusy_queued_urb(struct urb *urb,
struct usb_wwan_port_private *portdata)
{
int i;
for (i = 0; i < N_OUT_URB; i++) {
if (urb == portdata->out_urbs[i]) {
clear_bit(i, &portdata->out_busy);
break;
}
}
}
void usb_wwan_close(struct usb_serial_port *port)
{
int i;
struct usb_serial *serial = port->serial;
struct usb_wwan_port_private *portdata;
struct usb_wwan_intf_private *intfdata = usb_get_serial_data(serial);
struct urb *urb;
portdata = usb_get_serial_port_data(port);
/*
* Need to take susp_lock to make sure port is not already being
* resumed, but no need to hold it due to initialized
*/
spin_lock_irq(&intfdata->susp_lock);
if (--intfdata->open_ports == 0)
serial->interface->needs_remote_wakeup = 0;
spin_unlock_irq(&intfdata->susp_lock);
for (;;) {
urb = usb_get_from_anchor(&portdata->delayed);
if (!urb)
break;
unbusy_queued_urb(urb, portdata);
usb_autopm_put_interface_async(serial->interface);
}
for (i = 0; i < N_IN_URB; i++)
usb_kill_urb(portdata->in_urbs[i]);
for (i = 0; i < N_OUT_URB; i++)
usb_kill_urb(portdata->out_urbs[i]);
usb_kill_urb(port->interrupt_in_urb);
usb_autopm_get_interface_no_resume(serial->interface);
}
EXPORT_SYMBOL(usb_wwan_close);
static struct urb *usb_wwan_setup_urb(struct usb_serial_port *port,
int endpoint,
int dir, void *ctx, char *buf, int len,
void (*callback) (struct urb *))
{
struct usb_serial *serial = port->serial;
struct urb *urb;
urb = usb_alloc_urb(0, GFP_KERNEL); /* No ISO */
if (!urb)
return NULL;
usb_fill_bulk_urb(urb, serial->dev,
usb_sndbulkpipe(serial->dev, endpoint) | dir,
buf, len, callback, ctx);
#if 1 //Added by Quectel for Zero Packet
if (dir == USB_DIR_OUT) {
struct usb_device_descriptor *desc = &serial->dev->descriptor;
if (desc->idVendor == cpu_to_le16(0x05C6) && desc->idProduct == cpu_to_le16(0x9090))
urb->transfer_flags |= URB_ZERO_PACKET;
if (desc->idVendor == cpu_to_le16(0x05C6) && desc->idProduct == cpu_to_le16(0x9003))
urb->transfer_flags |= URB_ZERO_PACKET;
if (desc->idVendor == cpu_to_le16(0x05C6) && desc->idProduct == cpu_to_le16(0x9215))
urb->transfer_flags |= URB_ZERO_PACKET;
if (desc->idVendor == cpu_to_le16(0x2C7C))
urb->transfer_flags |= URB_ZERO_PACKET;
}
#endif
return urb;
}
int usb_wwan_port_probe(struct usb_serial_port *port)
{
struct usb_wwan_port_private *portdata;
struct urb *urb;
u8 *buffer;
int i;
if (!port->bulk_in_size || !port->bulk_out_size)
return -ENODEV;
portdata = kzalloc(sizeof(*portdata), GFP_KERNEL);
if (!portdata)
return -ENOMEM;
init_usb_anchor(&portdata->delayed);
for (i = 0; i < N_IN_URB; i++) {
buffer = (u8 *)__get_free_page(GFP_KERNEL);
if (!buffer)
goto bail_out_error;
portdata->in_buffer[i] = buffer;
urb = usb_wwan_setup_urb(port, port->bulk_in_endpointAddress,
USB_DIR_IN, port,
buffer, IN_BUFLEN,
usb_wwan_indat_callback);
portdata->in_urbs[i] = urb;
}
for (i = 0; i < N_OUT_URB; i++) {
buffer = kmalloc(OUT_BUFLEN, GFP_KERNEL);
if (!buffer)
goto bail_out_error2;
portdata->out_buffer[i] = buffer;
urb = usb_wwan_setup_urb(port, port->bulk_out_endpointAddress,
USB_DIR_OUT, port,
buffer, OUT_BUFLEN,
usb_wwan_outdat_callback);
portdata->out_urbs[i] = urb;
}
usb_set_serial_port_data(port, portdata);
return 0;
bail_out_error2:
for (i = 0; i < N_OUT_URB; i++) {
usb_free_urb(portdata->out_urbs[i]);
kfree(portdata->out_buffer[i]);
}
bail_out_error:
for (i = 0; i < N_IN_URB; i++) {
usb_free_urb(portdata->in_urbs[i]);
free_page((unsigned long)portdata->in_buffer[i]);
}
kfree(portdata);
return -ENOMEM;
}
EXPORT_SYMBOL_GPL(usb_wwan_port_probe);
int usb_wwan_port_remove(struct usb_serial_port *port)
{
int i;
struct usb_wwan_port_private *portdata;
portdata = usb_get_serial_port_data(port);
usb_set_serial_port_data(port, NULL);
for (i = 0; i < N_IN_URB; i++) {
usb_free_urb(portdata->in_urbs[i]);
free_page((unsigned long)portdata->in_buffer[i]);
}
for (i = 0; i < N_OUT_URB; i++) {
usb_free_urb(portdata->out_urbs[i]);
kfree(portdata->out_buffer[i]);
}
kfree(portdata);
return 0;
}
EXPORT_SYMBOL(usb_wwan_port_remove);
#ifdef CONFIG_PM
static void stop_urbs(struct usb_serial *serial)
{
int i, j;
struct usb_serial_port *port;
struct usb_wwan_port_private *portdata;
for (i = 0; i < serial->num_ports; ++i) {
port = serial->port[i];
portdata = usb_get_serial_port_data(port);
if (!portdata)
continue;
for (j = 0; j < N_IN_URB; j++)
usb_kill_urb(portdata->in_urbs[j]);
for (j = 0; j < N_OUT_URB; j++)
usb_kill_urb(portdata->out_urbs[j]);
usb_kill_urb(port->interrupt_in_urb);
}
}
int usb_wwan_suspend(struct usb_serial *serial, pm_message_t message)
{
struct usb_wwan_intf_private *intfdata = usb_get_serial_data(serial);
spin_lock_irq(&intfdata->susp_lock);
if (PMSG_IS_AUTO(message)) {
if (intfdata->in_flight) {
spin_unlock_irq(&intfdata->susp_lock);
return -EBUSY;
}
}
intfdata->suspended = 1;
spin_unlock_irq(&intfdata->susp_lock);
stop_urbs(serial);
return 0;
}
EXPORT_SYMBOL(usb_wwan_suspend);
/* Caller must hold susp_lock. */
static int usb_wwan_submit_delayed_urbs(struct usb_serial_port *port)
{
struct usb_serial *serial = port->serial;
struct usb_wwan_intf_private *data = usb_get_serial_data(serial);
struct usb_wwan_port_private *portdata;
struct urb *urb;
int err_count = 0;
int err;
portdata = usb_get_serial_port_data(port);
for (;;) {
urb = usb_get_from_anchor(&portdata->delayed);
if (!urb)
break;
err = usb_submit_urb(urb, GFP_ATOMIC);
if (err) {
dev_err(&port->dev, "%s: submit urb failed: %d\n",
__func__, err);
err_count++;
unbusy_queued_urb(urb, portdata);
usb_autopm_put_interface_async(serial->interface);
continue;
}
data->in_flight++;
}
if (err_count)
return -EIO;
return 0;
}
int usb_wwan_resume(struct usb_serial *serial)
{
int i, j;
struct usb_serial_port *port;
struct usb_wwan_intf_private *intfdata = usb_get_serial_data(serial);
struct usb_wwan_port_private *portdata;
struct urb *urb;
int err;
int err_count = 0;
spin_lock_irq(&intfdata->susp_lock);
for (i = 0; i < serial->num_ports; i++) {
port = serial->port[i];
if (!tty_port_initialized(&port->port))
continue;
portdata = usb_get_serial_port_data(port);
if (port->interrupt_in_urb) {
err = usb_submit_urb(port->interrupt_in_urb,
GFP_ATOMIC);
if (err) {
dev_err(&port->dev,
"%s: submit int urb failed: %d\n",
__func__, err);
err_count++;
}
}
err = usb_wwan_submit_delayed_urbs(port);
if (err)
err_count++;
for (j = 0; j < N_IN_URB; j++) {
urb = portdata->in_urbs[j];
err = usb_submit_urb(urb, GFP_ATOMIC);
if (err < 0) {
dev_err(&port->dev,
"%s: submit read urb %d failed: %d\n",
__func__, i, err);
err_count++;
}
}
}
intfdata->suspended = 0;
spin_unlock_irq(&intfdata->susp_lock);
if (err_count)
return -EIO;
return 0;
}
EXPORT_SYMBOL(usb_wwan_resume);
#endif
MODULE_AUTHOR(DRIVER_AUTHOR);
MODULE_DESCRIPTION(DRIVER_DESC);
MODULE_LICENSE("GPL");

218
quectel-CM/GobiNetCM.c Executable file
View File

@ -0,0 +1,218 @@
#include <stdio.h>
#include <string.h>
#include <termios.h>
#include <stdio.h>
#include <ctype.h>
#include "QMIThread.h"
#ifdef CONFIG_GOBINET
// IOCTL to generate a client ID for this service type
#define IOCTL_QMI_GET_SERVICE_FILE 0x8BE0 + 1
// IOCTL to get the VIDPID of the device
#define IOCTL_QMI_GET_DEVICE_VIDPID 0x8BE0 + 2
// IOCTL to get the MEID of the device
#define IOCTL_QMI_GET_DEVICE_MEID 0x8BE0 + 3
int GobiNetSendQMI(PQCQMIMSG pRequest) {
int ret, fd;
fd = qmiclientId[pRequest->QMIHdr.QMIType];
if (fd <= 0) {
dbg_time("%s QMIType: %d has no clientID", __func__, pRequest->QMIHdr.QMIType);
return -ENODEV;
}
// Always ready to write
if (1 == 1) {
ssize_t nwrites = le16_to_cpu(pRequest->QMIHdr.Length) + 1 - sizeof(QCQMI_HDR);
ret = write(fd, &pRequest->MUXMsg, nwrites);
if (ret == nwrites) {
ret = 0;
} else {
dbg_time("%s write=%d, errno: %d (%s)", __func__, ret, errno, strerror(errno));
}
} else {
dbg_time("%s poll=%d, errno: %d (%s)", __func__, ret, errno, strerror(errno));
}
return ret;
}
static int GobiNetGetClientID(const char *qcqmi, UCHAR QMIType) {
int ClientId;
ClientId = open(qcqmi, O_RDWR | O_NONBLOCK | O_NOCTTY);
if (ClientId == -1) {
dbg_time("failed to open %s, errno: %d (%s)", qcqmi, errno, strerror(errno));
return -1;
}
fcntl(cdc_wdm_fd, F_SETFD, FD_CLOEXEC) ;
if (ioctl(ClientId, IOCTL_QMI_GET_SERVICE_FILE, QMIType) != 0) {
dbg_time("failed to get ClientID for 0x%02x errno: %d (%s)", QMIType, errno, strerror(errno));
close(ClientId);
ClientId = 0;
}
switch (QMIType) {
case QMUX_TYPE_WDS: dbg_time("Get clientWDS = %d", ClientId); break;
case QMUX_TYPE_DMS: dbg_time("Get clientDMS = %d", ClientId); break;
case QMUX_TYPE_NAS: dbg_time("Get clientNAS = %d", ClientId); break;
case QMUX_TYPE_QOS: dbg_time("Get clientQOS = %d", ClientId); break;
case QMUX_TYPE_WMS: dbg_time("Get clientWMS = %d", ClientId); break;
case QMUX_TYPE_PDS: dbg_time("Get clientPDS = %d", ClientId); break;
case QMUX_TYPE_UIM: dbg_time("Get clientUIM = %d", ClientId); break;
case QMUX_TYPE_WDS_ADMIN: dbg_time("Get clientWDA = %d", ClientId);
break;
default: break;
}
return ClientId;
}
int GobiNetDeInit(void) {
unsigned int i;
for (i = 0; i < sizeof(qmiclientId)/sizeof(qmiclientId[0]); i++)
{
if (qmiclientId[i] != 0)
{
close(qmiclientId[i]);
qmiclientId[i] = 0;
}
}
return 0;
}
void * GobiNetThread(void *pData) {
PROFILE_T *profile = (PROFILE_T *)pData;
const char *qcqmi = (const char *)profile->qmichannel;
qmiclientId[QMUX_TYPE_WDS] = GobiNetGetClientID(qcqmi, QMUX_TYPE_WDS);
if (profile->IsDualIPSupported)
qmiclientId[QMUX_TYPE_WDS_IPV6] = GobiNetGetClientID(qcqmi, QMUX_TYPE_WDS);
qmiclientId[QMUX_TYPE_DMS] = GobiNetGetClientID(qcqmi, QMUX_TYPE_DMS);
qmiclientId[QMUX_TYPE_NAS] = GobiNetGetClientID(qcqmi, QMUX_TYPE_NAS);
qmiclientId[QMUX_TYPE_UIM] = GobiNetGetClientID(qcqmi, QMUX_TYPE_UIM);
if (profile->qmapnet_adapter == NULL) //when QMAP enabled, set data format in GobiNet Driver
qmiclientId[QMUX_TYPE_WDS_ADMIN] = GobiNetGetClientID(qcqmi, QMUX_TYPE_WDS_ADMIN);
//donot check clientWDA, there is only one client for WDA, if quectel-CM is killed by SIGKILL, i cannot get client ID for WDA again!
if (qmiclientId[QMUX_TYPE_WDS] == 0) /*|| (clientWDA == -1)*/ {
GobiNetDeInit();
dbg_time("%s Failed to open %s, errno: %d (%s)", __func__, qcqmi, errno, strerror(errno));
qmidevice_send_event_to_main(RIL_INDICATE_DEVICE_DISCONNECTED);
pthread_exit(NULL);
return NULL;
}
qmidevice_send_event_to_main(RIL_INDICATE_DEVICE_CONNECTED);
while (1) {
struct pollfd pollfds[16] = {{qmidevice_control_fd[1], POLLIN, 0}};
int ne, ret, nevents = 1;
unsigned int i;
for (i = 0; i < sizeof(qmiclientId)/sizeof(qmiclientId[0]); i++)
{
if (qmiclientId[i] != 0)
{
pollfds[nevents].fd = qmiclientId[i];
pollfds[nevents].events = POLLIN;
pollfds[nevents].revents = 0;
nevents++;
}
}
do {
ret = poll(pollfds, nevents, -1);
} while ((ret < 0) && (errno == EINTR));
if (ret <= 0) {
dbg_time("%s poll=%d, errno: %d (%s)", __func__, ret, errno, strerror(errno));
break;
}
for (ne = 0; ne < nevents; ne++) {
int fd = pollfds[ne].fd;
short revents = pollfds[ne].revents;
if (revents & (POLLERR | POLLHUP | POLLNVAL)) {
dbg_time("%s poll err/hup/inval", __func__);
dbg_time("epoll fd = %d, events = 0x%04x", fd, revents);
if (fd == qmidevice_control_fd[1]) {
} else {
}
if (revents & (POLLERR | POLLHUP | POLLNVAL))
goto __GobiNetThread_quit;
}
if ((revents & POLLIN) == 0)
continue;
if (fd == qmidevice_control_fd[1]) {
int triger_event;
if (read(fd, &triger_event, sizeof(triger_event)) == sizeof(triger_event)) {
//DBG("triger_event = 0x%x", triger_event);
switch (triger_event) {
case RIL_REQUEST_QUIT:
goto __GobiNetThread_quit;
break;
case SIGTERM:
case SIGHUP:
case SIGINT:
QmiThreadRecvQMI(NULL);
break;
default:
break;
}
}
continue;
}
{
ssize_t nreads;
UCHAR QMIBuf[512];
PQCQMIMSG pResponse = (PQCQMIMSG)QMIBuf;
nreads = read(fd, &pResponse->MUXMsg, sizeof(QMIBuf) - sizeof(QCQMI_HDR));
if (nreads <= 0)
{
dbg_time("%s read=%d errno: %d (%s)", __func__, (int)nreads, errno, strerror(errno));
break;
}
for (i = 0; i < sizeof(qmiclientId)/sizeof(qmiclientId[0]); i++)
{
if (qmiclientId[i] == fd)
{
pResponse->QMIHdr.QMIType = i;
}
}
pResponse->QMIHdr.IFType = USB_CTL_MSG_TYPE_QMI;
pResponse->QMIHdr.Length = cpu_to_le16(nreads + sizeof(QCQMI_HDR) - 1);
pResponse->QMIHdr.CtlFlags = 0x00;
pResponse->QMIHdr.ClientId = fd & 0xFF;
QmiThreadRecvQMI(pResponse);
}
}
}
__GobiNetThread_quit:
GobiNetDeInit();
qmidevice_send_event_to_main(RIL_INDICATE_DEVICE_DISCONNECTED);
QmiThreadRecvQMI(NULL); //main thread may pending on QmiThreadSendQMI()
dbg_time("%s exit", __func__);
pthread_exit(NULL);
return NULL;
}
#else
int GobiNetSendQMI(PQCQMIMSG pRequest) {return -1;}
void * GobiNetThread(void *pData) {dbg_time("please set CONFIG_GOBINET"); return NULL;}
#endif

376
quectel-CM/MPQCTL.h Executable file
View File

@ -0,0 +1,376 @@
/*===========================================================================
M P Q C T L. H
DESCRIPTION:
This module contains QMI QCTL module.
INITIALIZATION AND SEQUENCING REQUIREMENTS:
Copyright (C) 2011 by Qualcomm Technologies, Incorporated. All Rights Reserved.
===========================================================================*/
#ifndef MPQCTL_H
#define MPQCTL_H
#include "MPQMI.h"
#pragma pack(push, 1)
// ================= QMICTL ==================
// QMICTL Control Flags
#define QMICTL_CTL_FLAG_CMD 0x00
#define QMICTL_CTL_FLAG_RSP 0x01
#define QMICTL_CTL_FLAG_IND 0x02
#if 0
typedef struct _QMICTL_TRANSACTION_ITEM
{
LIST_ENTRY List;
UCHAR TransactionId; // QMICTL transaction id
PVOID Context; // Adapter or IocDev
PIRP Irp;
} QMICTL_TRANSACTION_ITEM, *PQMICTL_TRANSACTION_ITEM;
#endif
typedef struct _QCQMICTL_MSG_HDR
{
UCHAR CtlFlags; // 00-cmd, 01-rsp, 10-ind
UCHAR TransactionId;
USHORT QMICTLType;
USHORT Length;
} __attribute__ ((packed)) QCQMICTL_MSG_HDR, *PQCQMICTL_MSG_HDR;
#define QCQMICTL_MSG_HDR_SIZE sizeof(QCQMICTL_MSG_HDR)
typedef struct _QCQMICTL_MSG_HDR_RESP
{
UCHAR CtlFlags; // 00-cmd, 01-rsp, 10-ind
UCHAR TransactionId;
USHORT QMICTLType;
USHORT Length;
UCHAR TLVType; // 0x02 - result code
USHORT TLVLength; // 4
USHORT QMUXResult; // QMI_RESULT_SUCCESS
// QMI_RESULT_FAILURE
USHORT QMUXError; // QMI_ERR_INVALID_ARG
// QMI_ERR_NO_MEMORY
// QMI_ERR_INTERNAL
// QMI_ERR_FAULT
} __attribute__ ((packed)) QCQMICTL_MSG_HDR_RESP, *PQCQMICTL_MSG_HDR_RESP;
typedef struct _QCQMICTL_MSG
{
UCHAR CtlFlags; // 00-cmd, 01-rsp, 10-ind
UCHAR TransactionId;
USHORT QMICTLType;
USHORT Length;
UCHAR Payload;
} __attribute__ ((packed)) QCQMICTL_MSG, *PQCQMICTL_MSG;
// TLV Header
typedef struct _QCQMICTL_TLV_HDR
{
UCHAR TLVType;
USHORT TLVLength;
} __attribute__ ((packed)) QCQMICTL_TLV_HDR, *PQCQMICTL_TLV_HDR;
#define QCQMICTL_TLV_HDR_SIZE sizeof(QCQMICTL_TLV_HDR)
// QMICTL Type
#define QMICTL_SET_INSTANCE_ID_REQ 0x0020
#define QMICTL_SET_INSTANCE_ID_RESP 0x0020
#define QMICTL_GET_VERSION_REQ 0x0021
#define QMICTL_GET_VERSION_RESP 0x0021
#define QMICTL_GET_CLIENT_ID_REQ 0x0022
#define QMICTL_GET_CLIENT_ID_RESP 0x0022
#define QMICTL_RELEASE_CLIENT_ID_REQ 0x0023
#define QMICTL_RELEASE_CLIENT_ID_RESP 0x0023
#define QMICTL_REVOKE_CLIENT_ID_IND 0x0024
#define QMICTL_INVALID_CLIENT_ID_IND 0x0025
#define QMICTL_SET_DATA_FORMAT_REQ 0x0026
#define QMICTL_SET_DATA_FORMAT_RESP 0x0026
#define QMICTL_SYNC_REQ 0x0027
#define QMICTL_SYNC_RESP 0x0027
#define QMICTL_SYNC_IND 0x0027
#define QMICTL_FLAG_REQUEST 0x00
#define QMICTL_FLAG_RESPONSE 0x01
#define QMICTL_FLAG_INDICATION 0x02
// QMICTL Message Definitions
typedef struct _QMICTL_SET_INSTANCE_ID_REQ_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_REQUEST
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_SET_INSTANCE_ID_REQ
USHORT Length; // 4
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // 1
UCHAR Value; // Host-unique QMI instance for this device driver
} __attribute__ ((packed)) QMICTL_SET_INSTANCE_ID_REQ_MSG, *PQMICTL_SET_INSTANCE_ID_REQ_MSG;
typedef struct _QMICTL_SET_INSTANCE_ID_RESP_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_RESPONSE
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_SET_INSTANCE_ID_RESP
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_RESULT_CODE
USHORT TLVLength; // 0x0004
USHORT QMIResult;
USHORT QMIError;
UCHAR TLV2Type; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLV2Length; // 0x0002
USHORT QMI_ID; // Upper byte is assigned by MSM,
// lower assigned by host
} __attribute__ ((packed)) QMICTL_SET_INSTANCE_ID_RESP_MSG, *PQMICTL_SET_INSTANCE_ID_RESP_MSG;
typedef struct _QMICTL_GET_VERSION_REQ_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_REQUEST
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_GET_VERSION_REQ
USHORT Length; // 0
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // var
UCHAR QMUXTypes; // List of one byte QMUX_TYPE values
// 0xFF returns a list of versions for all
// QMUX_TYPEs implemented on the device
} __attribute__ ((packed)) QMICTL_GET_VERSION_REQ_MSG, *PQMICTL_GET_VERSION_REQ_MSG;
typedef struct _QMUX_TYPE_VERSION_STRUCT
{
UCHAR QMUXType;
USHORT MajorVersion;
USHORT MinorVersion;
} __attribute__ ((packed)) QMUX_TYPE_VERSION_STRUCT, *PQMUX_TYPE_VERSION_STRUCT;
typedef struct _ADDENDUM_VERSION_PREAMBLE
{
UCHAR LabelLength;
UCHAR Label;
} __attribute__ ((packed)) ADDENDUM_VERSION_PREAMBLE, *PADDENDUM_VERSION_PREAMBLE;
#define QMICTL_GET_VERSION_RSP_TLV_TYPE_VERSION 0x01
#define QMICTL_GET_VERSION_RSP_TLV_TYPE_ADD_VERSION 0x10
typedef struct _QMICTL_GET_VERSION_RESP_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_RESPONSE
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_GET_VERSION_RESP
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_RESULT_CODE
USHORT TLVLength; // 0x0004
USHORT QMIResult;
USHORT QMIError;
UCHAR TLV2Type; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLV2Length; // var
UCHAR NumElements; // Num of QMUX_TYPE_VERSION_STRUCT
QMUX_TYPE_VERSION_STRUCT TypeVersion[0];
} __attribute__ ((packed)) QMICTL_GET_VERSION_RESP_MSG, *PQMICTL_GET_VERSION_RESP_MSG;
typedef struct _QMICTL_GET_CLIENT_ID_REQ_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_REQUEST
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_GET_CLIENT_ID_REQ
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // 1
UCHAR QMIType; // QMUX type
} __attribute__ ((packed)) QMICTL_GET_CLIENT_ID_REQ_MSG, *PQMICTL_GET_CLIENT_ID_REQ_MSG;
typedef struct _QMICTL_GET_CLIENT_ID_RESP_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_RESPONSE
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_GET_CLIENT_ID_RESP
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_RESULT_CODE
USHORT TLVLength; // 0x0004
USHORT QMIResult; // result code
USHORT QMIError; // error code
UCHAR TLV2Type; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLV2Length; // 2
UCHAR QMIType;
UCHAR ClientId;
} __attribute__ ((packed)) QMICTL_GET_CLIENT_ID_RESP_MSG, *PQMICTL_GET_CLIENT_ID_RESP_MSG;
typedef struct _QMICTL_RELEASE_CLIENT_ID_REQ_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_REQUEST
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_RELEASE_CLIENT_ID_REQ
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // 0x0002
UCHAR QMIType;
UCHAR ClientId;
} __attribute__ ((packed)) QMICTL_RELEASE_CLIENT_ID_REQ_MSG, *PQMICTL_RELEASE_CLIENT_ID_REQ_MSG;
typedef struct _QMICTL_RELEASE_CLIENT_ID_RESP_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_RESPONSE
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_RELEASE_CLIENT_ID_RESP
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_RESULT_CODE
USHORT TLVLength; // 0x0004
USHORT QMIResult; // result code
USHORT QMIError; // error code
UCHAR TLV2Type; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLV2Length; // 2
UCHAR QMIType;
UCHAR ClientId;
} __attribute__ ((packed)) QMICTL_RELEASE_CLIENT_ID_RESP_MSG, *PQMICTL_RELEASE_CLIENT_ID_RESP_MSG;
typedef struct _QMICTL_REVOKE_CLIENT_ID_IND_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_INDICATION
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_REVOKE_CLIENT_ID_IND
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // 0x0002
UCHAR QMIType;
UCHAR ClientId;
} __attribute__ ((packed)) QMICTL_REVOKE_CLIENT_ID_IND_MSG, *PQMICTL_REVOKE_CLIENT_ID_IND_MSG;
typedef struct _QMICTL_INVALID_CLIENT_ID_IND_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_INDICATION
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_REVOKE_CLIENT_ID_IND
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // 0x0002
UCHAR QMIType;
UCHAR ClientId;
} __attribute__ ((packed)) QMICTL_INVALID_CLIENT_ID_IND_MSG, *PQMICTL_INVALID_CLIENT_ID_IND_MSG;
typedef struct _QMICTL_SET_DATA_FORMAT_REQ_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_REQUEST
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_SET_DATA_FORMAT_REQ
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_REQUIRED_PARAMETER
USHORT TLVLength; // 1
UCHAR DataFormat; // 0-default; 1-QoS hdr present
} __attribute__ ((packed)) QMICTL_SET_DATA_FORMAT_REQ_MSG, *PQMICTL_SET_DATA_FORMAT_REQ_MSG;
#ifdef QC_IP_MODE
#define SET_DATA_FORMAT_TLV_TYPE_LINK_PROTO 0x10
#define SET_DATA_FORMAT_LINK_PROTO_ETH 0x0001
#define SET_DATA_FORMAT_LINK_PROTO_IP 0x0002
typedef struct _QMICTL_SET_DATA_FORMAT_TLV_LINK_PROT
{
UCHAR TLVType; // Link-Layer Protocol
USHORT TLVLength; // 2
USHORT LinkProt; // 0x1: ETH; 0x2: IP
} QMICTL_SET_DATA_FORMAT_TLV_LINK_PROT, *PQMICTL_SET_DATA_FORMAT_TLV_LINK_PROT;
#ifdef QCMP_UL_TLP
#define SET_DATA_FORMAT_TLV_TYPE_UL_TLP 0x11
typedef struct _QMICTL_SET_DATA_FORMAT_TLV_UL_TLP
{
UCHAR TLVType; // 0x11, Uplink TLP Setting
USHORT TLVLength; // 1
UCHAR UlTlpSetting; // 0x0: Disable; 0x01: Enable
} QMICTL_SET_DATA_FORMAT_TLV_UL_TLP, *PQMICTL_SET_DATA_FORMAT_TLV_UL_TLP;
#endif // QCMP_UL_TLP
#ifdef QCMP_DL_TLP
#define SET_DATA_FORMAT_TLV_TYPE_DL_TLP 0x13
typedef struct _QMICTL_SET_DATA_FORMAT_TLV_DL_TLP
{
UCHAR TLVType; // 0x11, Uplink TLP Setting
USHORT TLVLength; // 1
UCHAR DlTlpSetting; // 0x0: Disable; 0x01: Enable
} QMICTL_SET_DATA_FORMAT_TLV_DL_TLP, *PQMICTL_SET_DATA_FORMAT_TLV_DL_TLP;
#endif // QCMP_DL_TLP
#endif // QC_IP_MODE
#ifdef MP_QCQOS_ENABLED
#define SET_DATA_FORMAT_TLV_TYPE_QOS_SETTING 0x12
typedef struct _QMICTL_SET_DATA_FORMAT_TLV_QOS_SETTING
{
UCHAR TLVType; // 0x12, QoS setting
USHORT TLVLength; // 1
UCHAR QosSetting; // 0x0: Disable; 0x01: Enable
} QMICTL_SET_DATA_FORMAT_TLV_QOS_SETTING, *PQMICTL_SET_DATA_FORMAT_TLV_QOS_SETTING;
#endif // MP_QCQOS_ENABLED
typedef struct _QMICTL_SET_DATA_FORMAT_RESP_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_RESPONSE
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_SET_DATA_FORMAT_RESP
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_RESULT_CODE
USHORT TLVLength; // 0x0004
USHORT QMIResult; // result code
USHORT QMIError; // error code
} __attribute__ ((packed)) QMICTL_SET_DATA_FORMAT_RESP_MSG, *PQMICTL_SET_DATA_FORMAT_RESP_MSG;
typedef struct _QMICTL_SYNC_REQ_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_REQUEST
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_CTL_SYNC_REQ
USHORT Length; // 0
} __attribute__ ((packed)) QMICTL_SYNC_REQ_MSG, *PQMICTL_SYNC_REQ_MSG;
typedef struct _QMICTL_SYNC_RESP_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_RESPONSE
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_CTL_SYNC_RESP
USHORT Length;
UCHAR TLVType; // QCTLV_TYPE_RESULT_CODE
USHORT TLVLength; // 0x0004
USHORT QMIResult;
USHORT QMIError;
} __attribute__ ((packed)) QMICTL_SYNC_RESP_MSG, *PQMICTL_SYNC_RESP_MSG;
typedef struct _QMICTL_SYNC_IND_MSG
{
UCHAR CtlFlags; // QMICTL_FLAG_INDICATION
UCHAR TransactionId;
USHORT QMICTLType; // QMICTL_REVOKE_CLIENT_ID_IND
USHORT Length;
} __attribute__ ((packed)) QMICTL_SYNC_IND_MSG, *PQMICTL_SYNC_IND_MSG;
typedef struct _QMICTL_MSG
{
union
{
// Message Header
QCQMICTL_MSG_HDR QMICTLMsgHdr;
QCQMICTL_MSG_HDR_RESP QMICTLMsgHdrRsp;
// QMICTL Message
QMICTL_SET_INSTANCE_ID_REQ_MSG SetInstanceIdReq;
QMICTL_SET_INSTANCE_ID_RESP_MSG SetInstanceIdRsp;
QMICTL_GET_VERSION_REQ_MSG GetVersionReq;
QMICTL_GET_VERSION_RESP_MSG GetVersionRsp;
QMICTL_GET_CLIENT_ID_REQ_MSG GetClientIdReq;
QMICTL_GET_CLIENT_ID_RESP_MSG GetClientIdRsp;
QMICTL_RELEASE_CLIENT_ID_REQ_MSG ReleaseClientIdReq;
QMICTL_RELEASE_CLIENT_ID_RESP_MSG ReleaseClientIdRsp;
QMICTL_REVOKE_CLIENT_ID_IND_MSG RevokeClientIdInd;
QMICTL_INVALID_CLIENT_ID_IND_MSG InvalidClientIdInd;
QMICTL_SET_DATA_FORMAT_REQ_MSG SetDataFormatReq;
QMICTL_SET_DATA_FORMAT_RESP_MSG SetDataFormatRsp;
QMICTL_SYNC_REQ_MSG SyncReq;
QMICTL_SYNC_RESP_MSG SyncRsp;
QMICTL_SYNC_IND_MSG SyncInd;
};
} __attribute__ ((packed)) QMICTL_MSG, *PQMICTL_MSG;
#endif // MPQCTL_H

222
quectel-CM/MPQMI.h Executable file
View File

@ -0,0 +1,222 @@
/*===========================================================================
M P Q M I. H
DESCRIPTION:
This module contains forward references to the QMI module.
INITIALIZATION AND SEQUENCING REQUIREMENTS:
Copyright (C) 2011 by Qualcomm Technologies, Incorporated. All Rights Reserved.
===========================================================================*/
/*===========================================================================
EDIT HISTORY FOR FILE
$Header: //depot/QMI/win/qcdrivers/ndis/MPQMI.h#3 $
when who what, where, why
-------- --- ----------------------------------------------------------
11/20/04 hg Initial version.
===========================================================================*/
#ifndef USBQMI_H
#define USBQMI_H
typedef char CHAR;
typedef unsigned char UCHAR;
typedef unsigned short USHORT;
typedef int INT;
typedef unsigned int UINT;
typedef long LONG;
typedef unsigned int ULONG;
typedef unsigned long long ULONG64;
typedef char *PCHAR;
typedef unsigned char *PUCHAR;
typedef int *PINT;
typedef int BOOL;
#define TRUE (1 == 1)
#define FALSE (1 != 1)
#define QMICTL_SUPPORTED_MAJOR_VERSION 1
#define QMICTL_SUPPORTED_MINOR_VERSION 0
#pragma pack(push, 1)
// ========= USB Control Message ==========
#define USB_CTL_MSG_TYPE_QMI 0x01
// USB Control Message
typedef struct _QCUSB_CTL_MSG_HDR
{
UCHAR IFType;
} __attribute__ ((packed)) QCUSB_CTL_MSG_HDR, *PQCUSB_CTL_MSG_HDR;
#define QCUSB_CTL_MSG_HDR_SIZE sizeof(QCUSB_CTL_MSG_HDR)
typedef struct _QCUSB_CTL_MSG
{
UCHAR IFType;
UCHAR Message;
} __attribute__ ((packed)) QCUSB_CTL_MSG, *PQCUSB_CTL_MSG;
#define QCTLV_TYPE_REQUIRED_PARAMETER 0x01
#define QCTLV_TYPE_RESULT_CODE 0x02
// ================= QMI ==================
// Define QMI Type
typedef enum _QMI_SERVICE_TYPE
{
QMUX_TYPE_CTL = 0x00,
QMUX_TYPE_WDS = 0x01,
QMUX_TYPE_DMS = 0x02,
QMUX_TYPE_NAS = 0x03,
QMUX_TYPE_QOS = 0x04,
QMUX_TYPE_WMS = 0x05,
QMUX_TYPE_PDS = 0x06,
QMUX_TYPE_UIM = 0x0B,
QMUX_TYPE_WDS_IPV6 = 0x11,
QMUX_TYPE_WDS_ADMIN = 0x1A,
QMUX_TYPE_MAX = 0xFF,
QMUX_TYPE_ALL = 0xFF
} QMI_SERVICE_TYPE;
typedef enum _QMI_RESULT_CODE_TYPE
{
QMI_RESULT_SUCCESS = 0x0000,
QMI_RESULT_FAILURE = 0x0001
} QMI_RESULT_CODE_TYPE;
typedef enum _QMI_ERROR_CODE_TYPE
{
QMI_ERR_NONE = 0x0000,
QMI_ERR_INTERNAL = 0x0003,
QMI_ERR_CLIENT_IDS_EXHAUSTED = 0x0005,
QMI_ERR_DENIED = 0x0006,
QMI_ERR_INVALID_CLIENT_IDS = 0x0007,
QMI_ERR_NO_BATTERY = 0x0008,
QMI_ERR_INVALID_HANDLE = 0x0009,
QMI_ERR_INVALID_PROFILE = 0x000A,
QMI_ERR_STORAGE_EXCEEDED = 0x000B,
QMI_ERR_INCORRECT_PIN = 0x000C,
QMI_ERR_NO_NETWORK = 0x000D,
QMI_ERR_PIN_LOCKED = 0x000E,
QMI_ERR_OUT_OF_CALL = 0x000F,
QMI_ERR_NOT_PROVISIONED = 0x0010,
QMI_ERR_ARG_TOO_LONG = 0x0013,
QMI_ERR_DEVICE_IN_USE = 0x0017,
QMI_ERR_OP_DEVICE_UNSUPPORTED = 0x0019,
QMI_ERR_NO_EFFECT = 0x001A,
QMI_ERR_INVALID_REGISTER_ACTION = 0x0020,
QMI_ERR_NO_MEMORY = 0x0021,
QMI_ERR_PIN_BLOCKED = 0x0023,
QMI_ERR_PIN_PERM_BLOCKED = 0x0024,
QMI_ERR_INVALID_ARG = 0x0030,
QMI_ERR_INVALID_INDEX = 0x0031,
QMI_ERR_NO_ENTRY = 0x0032,
QMI_ERR_EXTENDED_INTERNAL = 0x0051,
QMI_ERR_ACCESS_DENIED = 0x0052
} QMI_ERROR_CODE_TYPE;
#define QCQMI_CTL_FLAG_SERVICE 0x80
#define QCQMI_CTL_FLAG_CTL_POINT 0x00
typedef struct _QCQMI_HDR
{
UCHAR IFType;
USHORT Length;
UCHAR CtlFlags; // reserved
UCHAR QMIType;
UCHAR ClientId;
} __attribute__ ((packed)) QCQMI_HDR, *PQCQMI_HDR;
#define QCQMI_HDR_SIZE (sizeof(QCQMI_HDR)-1)
typedef struct _QCQMI
{
UCHAR IFType;
USHORT Length;
UCHAR CtlFlags; // reserved
UCHAR QMIType;
UCHAR ClientId;
UCHAR SDU;
} __attribute__ ((packed)) QCQMI, *PQCQMI;
typedef struct _QMI_SERVICE_VERSION
{
USHORT Major;
USHORT Minor;
USHORT AddendumMajor;
USHORT AddendumMinor;
} __attribute__ ((packed)) QMI_SERVICE_VERSION, *PQMI_SERVICE_VERSION;
// ================= QMUX ==================
#define QMUX_MSG_OVERHEAD_BYTES 4 // Type(USHORT) Length(USHORT) -- header
#define QMUX_BROADCAST_CID 0xFF
typedef struct _QCQMUX_HDR
{
UCHAR CtlFlags; // 0: single QMUX Msg; 1:
USHORT TransactionId;
} __attribute__ ((packed)) QCQMUX_HDR, *PQCQMUX_HDR;
typedef struct _QCQMUX
{
UCHAR CtlFlags; // 0: single QMUX Msg; 1:
USHORT TransactionId;
UCHAR Message; // Type(2), Length(2), Value
} __attribute__ ((packed)) QCQMUX, *PQCQMUX;
#define QCQMUX_HDR_SIZE sizeof(QCQMUX_HDR)
typedef struct _QCQMUX_MSG_HDR
{
USHORT Type;
USHORT Length;
} __attribute__ ((packed)) QCQMUX_MSG_HDR, *PQCQMUX_MSG_HDR;
#define QCQMUX_MSG_HDR_SIZE sizeof(QCQMUX_MSG_HDR)
typedef struct _QCQMUX_MSG_HDR_RESP
{
USHORT Type;
USHORT Length;
UCHAR TLVType; // 0x02 - result code
USHORT TLVLength; // 4
USHORT QMUXResult; // QMI_RESULT_SUCCESS
// QMI_RESULT_FAILURE
USHORT QMUXError; // QMI_ERR_INVALID_ARG
// QMI_ERR_NO_MEMORY
// QMI_ERR_INTERNAL
// QMI_ERR_FAULT
} __attribute__ ((packed)) QCQMUX_MSG_HDR_RESP, *PQCQMUX_MSG_HDR_RESP;
typedef struct _QCQMUX_TLV
{
UCHAR Type;
USHORT Length;
UCHAR Value;
} __attribute__ ((packed)) QCQMUX_TLV, *PQCQMUX_TLV;
typedef struct _QMI_TLV_HDR
{
UCHAR TLVType;
USHORT TLVLength;
} __attribute__ ((packed)) QMI_TLV_HDR, *PQMI_TLV_HDR;
// QMUX Message Definitions -- QMI SDU
#define QMUX_CTL_FLAG_SINGLE_MSG 0x00
#define QMUX_CTL_FLAG_COMPOUND_MSG 0x01
#define QMUX_CTL_FLAG_TYPE_CMD 0x00
#define QMUX_CTL_FLAG_TYPE_RSP 0x02
#define QMUX_CTL_FLAG_TYPE_IND 0x04
#define QMUX_CTL_FLAG_MASK_COMPOUND 0x01
#define QMUX_CTL_FLAG_MASK_TYPE 0x06 // 00-cmd, 01-rsp, 10-ind
#pragma pack(pop)
#endif // USBQMI_H

424
quectel-CM/MPQMUX.c Executable file
View File

@ -0,0 +1,424 @@
#include "QMIThread.h"
static char line[1024];
static pthread_mutex_t dumpQMIMutex = PTHREAD_MUTEX_INITIALIZER;
#undef dbg
#define dbg( format, arg... ) do {if (strlen(line) < sizeof(line)) snprintf(&line[strlen(line)], sizeof(line) - strlen(line), format, ## arg);} while (0)
PQMI_TLV_HDR GetTLV (PQCQMUX_MSG_HDR pQMUXMsgHdr, int TLVType);
typedef struct {
UINT type;
const char *name;
} QMI_NAME_T;
#define qmi_name_item(type) {type, #type}
static const QMI_NAME_T qmi_IFType[] = {
{USB_CTL_MSG_TYPE_QMI, "USB_CTL_MSG_TYPE_QMI"},
};
static const QMI_NAME_T qmi_CtlFlags[] = {
qmi_name_item(QMICTL_CTL_FLAG_CMD),
qmi_name_item(QCQMI_CTL_FLAG_SERVICE),
};
static const QMI_NAME_T qmi_QMIType[] = {
qmi_name_item(QMUX_TYPE_CTL),
qmi_name_item(QMUX_TYPE_WDS),
qmi_name_item(QMUX_TYPE_DMS),
qmi_name_item(QMUX_TYPE_NAS),
qmi_name_item(QMUX_TYPE_QOS),
qmi_name_item(QMUX_TYPE_WMS),
qmi_name_item(QMUX_TYPE_PDS),
qmi_name_item(QMUX_TYPE_WDS_ADMIN),
};
static const QMI_NAME_T qmi_ctl_CtlFlags[] = {
qmi_name_item(QMICTL_FLAG_REQUEST),
qmi_name_item(QMICTL_FLAG_RESPONSE),
qmi_name_item(QMICTL_FLAG_INDICATION),
};
static const QMI_NAME_T qmux_ctl_QMICTLType[] = {
// QMICTL Type
qmi_name_item(QMICTL_SET_INSTANCE_ID_REQ), // 0x0020
qmi_name_item(QMICTL_SET_INSTANCE_ID_RESP), // 0x0020
qmi_name_item(QMICTL_GET_VERSION_REQ), // 0x0021
qmi_name_item(QMICTL_GET_VERSION_RESP), // 0x0021
qmi_name_item(QMICTL_GET_CLIENT_ID_REQ), // 0x0022
qmi_name_item(QMICTL_GET_CLIENT_ID_RESP), // 0x0022
qmi_name_item(QMICTL_RELEASE_CLIENT_ID_REQ), // 0x0023
qmi_name_item(QMICTL_RELEASE_CLIENT_ID_RESP), // 0x0023
qmi_name_item(QMICTL_REVOKE_CLIENT_ID_IND), // 0x0024
qmi_name_item(QMICTL_INVALID_CLIENT_ID_IND), // 0x0025
qmi_name_item(QMICTL_SET_DATA_FORMAT_REQ), // 0x0026
qmi_name_item(QMICTL_SET_DATA_FORMAT_RESP), // 0x0026
qmi_name_item(QMICTL_SYNC_REQ), // 0x0027
qmi_name_item(QMICTL_SYNC_RESP), // 0x0027
qmi_name_item(QMICTL_SYNC_IND), // 0x0027
};
static const QMI_NAME_T qmux_CtlFlags[] = {
qmi_name_item(QMUX_CTL_FLAG_TYPE_CMD),
qmi_name_item(QMUX_CTL_FLAG_TYPE_RSP),
qmi_name_item(QMUX_CTL_FLAG_TYPE_IND),
};
static const QMI_NAME_T qmux_wds_Type[] = {
qmi_name_item(QMIWDS_SET_EVENT_REPORT_REQ), // 0x0001
qmi_name_item(QMIWDS_SET_EVENT_REPORT_RESP), // 0x0001
qmi_name_item(QMIWDS_EVENT_REPORT_IND), // 0x0001
qmi_name_item(QMIWDS_START_NETWORK_INTERFACE_REQ), // 0x0020
qmi_name_item(QMIWDS_START_NETWORK_INTERFACE_RESP), // 0x0020
qmi_name_item(QMIWDS_STOP_NETWORK_INTERFACE_REQ), // 0x0021
qmi_name_item(QMIWDS_STOP_NETWORK_INTERFACE_RESP), // 0x0021
qmi_name_item(QMIWDS_GET_PKT_SRVC_STATUS_REQ), // 0x0022
qmi_name_item(QMIWDS_GET_PKT_SRVC_STATUS_RESP), // 0x0022
qmi_name_item(QMIWDS_GET_PKT_SRVC_STATUS_IND), // 0x0022
qmi_name_item(QMIWDS_GET_CURRENT_CHANNEL_RATE_REQ), // 0x0023
qmi_name_item(QMIWDS_GET_CURRENT_CHANNEL_RATE_RESP), // 0x0023
qmi_name_item(QMIWDS_GET_PKT_STATISTICS_REQ), // 0x0024
qmi_name_item(QMIWDS_GET_PKT_STATISTICS_RESP), // 0x0024
qmi_name_item(QMIWDS_MODIFY_PROFILE_SETTINGS_REQ), // 0x0028
qmi_name_item(QMIWDS_MODIFY_PROFILE_SETTINGS_RESP), // 0x0028
qmi_name_item(QMIWDS_GET_PROFILE_SETTINGS_REQ), // 0x002B
qmi_name_item(QMIWDS_GET_PROFILE_SETTINGS_RESP), // 0x002BD
qmi_name_item(QMIWDS_GET_DEFAULT_SETTINGS_REQ), // 0x002C
qmi_name_item(QMIWDS_GET_DEFAULT_SETTINGS_RESP), // 0x002C
qmi_name_item(QMIWDS_GET_RUNTIME_SETTINGS_REQ), // 0x002D
qmi_name_item(QMIWDS_GET_RUNTIME_SETTINGS_RESP), // 0x002D
qmi_name_item(QMIWDS_GET_MIP_MODE_REQ), // 0x002F
qmi_name_item(QMIWDS_GET_MIP_MODE_RESP), // 0x002F
qmi_name_item(QMIWDS_GET_DATA_BEARER_REQ), // 0x0037
qmi_name_item(QMIWDS_GET_DATA_BEARER_RESP), // 0x0037
qmi_name_item(QMIWDS_DUN_CALL_INFO_REQ), // 0x0038
qmi_name_item(QMIWDS_DUN_CALL_INFO_RESP), // 0x0038
qmi_name_item(QMIWDS_DUN_CALL_INFO_IND), // 0x0038
qmi_name_item(QMIWDS_SET_CLIENT_IP_FAMILY_PREF_REQ), // 0x004D
qmi_name_item(QMIWDS_SET_CLIENT_IP_FAMILY_PREF_RESP), // 0x004D
qmi_name_item(QMIWDS_SET_AUTO_CONNECT_REQ), // 0x0051
qmi_name_item(QMIWDS_SET_AUTO_CONNECT_RESP), // 0x0051
qmi_name_item(QMIWDS_BIND_MUX_DATA_PORT_REQ), // 0x00A2
qmi_name_item(QMIWDS_BIND_MUX_DATA_PORT_RESP), // 0x00A2
};
static const QMI_NAME_T qmux_dms_Type[] = {
// ======================= DMS ==============================
qmi_name_item(QMIDMS_SET_EVENT_REPORT_REQ), // 0x0001
qmi_name_item(QMIDMS_SET_EVENT_REPORT_RESP), // 0x0001
qmi_name_item(QMIDMS_EVENT_REPORT_IND), // 0x0001
qmi_name_item(QMIDMS_GET_DEVICE_CAP_REQ), // 0x0020
qmi_name_item(QMIDMS_GET_DEVICE_CAP_RESP), // 0x0020
qmi_name_item(QMIDMS_GET_DEVICE_MFR_REQ), // 0x0021
qmi_name_item(QMIDMS_GET_DEVICE_MFR_RESP), // 0x0021
qmi_name_item(QMIDMS_GET_DEVICE_MODEL_ID_REQ), // 0x0022
qmi_name_item(QMIDMS_GET_DEVICE_MODEL_ID_RESP), // 0x0022
qmi_name_item(QMIDMS_GET_DEVICE_REV_ID_REQ), // 0x0023
qmi_name_item(QMIDMS_GET_DEVICE_REV_ID_RESP), // 0x0023
qmi_name_item(QMIDMS_GET_MSISDN_REQ), // 0x0024
qmi_name_item(QMIDMS_GET_MSISDN_RESP), // 0x0024
qmi_name_item(QMIDMS_GET_DEVICE_SERIAL_NUMBERS_REQ), // 0x0025
qmi_name_item(QMIDMS_GET_DEVICE_SERIAL_NUMBERS_RESP), // 0x0025
qmi_name_item(QMIDMS_UIM_SET_PIN_PROTECTION_REQ), // 0x0027
qmi_name_item(QMIDMS_UIM_SET_PIN_PROTECTION_RESP), // 0x0027
qmi_name_item(QMIDMS_UIM_VERIFY_PIN_REQ), // 0x0028
qmi_name_item(QMIDMS_UIM_VERIFY_PIN_RESP), // 0x0028
qmi_name_item(QMIDMS_UIM_UNBLOCK_PIN_REQ), // 0x0029
qmi_name_item(QMIDMS_UIM_UNBLOCK_PIN_RESP), // 0x0029
qmi_name_item(QMIDMS_UIM_CHANGE_PIN_REQ), // 0x002A
qmi_name_item(QMIDMS_UIM_CHANGE_PIN_RESP), // 0x002A
qmi_name_item(QMIDMS_UIM_GET_PIN_STATUS_REQ), // 0x002B
qmi_name_item(QMIDMS_UIM_GET_PIN_STATUS_RESP), // 0x002B
qmi_name_item(QMIDMS_GET_DEVICE_HARDWARE_REV_REQ), // 0x002C
qmi_name_item(QMIDMS_GET_DEVICE_HARDWARE_REV_RESP), // 0x002C
qmi_name_item(QMIDMS_GET_OPERATING_MODE_REQ), // 0x002D
qmi_name_item(QMIDMS_GET_OPERATING_MODE_RESP), // 0x002D
qmi_name_item(QMIDMS_SET_OPERATING_MODE_REQ), // 0x002E
qmi_name_item(QMIDMS_SET_OPERATING_MODE_RESP), // 0x002E
qmi_name_item(QMIDMS_GET_ACTIVATED_STATUS_REQ), // 0x0031
qmi_name_item(QMIDMS_GET_ACTIVATED_STATUS_RESP), // 0x0031
qmi_name_item(QMIDMS_ACTIVATE_AUTOMATIC_REQ), // 0x0032
qmi_name_item(QMIDMS_ACTIVATE_AUTOMATIC_RESP), // 0x0032
qmi_name_item(QMIDMS_ACTIVATE_MANUAL_REQ), // 0x0033
qmi_name_item(QMIDMS_ACTIVATE_MANUAL_RESP), // 0x0033
qmi_name_item(QMIDMS_UIM_GET_ICCID_REQ), // 0x003C
qmi_name_item(QMIDMS_UIM_GET_ICCID_RESP), // 0x003C
qmi_name_item(QMIDMS_UIM_GET_CK_STATUS_REQ), // 0x0040
qmi_name_item(QMIDMS_UIM_GET_CK_STATUS_RESP), // 0x0040
qmi_name_item(QMIDMS_UIM_SET_CK_PROTECTION_REQ), // 0x0041
qmi_name_item(QMIDMS_UIM_SET_CK_PROTECTION_RESP), // 0x0041
qmi_name_item(QMIDMS_UIM_UNBLOCK_CK_REQ), // 0x0042
qmi_name_item(QMIDMS_UIM_UNBLOCK_CK_RESP), // 0x0042
qmi_name_item(QMIDMS_UIM_GET_IMSI_REQ), // 0x0043
qmi_name_item(QMIDMS_UIM_GET_IMSI_RESP), // 0x0043
qmi_name_item(QMIDMS_UIM_GET_STATE_REQ), // 0x0044
qmi_name_item(QMIDMS_UIM_GET_STATE_RESP), // 0x0044
qmi_name_item(QMIDMS_GET_BAND_CAP_REQ), // 0x0045
qmi_name_item(QMIDMS_GET_BAND_CAP_RESP), // 0x0045
};
static const QMI_NAME_T qmux_nas_Type[] = {
// ======================= NAS ==============================
qmi_name_item(QMINAS_SET_EVENT_REPORT_REQ), // 0x0002
qmi_name_item(QMINAS_SET_EVENT_REPORT_RESP), // 0x0002
qmi_name_item(QMINAS_EVENT_REPORT_IND), // 0x0002
qmi_name_item(QMINAS_GET_SIGNAL_STRENGTH_REQ), // 0x0020
qmi_name_item(QMINAS_GET_SIGNAL_STRENGTH_RESP), // 0x0020
qmi_name_item(QMINAS_PERFORM_NETWORK_SCAN_REQ), // 0x0021
qmi_name_item(QMINAS_PERFORM_NETWORK_SCAN_RESP), // 0x0021
qmi_name_item(QMINAS_INITIATE_NW_REGISTER_REQ), // 0x0022
qmi_name_item(QMINAS_INITIATE_NW_REGISTER_RESP), // 0x0022
qmi_name_item(QMINAS_INITIATE_ATTACH_REQ), // 0x0023
qmi_name_item(QMINAS_INITIATE_ATTACH_RESP), // 0x0023
qmi_name_item(QMINAS_GET_SERVING_SYSTEM_REQ), // 0x0024
qmi_name_item(QMINAS_GET_SERVING_SYSTEM_RESP), // 0x0024
qmi_name_item(QMINAS_SERVING_SYSTEM_IND), // 0x0024
qmi_name_item(QMINAS_GET_HOME_NETWORK_REQ), // 0x0025
qmi_name_item(QMINAS_GET_HOME_NETWORK_RESP), // 0x0025
qmi_name_item(QMINAS_GET_PREFERRED_NETWORK_REQ), // 0x0026
qmi_name_item(QMINAS_GET_PREFERRED_NETWORK_RESP), // 0x0026
qmi_name_item(QMINAS_SET_PREFERRED_NETWORK_REQ), // 0x0027
qmi_name_item(QMINAS_SET_PREFERRED_NETWORK_RESP), // 0x0027
qmi_name_item(QMINAS_GET_FORBIDDEN_NETWORK_REQ), // 0x0028
qmi_name_item(QMINAS_GET_FORBIDDEN_NETWORK_RESP), // 0x0028
qmi_name_item(QMINAS_SET_FORBIDDEN_NETWORK_REQ), // 0x0029
qmi_name_item(QMINAS_SET_FORBIDDEN_NETWORK_RESP), // 0x0029
qmi_name_item(QMINAS_SET_TECHNOLOGY_PREF_REQ), // 0x002A
qmi_name_item(QMINAS_SET_TECHNOLOGY_PREF_RESP), // 0x002A
qmi_name_item(QMINAS_GET_RF_BAND_INFO_REQ), // 0x0031
qmi_name_item(QMINAS_GET_RF_BAND_INFO_RESP), // 0x0031
qmi_name_item(QMINAS_GET_PLMN_NAME_REQ), // 0x0044
qmi_name_item(QMINAS_GET_PLMN_NAME_RESP), // 0x0044
qmi_name_item(QUECTEL_PACKET_TRANSFER_START_IND), // 0X100
qmi_name_item(QUECTEL_PACKET_TRANSFER_END_IND), // 0X101
qmi_name_item(QMINAS_GET_SYS_INFO_REQ), // 0x004D
qmi_name_item(QMINAS_GET_SYS_INFO_RESP), // 0x004D
qmi_name_item(QMINAS_SYS_INFO_IND), // 0x004D
};
static const QMI_NAME_T qmux_wms_Type[] = {
// ======================= WMS ==============================
qmi_name_item(QMIWMS_SET_EVENT_REPORT_REQ), // 0x0001
qmi_name_item(QMIWMS_SET_EVENT_REPORT_RESP), // 0x0001
qmi_name_item(QMIWMS_EVENT_REPORT_IND), // 0x0001
qmi_name_item(QMIWMS_RAW_SEND_REQ), // 0x0020
qmi_name_item(QMIWMS_RAW_SEND_RESP), // 0x0020
qmi_name_item(QMIWMS_RAW_WRITE_REQ), // 0x0021
qmi_name_item(QMIWMS_RAW_WRITE_RESP), // 0x0021
qmi_name_item(QMIWMS_RAW_READ_REQ), // 0x0022
qmi_name_item(QMIWMS_RAW_READ_RESP), // 0x0022
qmi_name_item(QMIWMS_MODIFY_TAG_REQ), // 0x0023
qmi_name_item(QMIWMS_MODIFY_TAG_RESP), // 0x0023
qmi_name_item(QMIWMS_DELETE_REQ), // 0x0024
qmi_name_item(QMIWMS_DELETE_RESP), // 0x0024
qmi_name_item(QMIWMS_GET_MESSAGE_PROTOCOL_REQ), // 0x0030
qmi_name_item(QMIWMS_GET_MESSAGE_PROTOCOL_RESP), // 0x0030
qmi_name_item(QMIWMS_LIST_MESSAGES_REQ), // 0x0031
qmi_name_item(QMIWMS_LIST_MESSAGES_RESP), // 0x0031
qmi_name_item(QMIWMS_GET_SMSC_ADDRESS_REQ), // 0x0034
qmi_name_item(QMIWMS_GET_SMSC_ADDRESS_RESP), // 0x0034
qmi_name_item(QMIWMS_SET_SMSC_ADDRESS_REQ), // 0x0035
qmi_name_item(QMIWMS_SET_SMSC_ADDRESS_RESP), // 0x0035
qmi_name_item(QMIWMS_GET_STORE_MAX_SIZE_REQ), // 0x0036
qmi_name_item(QMIWMS_GET_STORE_MAX_SIZE_RESP), // 0x0036
};
static const QMI_NAME_T qmux_wds_admin_Type[] = {
qmi_name_item(QMIWDS_ADMIN_SET_DATA_FORMAT_REQ), // 0x0020
qmi_name_item(QMIWDS_ADMIN_SET_DATA_FORMAT_RESP), // 0x0020
qmi_name_item(QMIWDS_ADMIN_GET_DATA_FORMAT_REQ), // 0x0021
qmi_name_item(QMIWDS_ADMIN_GET_DATA_FORMAT_RESP), // 0x0021
qmi_name_item(QMIWDS_ADMIN_SET_QMAP_SETTINGS_REQ), // 0x002B
qmi_name_item(QMIWDS_ADMIN_SET_QMAP_SETTINGS_RESP), // 0x002B
qmi_name_item(QMIWDS_ADMIN_GET_QMAP_SETTINGS_REQ), // 0x002C
qmi_name_item(QMIWDS_ADMIN_GET_QMAP_SETTINGS_RESP), // 0x002C
};
static const QMI_NAME_T qmux_uim_Type[] = {
qmi_name_item( QMIUIM_READ_TRANSPARENT_REQ), // 0x0020
qmi_name_item( QMIUIM_READ_TRANSPARENT_RESP), // 0x0020
qmi_name_item( QMIUIM_READ_TRANSPARENT_IND), // 0x0020
qmi_name_item( QMIUIM_READ_RECORD_REQ), // 0x0021
qmi_name_item( QMIUIM_READ_RECORD_RESP), // 0x0021
qmi_name_item( QMIUIM_READ_RECORD_IND), // 0x0021
qmi_name_item( QMIUIM_WRITE_TRANSPARENT_REQ), // 0x0022
qmi_name_item( QMIUIM_WRITE_TRANSPARENT_RESP), // 0x0022
qmi_name_item( QMIUIM_WRITE_TRANSPARENT_IND), // 0x0022
qmi_name_item( QMIUIM_WRITE_RECORD_REQ), // 0x0023
qmi_name_item( QMIUIM_WRITE_RECORD_RESP), // 0x0023
qmi_name_item( QMIUIM_WRITE_RECORD_IND), // 0x0023
qmi_name_item( QMIUIM_SET_PIN_PROTECTION_REQ), // 0x0025
qmi_name_item( QMIUIM_SET_PIN_PROTECTION_RESP), // 0x0025
qmi_name_item( QMIUIM_SET_PIN_PROTECTION_IND), // 0x0025
qmi_name_item( QMIUIM_VERIFY_PIN_REQ), // 0x0026
qmi_name_item( QMIUIM_VERIFY_PIN_RESP), // 0x0026
qmi_name_item( QMIUIM_VERIFY_PIN_IND), // 0x0026
qmi_name_item( QMIUIM_UNBLOCK_PIN_REQ), // 0x0027
qmi_name_item( QMIUIM_UNBLOCK_PIN_RESP), // 0x0027
qmi_name_item( QMIUIM_UNBLOCK_PIN_IND), // 0x0027
qmi_name_item( QMIUIM_CHANGE_PIN_REQ), // 0x0028
qmi_name_item( QMIUIM_CHANGE_PIN_RESP), // 0x0028
qmi_name_item( QMIUIM_CHANGE_PIN_IND), // 0x0028
qmi_name_item( QMIUIM_DEPERSONALIZATION_REQ), // 0x0029
qmi_name_item( QMIUIM_DEPERSONALIZATION_RESP), // 0x0029
qmi_name_item( QMIUIM_EVENT_REG_REQ), // 0x002E
qmi_name_item( QMIUIM_EVENT_REG_RESP), // 0x002E
qmi_name_item( QMIUIM_GET_CARD_STATUS_REQ), // 0x002F
qmi_name_item( QMIUIM_GET_CARD_STATUS_RESP), // 0x002F
qmi_name_item( QMIUIM_STATUS_CHANGE_IND), // 0x0032
};
static const char * qmi_name_get(const QMI_NAME_T *table, size_t size, int type, const char *tag) {
static char unknow[40];
size_t i;
if (qmux_CtlFlags == table) {
if (!strcmp(tag, "_REQ"))
tag = "_CMD";
else if (!strcmp(tag, "_RESP"))
tag = "_RSP";
}
for (i = 0; i < size; i++) {
if (table[i].type == (UINT)type) {
if (!tag || (strstr(table[i].name, tag)))
return table[i].name;
}
}
sprintf(unknow, "unknow_%x", type);
return unknow;
}
#define QMI_NAME(table, type) qmi_name_get(table, sizeof(table) / sizeof(table[0]), type, 0)
#define QMUX_NAME(table, type, tag) qmi_name_get(table, sizeof(table) / sizeof(table[0]), type, tag)
void dump_tlv(PQCQMUX_MSG_HDR pQMUXMsgHdr) {
int TLVFind = 0;
int i;
//dbg("QCQMUX_TLV-----------------------------------\n");
//dbg("{Type,\tLength,\tValue}\n");
while (1) {
PQMI_TLV_HDR TLVHdr = GetTLV(pQMUXMsgHdr, 0x1000 + (++TLVFind));
if (TLVHdr == NULL)
break;
//if ((TLVHdr->TLVType == 0x02) && ((USHORT *)(TLVHdr+1))[0])
{
dbg("{%02x,\t%04x,\t", TLVHdr->TLVType, le16_to_cpu(TLVHdr->TLVLength));
for (i = 0; i < le16_to_cpu(TLVHdr->TLVLength); i++) {
dbg("%02x ", ((UCHAR *)(TLVHdr+1))[i]);
}
dbg("}\n");
}
} // while
}
void dump_ctl(PQCQMICTL_MSG_HDR CTLHdr) {
const char *tag;
//dbg("QCQMICTL_MSG--------------------------------------------\n");
//dbg("CtlFlags: %02x\t\t%s\n", CTLHdr->CtlFlags, QMI_NAME(qmi_ctl_CtlFlags, CTLHdr->CtlFlags));
dbg("TransactionId: %02x\n", CTLHdr->TransactionId);
switch (CTLHdr->CtlFlags) {
case QMICTL_FLAG_REQUEST: tag = "_REQ"; break;
case QMICTL_FLAG_RESPONSE: tag = "_RESP"; break;
case QMICTL_FLAG_INDICATION: tag = "_IND"; break;
default: tag = 0; break;
}
dbg("QMICTLType: %04x\t%s\n", le16_to_cpu(CTLHdr->QMICTLType),
QMUX_NAME(qmux_ctl_QMICTLType, le16_to_cpu(CTLHdr->QMICTLType), tag));
dbg("Length: %04x\n", le16_to_cpu(CTLHdr->Length));
dump_tlv((PQCQMUX_MSG_HDR)(&CTLHdr->QMICTLType));
}
int dump_qmux(QMI_SERVICE_TYPE serviceType, PQCQMUX_HDR QMUXHdr) {
PQCQMUX_MSG_HDR QMUXMsgHdr = (PQCQMUX_MSG_HDR) (QMUXHdr + 1);
CHAR *tag;
//dbg("QCQMUX--------------------------------------------\n");
switch (QMUXHdr->CtlFlags&QMUX_CTL_FLAG_MASK_TYPE) {
case QMUX_CTL_FLAG_TYPE_CMD: tag = "_REQ"; break;
case QMUX_CTL_FLAG_TYPE_RSP: tag = "_RESP"; break;
case QMUX_CTL_FLAG_TYPE_IND: tag = "_IND"; break;
default: tag = 0; break;
}
//dbg("CtlFlags: %02x\t\t%s\n", QMUXHdr->CtlFlags, QMUX_NAME(qmux_CtlFlags, QMUXHdr->CtlFlags, tag));
dbg("TransactionId: %04x\n", le16_to_cpu(QMUXHdr->TransactionId));
//dbg("QCQMUX_MSG_HDR-----------------------------------\n");
switch (serviceType) {
case QMUX_TYPE_DMS:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type),
QMUX_NAME(qmux_dms_Type, le16_to_cpu(QMUXMsgHdr->Type), tag));
break;
case QMUX_TYPE_NAS:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type),
QMUX_NAME(qmux_nas_Type, le16_to_cpu(QMUXMsgHdr->Type), tag));
break;
case QMUX_TYPE_WDS:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type),
QMUX_NAME(qmux_wds_Type, le16_to_cpu(QMUXMsgHdr->Type), tag));
break;
case QMUX_TYPE_WMS:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type),
QMUX_NAME(qmux_wms_Type, le16_to_cpu(QMUXMsgHdr->Type), tag));
break;
case QMUX_TYPE_WDS_ADMIN:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type),
QMUX_NAME(qmux_wds_admin_Type, le16_to_cpu(QMUXMsgHdr->Type), tag));
break;
case QMUX_TYPE_UIM:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type),
QMUX_NAME(qmux_uim_Type, le16_to_cpu(QMUXMsgHdr->Type), tag));
break;
case QMUX_TYPE_PDS:
case QMUX_TYPE_QOS:
case QMUX_TYPE_CTL:
default:
dbg("Type: %04x\t%s\n", le16_to_cpu(QMUXMsgHdr->Type), "PDS/QOS/CTL/unknown!");
break;
}
dbg("Length: %04x\n", le16_to_cpu(QMUXMsgHdr->Length));
dump_tlv(QMUXMsgHdr);
return 0;
}
void dump_qmi(void *dataBuffer, int dataLen)
{
PQCQMI_HDR QMIHdr = (PQCQMI_HDR)dataBuffer;
PQCQMUX_HDR QMUXHdr = (PQCQMUX_HDR) (QMIHdr + 1);
PQCQMICTL_MSG_HDR CTLHdr = (PQCQMICTL_MSG_HDR) (QMIHdr + 1);
int i;
if (!debug_qmi)
return;
pthread_mutex_lock(&dumpQMIMutex);
line[0] = 0;
for (i = 0; i < dataLen; i++) {
dbg("%02x ", ((unsigned char *)dataBuffer)[i]);
}
dbg_time("%s", line);
line[0] = 0;
//dbg("QCQMI_HDR-----------------------------------------");
//dbg("IFType: %02x\t\t%s", QMIHdr->IFType, QMI_NAME(qmi_IFType, QMIHdr->IFType));
//dbg("Length: %04x", le16_to_cpu(QMIHdr->Length));
//dbg("CtlFlags: %02x\t\t%s", QMIHdr->CtlFlags, QMI_NAME(qmi_CtlFlags, QMIHdr->CtlFlags));
//dbg("QMIType: %02x\t\t%s", QMIHdr->QMIType, QMI_NAME(qmi_QMIType, QMIHdr->QMIType));
//dbg("ClientId: %02x", QMIHdr->ClientId);
if (QMIHdr->QMIType == QMUX_TYPE_CTL) {
dump_ctl(CTLHdr);
} else {
dump_qmux(QMIHdr->QMIType, QMUXHdr);
}
dbg_time("%s", line);
pthread_mutex_unlock(&dumpQMIMutex);
}

3321
quectel-CM/MPQMUX.h Executable file

File diff suppressed because it is too large Load Diff

12
quectel-CM/Makefile Executable file
View File

@ -0,0 +1,12 @@
release: clean qmi-proxy
$(CC) -Wall -s QmiWwanCM.c GobiNetCM.c main.c MPQMUX.c QMIThread.c util.c udhcpc.c -o quectel-CM -lpthread -ldl
debug: clean
$(CC) -Wall -g QmiWwanCM.c GobiNetCM.c main.c MPQMUX.c QMIThread.c util.c udhcpc.c -o quectel-CM -lpthread -ldl
qmi-proxy:
$(CC) -Wall -s quectel-qmi-proxy.c -o quectel-qmi-proxy -lpthread -ldl
clean:
rm -rf quectel-CM *~
rm -rf quectel-qmi-proxy

1927
quectel-CM/QMIThread.c Executable file

File diff suppressed because it is too large Load Diff

177
quectel-CM/QMIThread.h Executable file
View File

@ -0,0 +1,177 @@
#ifndef __QMI_THREAD_H__
#define __QMI_THREAD_H__
#define CONFIG_GOBINET
#define CONFIG_QMIWWAN
#define CONFIG_SIM
#define CONFIG_APN
#define CONFIG_VERSION
#define CONFIG_DEFAULT_PDP 1
//#define CONFIG_IMSI_ICCID
#ifndef ANDROID
#define CONFIG_RESET_RADIO (45) //Reset Radiao(AT+CFUN=4,AT+CFUN=1) when cann not register network or setup data call in 45 seconds
#endif
#include <stdio.h>
#include <string.h>
#include <termios.h>
#include <stdio.h>
#include <ctype.h>
#include <time.h>
#include <fcntl.h>
#include <signal.h>
#include <errno.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
#include <errno.h>
#include <pthread.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/epoll.h>
#include <sys/poll.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <stddef.h>
#include "MPQMI.h"
#include "MPQCTL.h"
#include "MPQMUX.h"
#define DEVICE_CLASS_UNKNOWN 0
#define DEVICE_CLASS_CDMA 1
#define DEVICE_CLASS_GSM 2
#define WWAN_DATA_CLASS_NONE 0x00000000
#define WWAN_DATA_CLASS_GPRS 0x00000001
#define WWAN_DATA_CLASS_EDGE 0x00000002 /* EGPRS */
#define WWAN_DATA_CLASS_UMTS 0x00000004
#define WWAN_DATA_CLASS_HSDPA 0x00000008
#define WWAN_DATA_CLASS_HSUPA 0x00000010
#define WWAN_DATA_CLASS_LTE 0x00000020
#define WWAN_DATA_CLASS_1XRTT 0x00010000
#define WWAN_DATA_CLASS_1XEVDO 0x00020000
#define WWAN_DATA_CLASS_1XEVDO_REVA 0x00040000
#define WWAN_DATA_CLASS_1XEVDV 0x00080000
#define WWAN_DATA_CLASS_3XRTT 0x00100000
#define WWAN_DATA_CLASS_1XEVDO_REVB 0x00200000 /* for future use */
#define WWAN_DATA_CLASS_UMB 0x00400000
#define WWAN_DATA_CLASS_CUSTOM 0x80000000
struct wwan_data_class_str {
ULONG class;
CHAR *str;
};
#pragma pack(push, 1)
typedef struct _QCQMIMSG {
QCQMI_HDR QMIHdr;
union {
QMICTL_MSG CTLMsg;
QMUX_MSG MUXMsg;
};
} __attribute__ ((packed)) QCQMIMSG, *PQCQMIMSG;
#pragma pack(pop)
typedef struct __IPV4 {
uint32_t Address;
uint32_t Gateway;
uint32_t SubnetMask;
uint32_t DnsPrimary;
uint32_t DnsSecondary;
uint32_t Mtu;
} IPV4_T;
typedef struct __IPV6 {
UCHAR Address[16];
UCHAR Gateway[16];
UCHAR SubnetMask[16];
UCHAR DnsPrimary[16];
UCHAR DnsSecondary[16];
UCHAR PrefixLengthIPAddr;
UCHAR PrefixLengthGateway;
ULONG Mtu;
} IPV6_T;
#define IpFamilyV4 (0x04)
#define IpFamilyV6 (0x06)
typedef struct __PROFILE {
char * qmichannel;
char * usbnet_adapter;
char * qmapnet_adapter;
int qmap_mode;
int qmap_version;
const char *apn;
const char *user;
const char *password;
const char *pincode;
int auth;
int pdp;
int IsDualIPSupported;
int curIpFamily;
int rawIP;
IPV4_T ipv4;
IPV6_T ipv6;
} PROFILE_T;
typedef enum {
SIM_ABSENT = 0,
SIM_NOT_READY = 1,
SIM_READY = 2, /* SIM_READY means the radio state is RADIO_STATE_SIM_READY */
SIM_PIN = 3,
SIM_PUK = 4,
SIM_NETWORK_PERSONALIZATION = 5,
SIM_BAD = 6,
} SIM_Status;
#define WDM_DEFAULT_BUFSIZE 256
#define RIL_REQUEST_QUIT 0x1000
#define RIL_INDICATE_DEVICE_CONNECTED 0x1002
#define RIL_INDICATE_DEVICE_DISCONNECTED 0x1003
#define RIL_UNSOL_RESPONSE_VOICE_NETWORK_STATE_CHANGED 0x1004
#define RIL_UNSOL_DATA_CALL_LIST_CHANGED 0x1005
extern int pthread_cond_timeout_np(pthread_cond_t *cond, pthread_mutex_t * mutex, unsigned msecs);
extern int QmiThreadSendQMI(PQCQMIMSG pRequest, PQCQMIMSG *ppResponse);
extern int QmiThreadSendQMITimeout(PQCQMIMSG pRequest, PQCQMIMSG *ppResponse, unsigned msecs);
extern void QmiThreadRecvQMI(PQCQMIMSG pResponse);
extern int QmiWwanInit(PROFILE_T *profile);
extern int QmiWwanDeInit(void);
extern int QmiWwanSendQMI(PQCQMIMSG pRequest);
extern void * QmiWwanThread(void *pData);
extern int GobiNetSendQMI(PQCQMIMSG pRequest);
extern void * GobiNetThread(void *pData);
extern void udhcpc_start(PROFILE_T *profile);
extern void udhcpc_stop(PROFILE_T *profile);
extern void dump_qmi(void *dataBuffer, int dataLen);
extern void qmidevice_send_event_to_main(int triger_event);
extern int requestSetEthMode(PROFILE_T *profile);
extern int requestGetSIMStatus(SIM_Status *pSIMStatus);
extern int requestEnterSimPin(const CHAR *pPinCode);
extern int requestGetICCID(void);
extern int requestGetIMSI(void);
extern int requestRegistrationState(UCHAR *pPSAttachedState);
extern int requestQueryDataCall(UCHAR *pConnectionStatus, int curIpFamily);
extern int requestSetupDataCall(PROFILE_T *profile, int curIpFamily);
extern int requestDeactivateDefaultPDP(PROFILE_T *profile, int curIpFamily);
extern int requestSetProfile(PROFILE_T *profile);
extern int requestGetProfile(PROFILE_T *profile);
extern int requestBaseBandVersion(const char **pp_reversion);
extern int requestGetIPAddress(PROFILE_T *profile, int curIpFamily);
extern int requestSetOperatingMode(UCHAR OperatingMode);
extern FILE *logfilefp;
extern int debug_qmi;
extern char * qmichannel;
extern int qmidevice_control_fd[2];
extern int qmiclientId[QMUX_TYPE_WDS_ADMIN + 1];
extern int cdc_wdm_fd;
extern void dbg_time (const char *fmt, ...);
extern USHORT le16_to_cpu(USHORT v16);
extern UINT le32_to_cpu (UINT v32);
extern UINT ql_swap32(UINT v32);
extern USHORT cpu_to_le16(USHORT v16);
extern UINT cpu_to_le32(UINT v32);
#endif

359
quectel-CM/QmiWwanCM.c Executable file
View File

@ -0,0 +1,359 @@
#include <stdio.h>
#include <string.h>
#include <termios.h>
#include <stdio.h>
#include <ctype.h>
typedef unsigned short sa_family_t;
#include <linux/un.h>
#include "QMIThread.h"
#ifdef CONFIG_QMIWWAN
int cdc_wdm_fd = -1;
static UCHAR GetQCTLTransactionId(void) {
static int TransactionId = 0;
if (++TransactionId > 0xFF)
TransactionId = 1;
return TransactionId;
}
typedef USHORT (*CUSTOMQCTL)(PQMICTL_MSG pCTLMsg, void *arg);
static PQCQMIMSG ComposeQCTLMsg(USHORT QMICTLType, CUSTOMQCTL customQctlMsgFunction, void *arg) {
UCHAR QMIBuf[WDM_DEFAULT_BUFSIZE];
PQCQMIMSG pRequest = (PQCQMIMSG)QMIBuf;
int Length;
pRequest->QMIHdr.IFType = USB_CTL_MSG_TYPE_QMI;
pRequest->QMIHdr.CtlFlags = 0x00;
pRequest->QMIHdr.QMIType = QMUX_TYPE_CTL;
pRequest->QMIHdr.ClientId= 0x00;
pRequest->CTLMsg.QMICTLMsgHdr.CtlFlags = QMICTL_FLAG_REQUEST;
pRequest->CTLMsg.QMICTLMsgHdr.TransactionId = GetQCTLTransactionId();
pRequest->CTLMsg.QMICTLMsgHdr.QMICTLType = cpu_to_le16(QMICTLType);
if (customQctlMsgFunction)
pRequest->CTLMsg.QMICTLMsgHdr.Length = cpu_to_le16(customQctlMsgFunction(&pRequest->CTLMsg, arg) - sizeof(QCQMICTL_MSG_HDR));
else
pRequest->CTLMsg.QMICTLMsgHdr.Length = cpu_to_le16(0x0000);
pRequest->QMIHdr.Length = cpu_to_le16(le16_to_cpu(pRequest->CTLMsg.QMICTLMsgHdr.Length) + sizeof(QCQMICTL_MSG_HDR) + sizeof(QCQMI_HDR) - 1);
Length = le16_to_cpu(pRequest->QMIHdr.Length) + 1;
pRequest = (PQCQMIMSG)malloc(Length);
if (pRequest == NULL) {
dbg_time("%s fail to malloc", __func__);
} else {
memcpy(pRequest, QMIBuf, Length);
}
return pRequest;
}
static USHORT CtlGetVersionReq(PQMICTL_MSG QCTLMsg, void *arg) {
QCTLMsg->GetVersionReq.TLVType = QCTLV_TYPE_REQUIRED_PARAMETER;
QCTLMsg->GetVersionReq.TLVLength = cpu_to_le16(0x0001);
QCTLMsg->GetVersionReq.QMUXTypes = QMUX_TYPE_ALL;
return sizeof(QMICTL_GET_VERSION_REQ_MSG);
}
static USHORT CtlGetClientIdReq(PQMICTL_MSG QCTLMsg, void *arg) {
QCTLMsg->GetClientIdReq.TLVType = QCTLV_TYPE_REQUIRED_PARAMETER;
QCTLMsg->GetClientIdReq.TLVLength = cpu_to_le16(0x0001);
QCTLMsg->GetClientIdReq.QMIType = ((UCHAR *)arg)[0];
return sizeof(QMICTL_GET_CLIENT_ID_REQ_MSG);
}
static USHORT CtlReleaseClientIdReq(PQMICTL_MSG QCTLMsg, void *arg) {
QCTLMsg->ReleaseClientIdReq.TLVType = QCTLV_TYPE_REQUIRED_PARAMETER;
QCTLMsg->ReleaseClientIdReq.TLVLength = cpu_to_le16(0x0002);
QCTLMsg->ReleaseClientIdReq.QMIType = ((UCHAR *)arg)[0];
QCTLMsg->ReleaseClientIdReq.ClientId = ((UCHAR *)arg)[1] ;
return sizeof(QMICTL_RELEASE_CLIENT_ID_REQ_MSG);
}
int QmiWwanSendQMI(PQCQMIMSG pRequest) {
struct pollfd pollfds[]= {{cdc_wdm_fd, POLLOUT, 0}};
int ret;
if (cdc_wdm_fd == -1) {
dbg_time("%s cdc_wdm_fd = -1", __func__);
return -ENODEV;
}
if (pRequest->QMIHdr.QMIType == QMUX_TYPE_WDS_IPV6)
pRequest->QMIHdr.QMIType = QMUX_TYPE_WDS;
do {
ret = poll(pollfds, sizeof(pollfds)/sizeof(pollfds[0]), 5000);
} while ((ret < 0) && (errno == EINTR));
if (pollfds[0].revents & POLLOUT) {
ssize_t nwrites = le16_to_cpu(pRequest->QMIHdr.Length) + 1;
ret = write(cdc_wdm_fd, pRequest, nwrites);
if (ret == nwrites) {
ret = 0;
} else {
dbg_time("%s write=%d, errno: %d (%s)", __func__, ret, errno, strerror(errno));
}
} else {
dbg_time("%s poll=%d, revents = 0x%x, errno: %d (%s)", __func__, ret, pollfds[0].revents, errno, strerror(errno));
}
return ret;
}
static int QmiWwanGetClientID(UCHAR QMIType) {
PQCQMIMSG pResponse;
QmiThreadSendQMI(ComposeQCTLMsg(QMICTL_GET_CLIENT_ID_REQ, CtlGetClientIdReq, &QMIType), &pResponse);
if (pResponse) {
USHORT QMUXResult = cpu_to_le16(pResponse->CTLMsg.QMICTLMsgHdrRsp.QMUXResult); // QMI_RESULT_SUCCESS
USHORT QMUXError = cpu_to_le16(pResponse->CTLMsg.QMICTLMsgHdrRsp.QMUXError); // QMI_ERR_INVALID_ARG
//UCHAR QMIType = pResponse->CTLMsg.GetClientIdRsp.QMIType;
UCHAR ClientId = pResponse->CTLMsg.GetClientIdRsp.ClientId;
if (!QMUXResult && !QMUXError && (QMIType == pResponse->CTLMsg.GetClientIdRsp.QMIType)) {
switch (QMIType) {
case QMUX_TYPE_WDS: dbg_time("Get clientWDS = %d", ClientId); break;
case QMUX_TYPE_DMS: dbg_time("Get clientDMS = %d", ClientId); break;
case QMUX_TYPE_NAS: dbg_time("Get clientNAS = %d", ClientId); break;
case QMUX_TYPE_QOS: dbg_time("Get clientQOS = %d", ClientId); break;
case QMUX_TYPE_WMS: dbg_time("Get clientWMS = %d", ClientId); break;
case QMUX_TYPE_PDS: dbg_time("Get clientPDS = %d", ClientId); break;
case QMUX_TYPE_UIM: dbg_time("Get clientUIM = %d", ClientId); break;
case QMUX_TYPE_WDS_ADMIN: dbg_time("Get clientWDA = %d", ClientId);
break;
default: break;
}
return ClientId;
}
}
return 0;
}
static int QmiWwanReleaseClientID(QMI_SERVICE_TYPE QMIType, UCHAR ClientId) {
UCHAR argv[] = {QMIType, ClientId};
QmiThreadSendQMI(ComposeQCTLMsg(QMICTL_RELEASE_CLIENT_ID_REQ, CtlReleaseClientIdReq, argv), NULL);
return 0;
}
int QmiWwanInit(PROFILE_T *profile) {
unsigned i;
int ret;
PQCQMIMSG pResponse;
if (profile->qmapnet_adapter == NULL || profile->qmapnet_adapter == profile->usbnet_adapter)
{
for (i = 0; i < 10; i++) {
ret = QmiThreadSendQMITimeout(ComposeQCTLMsg(QMICTL_SYNC_REQ, NULL, NULL), NULL, 1 * 1000);
if (!ret)
break;
sleep(1);
}
if (ret)
return ret;
}
QmiThreadSendQMI(ComposeQCTLMsg(QMICTL_GET_VERSION_REQ, CtlGetVersionReq, NULL), &pResponse);
if (profile->qmapnet_adapter != NULL && profile->qmapnet_adapter == profile->usbnet_adapter) {
if (pResponse) {
if (pResponse->CTLMsg.QMICTLMsgHdrRsp.QMUXResult == 0 && pResponse->CTLMsg.QMICTLMsgHdrRsp.QMUXError == 0) {
uint8_t NumElements = 0;
for (NumElements = 0; NumElements < pResponse->CTLMsg.GetVersionRsp.NumElements; NumElements++) {
#if 0
dbg_time("QMUXType = %02x Version = %d.%d",
pResponse->CTLMsg.GetVersionRsp.TypeVersion[NumElements].QMUXType,
pResponse->CTLMsg.GetVersionRsp.TypeVersion[NumElements].MajorVersion,
pResponse->CTLMsg.GetVersionRsp.TypeVersion[NumElements].MinorVersion);
#endif
if (pResponse->CTLMsg.GetVersionRsp.TypeVersion[NumElements].QMUXType == QMUX_TYPE_WDS_ADMIN)
profile->qmap_version = (pResponse->CTLMsg.GetVersionRsp.TypeVersion[NumElements].MinorVersion > 16);
}
}
}
}
if (pResponse) free(pResponse);
qmiclientId[QMUX_TYPE_WDS] = QmiWwanGetClientID(QMUX_TYPE_WDS);
if (profile->IsDualIPSupported)
qmiclientId[QMUX_TYPE_WDS_IPV6] = QmiWwanGetClientID(QMUX_TYPE_WDS);
qmiclientId[QMUX_TYPE_DMS] = QmiWwanGetClientID(QMUX_TYPE_DMS);
qmiclientId[QMUX_TYPE_NAS] = QmiWwanGetClientID(QMUX_TYPE_NAS);
qmiclientId[QMUX_TYPE_UIM] = QmiWwanGetClientID(QMUX_TYPE_UIM);
if (profile->qmapnet_adapter == NULL || profile->qmapnet_adapter == profile->usbnet_adapter)
qmiclientId[QMUX_TYPE_WDS_ADMIN] = QmiWwanGetClientID(QMUX_TYPE_WDS_ADMIN);
return 0;
}
int QmiWwanDeInit(void) {
unsigned int i;
for (i = 0; i < sizeof(qmiclientId)/sizeof(qmiclientId[0]); i++)
{
if (qmiclientId[i] != 0)
{
QmiWwanReleaseClientID(i, qmiclientId[i]);
qmiclientId[i] = 0;
}
}
return 0;
}
#define QUECTEL_QMI_PROXY "quectel-qmi-proxy"
static int qmi_proxy_open(const char *name) {
int sockfd = -1;
int reuse_addr = 1;
struct sockaddr_un sockaddr;
socklen_t alen;
/*Create server socket*/
(sockfd = socket(AF_LOCAL, SOCK_STREAM, 0));
if (sockfd < 0)
return sockfd;
memset(&sockaddr, 0, sizeof(sockaddr));
sockaddr.sun_family = AF_LOCAL;
sockaddr.sun_path[0] = 0;
memcpy(sockaddr.sun_path + 1, name, strlen(name) );
alen = strlen(name) + offsetof(struct sockaddr_un, sun_path) + 1;
if(connect(sockfd, (struct sockaddr *)&sockaddr, alen) < 0) {
close(sockfd);
dbg_time("%s connect %s errno: %d (%s)\n", __func__, name, errno, strerror(errno));
return -1;
}
(setsockopt(sockfd, SOL_SOCKET, SO_REUSEADDR, &reuse_addr,sizeof(reuse_addr)));
dbg_time("connect to %s sockfd = %d\n", name, sockfd);
return sockfd;
}
static ssize_t qmi_proxy_read (int fd, void *buf, size_t size) {
ssize_t nreads;
PQCQMI_HDR pHdr = (PQCQMI_HDR)buf;
nreads = read(fd, pHdr, sizeof(QCQMI_HDR));
if (nreads == sizeof(QCQMI_HDR)) {
nreads += read(fd, pHdr+1, le16_to_cpu(pHdr->Length) + 1 - sizeof(QCQMI_HDR));
}
return nreads;
}
void * QmiWwanThread(void *pData) {
PROFILE_T *profile = (PROFILE_T *)pData;
const char *cdc_wdm = (const char *)profile->qmichannel;
if (profile->qmapnet_adapter == NULL || profile->qmapnet_adapter == profile->usbnet_adapter)
cdc_wdm_fd = open(cdc_wdm, O_RDWR | O_NONBLOCK | O_NOCTTY);
else
cdc_wdm_fd = qmi_proxy_open(QUECTEL_QMI_PROXY);
if (cdc_wdm_fd == -1) {
dbg_time("%s Failed to open %s, errno: %d (%s)", __func__, cdc_wdm, errno, strerror(errno));
qmidevice_send_event_to_main(RIL_INDICATE_DEVICE_DISCONNECTED);
pthread_exit(NULL);
return NULL;
}
fcntl(cdc_wdm_fd, F_SETFL, fcntl(cdc_wdm_fd,F_GETFL) | O_NONBLOCK);
fcntl(cdc_wdm_fd, F_SETFD, FD_CLOEXEC);
dbg_time("cdc_wdm_fd = %d", cdc_wdm_fd);
qmidevice_send_event_to_main(RIL_INDICATE_DEVICE_CONNECTED);
while (1) {
struct pollfd pollfds[] = {{qmidevice_control_fd[1], POLLIN, 0}, {cdc_wdm_fd, POLLIN, 0}};
int ne, ret, nevents = sizeof(pollfds)/sizeof(pollfds[0]);
do {
ret = poll(pollfds, nevents, -1);
} while ((ret < 0) && (errno == EINTR));
if (ret <= 0) {
dbg_time("%s poll=%d, errno: %d (%s)", __func__, ret, errno, strerror(errno));
break;
}
for (ne = 0; ne < nevents; ne++) {
int fd = pollfds[ne].fd;
short revents = pollfds[ne].revents;
//dbg_time("{%d, %x, %x}", pollfds[ne].fd, pollfds[ne].events, pollfds[ne].revents);
if (revents & (POLLERR | POLLHUP | POLLNVAL)) {
dbg_time("%s poll err/hup/inval", __func__);
dbg_time("poll fd = %d, events = 0x%04x", fd, revents);
if (fd == cdc_wdm_fd) {
} else {
}
if (revents & (POLLHUP | POLLNVAL)) //EC20 bug, Can get POLLERR
goto __QmiWwanThread_quit;
}
if ((revents & POLLIN) == 0)
continue;
if (fd == qmidevice_control_fd[1]) {
int triger_event;
if (read(fd, &triger_event, sizeof(triger_event)) == sizeof(triger_event)) {
//DBG("triger_event = 0x%x", triger_event);
switch (triger_event) {
case RIL_REQUEST_QUIT:
goto __QmiWwanThread_quit;
break;
case SIGTERM:
case SIGHUP:
case SIGINT:
QmiThreadRecvQMI(NULL);
break;
default:
break;
}
}
}
if (fd == cdc_wdm_fd) {
ssize_t nreads;
UCHAR QMIBuf[512];
PQCQMIMSG pResponse = (PQCQMIMSG)QMIBuf;
if (profile->qmapnet_adapter == NULL || profile->qmapnet_adapter == profile->usbnet_adapter)
nreads = read(fd, QMIBuf, sizeof(QMIBuf));
else
nreads = qmi_proxy_read(fd, QMIBuf, sizeof(QMIBuf));
//dbg_time("%s read=%d errno: %d (%s)", __func__, (int)nreads, errno, strerror(errno));
if (nreads <= 0) {
dbg_time("%s read=%d errno: %d (%s)", __func__, (int)nreads, errno, strerror(errno));
break;
}
if (nreads != (le16_to_cpu(pResponse->QMIHdr.Length) + 1)) {
dbg_time("%s nreads=%d, pQCQMI->QMIHdr.Length = %d", __func__, (int)nreads, le16_to_cpu(pResponse->QMIHdr.Length));
continue;
}
QmiThreadRecvQMI(pResponse);
}
}
}
__QmiWwanThread_quit:
if (cdc_wdm_fd != -1) { close(cdc_wdm_fd); cdc_wdm_fd = -1; }
qmidevice_send_event_to_main(RIL_INDICATE_DEVICE_DISCONNECTED);
QmiThreadRecvQMI(NULL); //main thread may pending on QmiThreadSendQMI()
dbg_time("%s exit", __func__);
pthread_exit(NULL);
return NULL;
}
#else
int QmiWwanSendQMI(PQCQMIMSG pRequest) {return -1;}
int QmiWwanInit(PROFILE_T *profile) {return -1;}
int QmiWwanDeInit(void) {return -1;}
void * QmiWwanThread(void *pData) {dbg_time("please set CONFIG_QMIWWAN"); return NULL;}
#endif

6
quectel-CM/README.md Normal file
View File

@ -0,0 +1,6 @@
# Quectel Connect Manager
For those who struggle to get the sources. Their support gave me the sources.
## Version 1.1.45 for Linux&Android
This is the version 1.1.45 of the **Connect Manager** from Quectel.
## Makefile
The Makefile was adapted to work with the Yocto/Poky build envrionnement (not much done but 'as is', it wasn't working).

63
quectel-CM/default.script Executable file
View File

@ -0,0 +1,63 @@
#!/bin/sh
# Busybox udhcpc dispatcher script. Copyright (C) 2009 by Axel Beckert.
#
# Based on the busybox example scripts and the old udhcp source
# package default.* scripts.
RESOLV_CONF="/etc/resolv.conf"
case $1 in
bound|renew)
[ -n "$broadcast" ] && BROADCAST="broadcast $broadcast"
[ -n "$subnet" ] && NETMASK="netmask $subnet"
/sbin/ifconfig $interface $ip $BROADCAST $NETMASK
if [ -n "$router" ]; then
echo "$0: Resetting default routes"
while /sbin/route del default gw 0.0.0.0 dev $interface; do :; done
metric=0
for i in $router; do
/sbin/route add default gw $i dev $interface metric $metric
metric=$(($metric + 1))
done
fi
# Update resolver configuration file
R=""
[ -n "$domain" ] && R="domain $domain
"
for i in $dns; do
echo "$0: Adding DNS $i"
R="${R}nameserver $i
"
done
if [ ! -x /sbin/resolvconf ]; then
echo -n "$R" | resolvconf -a "${interface}.udhcpc"
else
echo -n "$R" > "$RESOLV_CONF"
fi
;;
deconfig)
if [ -x /sbin/resolvconf ]; then
resolvconf -d "${interface}.udhcpc"
fi
/sbin/ifconfig $interface 0.0.0.0
;;
leasefail)
echo "$0: Lease failed: $message"
;;
nak)
echo "$0: Received a NAK: $message"
;;
*)
echo "$0: Unknown udhcpc command: $1";
exit 1;
;;
esac

90
quectel-CM/dhcpclient.c Executable file
View File

@ -0,0 +1,90 @@
#ifdef ANDROID
/*
* Copyright 2008, The Android Open Source Project
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
#include <string.h>
#include <errno.h>
#include <arpa/inet.h>
#include "QMIThread.h"
#ifdef USE_NDK
extern int (*ifc_init)(void);
extern void (*ifc_close)(void);
extern int (*do_dhcp)(const char *iname);
extern void (*get_dhcp_info)(uint32_t *ipaddr, uint32_t *gateway, uint32_t *prefixLength,
uint32_t *dns1, uint32_t *dns2, uint32_t *server,
uint32_t *lease);
extern int (*property_set)(const char *key, const char *value);
#else
#include <cutils/properties.h>
#include <netutils/ifc.h>
extern int do_dhcp(const char *iname);
extern void get_dhcp_info(uint32_t *ipaddr, uint32_t *gateway, uint32_t *prefixLength,
uint32_t *dns1, uint32_t *dns2, uint32_t *server,
uint32_t *lease);
#endif
static const char *ipaddr_to_string(in_addr_t addr)
{
struct in_addr in_addr;
in_addr.s_addr = addr;
return inet_ntoa(in_addr);
}
void do_dhcp_request(PROFILE_T *profile) {
#ifdef USE_NDK
if (!ifc_init ||!ifc_close ||!do_dhcp || !get_dhcp_info || !property_set) {
return;
}
#endif
char *ifname = profile->usbnet_adapter;
uint32_t ipaddr, gateway, prefixLength, dns1, dns2, server, lease;
char propKey[128];
#if 0
if (profile->rawIP && ((profile->IPType==0x04 && profile->ipv4.Address)))
{
snprintf(propKey, sizeof(propKey), "net.%s.dns1", ifname);
property_set(propKey, profile->ipv4.DnsPrimary ? ipaddr_to_string(ql_swap32(profile->ipv4.DnsPrimary)) : "8.8.8.8");
snprintf(propKey, sizeof(propKey), "net.%s.dns2", ifname);
property_set(propKey, profile->ipv4.DnsSecondary ? ipaddr_to_string(ql_swap32(profile->ipv4.DnsSecondary)) : "8.8.8.8");
snprintf(propKey, sizeof(propKey), "net.%s.gw", ifname);
property_set(propKey, profile->ipv4.Gateway ? ipaddr_to_string(ql_swap32(profile->ipv4.Gateway)) : "0.0.0.0");
return;
}
#endif
if(ifc_init()) {
dbg_time("failed to ifc_init(%s): %s\n", ifname, strerror(errno));
}
if (do_dhcp(ifname) < 0) {
dbg_time("failed to do_dhcp(%s): %s\n", ifname, strerror(errno));
}
ifc_close();
get_dhcp_info(&ipaddr, &gateway, &prefixLength, &dns1, &dns2, &server, &lease);
snprintf(propKey, sizeof(propKey), "net.%s.gw", ifname);
property_set(propKey, gateway ? ipaddr_to_string(gateway) : "0.0.0.0");
}
#endif

1080
quectel-CM/main.c Executable file

File diff suppressed because it is too large Load Diff

1131
quectel-CM/quectel-qmi-proxy.c Executable file

File diff suppressed because it is too large Load Diff

312
quectel-CM/udhcpc.c Executable file
View File

@ -0,0 +1,312 @@
#include <sys/socket.h>
#include <sys/select.h>
#include <sys/types.h>
#include <net/if.h>
#include "QMIThread.h"
static int ql_system(const char *shell_cmd) {
int ret = 0;
dbg_time("%s", shell_cmd);
ret = system(shell_cmd);
if (ret) {
//dbg_time("Fail to system(\"%s\") = %d, errno: %d (%s)", shell_cmd, ret, errno, strerror(errno));
}
return ret;
}
static void ql_set_mtu(const char *ifname, int ifru_mtu) {
int inet_sock;
struct ifreq ifr;
inet_sock = socket(AF_INET, SOCK_DGRAM, 0);
if (inet_sock > 0) {
strcpy(ifr.ifr_name, ifname);
if (!ioctl(inet_sock, SIOCGIFMTU, &ifr)) {
if (ifr.ifr_ifru.ifru_mtu != ifru_mtu) {
dbg_time("change mtu %d -> %d", ifr.ifr_ifru.ifru_mtu , ifru_mtu);
ifr.ifr_ifru.ifru_mtu = ifru_mtu;
ioctl(inet_sock, SIOCSIFMTU, &ifr);
}
}
close(inet_sock);
}
}
#ifdef ANDROID
static void android_property_set(char *ifname, char *type, uint32_t ipaddr) {
char shell_cmd[128];
unsigned char *r = (unsigned char *)&ipaddr;
snprintf(shell_cmd, sizeof(shell_cmd), "/system/bin/setprop net.%s.%s %d.%d.%d.%d", ifname, type, r[3], r[2], r[1], r[0]);
ql_system(shell_cmd);
}
#endif
static void* udhcpc_thread_function(void* arg) {
FILE * udhcpc_fp;
char *udhcpc_cmd = (char *)arg;
if (udhcpc_cmd == NULL)
return NULL;
dbg_time("%s", udhcpc_cmd);
udhcpc_fp = popen(udhcpc_cmd, "r");
free(udhcpc_cmd);
if (udhcpc_fp) {
char buf[0xff];
buf[sizeof(buf)-1] = '\0';
while((fgets(buf, sizeof(buf)-1, udhcpc_fp)) != NULL) {
if ((strlen(buf) > 1) && (buf[strlen(buf) - 1] == '\n'))
buf[strlen(buf) - 1] = '\0';
dbg_time("%s", buf);
}
pclose(udhcpc_fp);
}
return NULL;
}
#define USE_DHCLIENT
#ifdef USE_DHCLIENT
static int dhclient_alive = 0;
#endif
static int dibbler_client_alive = 0;
void udhcpc_start(PROFILE_T *profile) {
char *ifname = profile->usbnet_adapter;
char shell_cmd[128];
if (profile->qmapnet_adapter) {
ifname = profile->qmapnet_adapter;
}
if (profile->rawIP && profile->ipv4.Address && profile->ipv4.Mtu) {
ql_set_mtu(ifname, (profile->ipv4.Mtu));
}
#ifdef ANDROID
if(!access("/system/bin/netcfg", F_OK)) {
snprintf(shell_cmd, sizeof(shell_cmd), "/system/bin/netcfg %s up", ifname);
ql_system(shell_cmd);
snprintf(shell_cmd, sizeof(shell_cmd), "/system/bin/netcfg %s dhcp", ifname);
ql_system(shell_cmd);
} else {
// snprintf(shell_cmd, sizeof(shell_cmd), "/system/bin/dhcptool %s", ifname);
unsigned char *r = (unsigned char *)&profile->ipv4.Address;
unsigned char *m = (unsigned char *)&profile->ipv4.SubnetMask;
snprintf(shell_cmd, sizeof(shell_cmd), "/system/bin/ifconfig %s %d.%d.%d.%d netmask %d.%d.%d.%d",
ifname, r[3],r[2], r[1], r[0], m[3],m[2], m[1], m[0]);
ql_system(shell_cmd);
android_property_set(ifname, "dns1", profile->ipv4.DnsPrimary);
android_property_set(ifname, "dns2", profile->ipv4.DnsSecondary);
}
android_property_set(ifname, "gw", profile->ipv4.Gateway);
return;
#endif
if (strcmp(ifname, profile->usbnet_adapter)) {
snprintf(shell_cmd, sizeof(shell_cmd) - 1, "ifconfig %s up", profile->usbnet_adapter);
ql_system(shell_cmd);
}
snprintf(shell_cmd, sizeof(shell_cmd) - 1, "ifconfig %s up", ifname);
ql_system(shell_cmd);
#if 1 //for bridge mode, only one public IP, so donot run udhcpc to obtain
{
char BRIDGE_MODE_FILE[128];
char BRIDGE_IPV4_FILE[128];
if (strncmp(qmichannel, "/dev/qcqmi", strlen("/dev/qcqmi"))) {
strcpy(BRIDGE_MODE_FILE , "/sys/module/qmi_wwan/parameters/bridge_mode");
strcpy(BRIDGE_IPV4_FILE, "/sys/module/qmi_wwan/parameters/bridge_ipv4");
} else {
snprintf(BRIDGE_MODE_FILE, sizeof(BRIDGE_MODE_FILE), "/sys/class/net/%s/bridge_mode", ifname);
snprintf(BRIDGE_IPV4_FILE, sizeof(BRIDGE_IPV4_FILE), "/sys/class/net/%s/bridge_ipv4", ifname);
}
if (profile->ipv4.Address && !access(BRIDGE_MODE_FILE, R_OK)) {
int bridge_fd = open(BRIDGE_MODE_FILE, O_RDONLY);
char bridge_mode[2] = {0, 0};
if (bridge_fd > 0) {
read(bridge_fd, &bridge_mode, sizeof(bridge_mode));
close(bridge_fd);
if(bridge_mode[0] != '0') {
snprintf(shell_cmd, sizeof(shell_cmd), "echo 0x%08x > %s", profile->ipv4.Address, BRIDGE_IPV4_FILE);
ql_system(shell_cmd);
return;
}
}
}
}
#endif
//because must use udhcpc to obtain IP when working on ETH mode,
//so it is better also use udhcpc to obtain IP when working on IP mode.
//use the same policy for all modules
#if 0
if (profile->rawIP != 0) //mdm9x07/ec25,ec20 R2.0
{
if (profile->ipv4.Address) {
unsigned char *ip = (unsigned char *)&profile->ipv4.Address;
unsigned char *gw = (unsigned char *)&profile->ipv4.Gateway;
unsigned char *netmask = (unsigned char *)&profile->ipv4.SubnetMask;
unsigned char *dns1 = (unsigned char *)&profile->ipv4.DnsPrimary;
unsigned char *dns2 = (unsigned char *)&profile->ipv4.DnsSecondary;
snprintf(shell_cmd, sizeof(shell_cmd), "ifconfig %s %d.%d.%d.%d netmask %d.%d.%d.%d",ifname,
ip[3], ip[2], ip[1], ip[0], netmask[3], netmask[2], netmask[1], netmask[0]);
ql_system(shell_cmd);
//Resetting default routes
snprintf(shell_cmd, sizeof(shell_cmd), "route del default gw 0.0.0.0 dev %s", ifname);
while(!system(shell_cmd));
snprintf(shell_cmd, sizeof(shell_cmd), "route add default gw %d.%d.%d.%d dev %s metric 0", gw[3], gw[2], gw[1], gw[0], ifname);
ql_system(shell_cmd);
//Adding DNS
if (profile->ipv4.DnsSecondary == 0)
profile->ipv4.DnsSecondary = profile->ipv4.DnsPrimary;
if (dns1[0]) {
dbg_time("Adding DNS %d.%d.%d.%d %d.%d.%d.%d", dns1[3], dns1[2], dns1[1], dns1[0], dns2[3], dns2[2], dns2[1], dns2[0]);
snprintf(shell_cmd, sizeof(shell_cmd), "echo -n \"nameserver %d.%d.%d.%d\nnameserver %d.%d.%d.%d\n\" > /etc/resolv.conf",
dns1[3], dns1[2], dns1[1], dns1[0], dns2[3], dns2[2], dns2[1], dns2[0]);
system(shell_cmd);
}
}
if (profile->ipv6.Address[0] && profile->ipv6.PrefixLengthIPAddr) {
unsigned char *ip = (unsigned char *)&profile->ipv4.Address;
#if 1
snprintf(shell_cmd, sizeof(shell_cmd), "ifconfig %s inet6 add %02x%02x:%02x%02x:%02x%02x:%02x%02x:%02x%02x:%02x%02x/%d",
ifname, ip[0], ip[1], ip[2], ip[3], ip[4], ip[5], ip[6], ip[7], ip[8], ip[9], ip[10], ip[11], ip[12], ip[13], ip[14], ip[15], profile->ipv6.PrefixLengthIPAddr);
#else
snprintf(shell_cmd, sizeof(shell_cmd), "ip -6 addr add %02x%02x:%02x%02x:%02x%02x:%02x%02x:%02x%02x:%02x%02x/%d dev %s",
ip[0], ip[1], ip[2], ip[3], ip[4], ip[5], ip[6], ip[7], ip[8], ip[9], ip[10], ip[11], ip[12], ip[13], ip[14], ip[15], profile->ipv6.PrefixLengthIPAddr, ifname);
#endif
ql_system(shell_cmd);
snprintf(shell_cmd, sizeof(shell_cmd), "route -A inet6 add default dev %s", ifname);
ql_system(shell_cmd);
}
return;
}
#endif
{
char udhcpc_cmd[128];
pthread_attr_t udhcpc_thread_attr;
pthread_t udhcpc_thread_id;
pthread_attr_init(&udhcpc_thread_attr);
pthread_attr_setdetachstate(&udhcpc_thread_attr, PTHREAD_CREATE_DETACHED);
if (profile->ipv4.Address) {
#ifdef USE_DHCLIENT
snprintf(udhcpc_cmd, sizeof(udhcpc_cmd), "dhclient -4 -d -q --no-pid %s", ifname);
dhclient_alive++;
#else
if (access("/usr/share/udhcpc/default.script", X_OK)) {
dbg_time("Fail to access /usr/share/udhcpc/default.script, errno: %d (%s)", errno, strerror(errno));
}
//-f,--foreground Run in foreground
//-b,--background Background if lease is not obtained
//-n,--now Exit if lease is not obtained
//-q,--quit Exit after obtaining lease
//-t,--retries N Send up to N discover packets (default 3)
snprintf(udhcpc_cmd, sizeof(udhcpc_cmd), "busybox udhcpc -f -n -q -t 5 -i %s", ifname);
#endif
#if 1 //for OpenWrt
if (!access("/lib/netifd/dhcp.script", X_OK) && !access("/sbin/ifup", X_OK) && !access("/sbin/ifstatus", X_OK)) {
dbg_time("you are use OpenWrt?");
dbg_time("should not calling udhcpc manually?");
dbg_time("should modify /etc/config/network as below?");
dbg_time("config interface wan");
dbg_time("\toption ifname %s", ifname);
dbg_time("\toption proto dhcp");
dbg_time("should use \"/sbin/ifstaus wan\" to check %s 's status?", ifname);
}
#endif
pthread_create(&udhcpc_thread_id, &udhcpc_thread_attr, udhcpc_thread_function, (void*)strdup(udhcpc_cmd));
sleep(1);
}
if (profile->ipv6.Address[0] && profile->ipv6.PrefixLengthIPAddr) {
#ifdef USE_DHCLIENT
snprintf(udhcpc_cmd, sizeof(udhcpc_cmd), "dhclient -6 -d -q --no-pid %s", ifname);
dhclient_alive++;
#else
/*
DHCPv6: Dibbler - a portable DHCPv6
1. download from http://klub.com.pl/dhcpv6/
2. cross-compile
2.1 ./configure --host=arm-linux-gnueabihf
2.2 copy dibbler-client to your board
3. mkdir -p /var/log/dibbler/ /var/lib/ on your board
4. create /etc/dibbler/client.conf on your board, the content is
log-mode short
log-level 7
iface wwan0 {
ia
option dns-server
}
5. run "dibbler-client start" to get ipV6 address
6. run "route -A inet6 add default dev wwan0" to add default route
*/
snprintf(shell_cmd, sizeof(shell_cmd), "route -A inet6 add default %s", ifname);
ql_system(shell_cmd);
snprintf(udhcpc_cmd, sizeof(udhcpc_cmd), "dibbler-client run");
dibbler_client_alive++;
#endif
pthread_create(&udhcpc_thread_id, &udhcpc_thread_attr, udhcpc_thread_function, (void*)strdup(udhcpc_cmd));
}
}
}
void udhcpc_stop(PROFILE_T *profile) {
char *ifname = profile->usbnet_adapter;
char shell_cmd[128];
char reset_ip[128];
if (profile->qmapnet_adapter) {
ifname = profile->qmapnet_adapter;
}
#ifdef ANDROID
if(!access("/system/bin/netcfg", F_OK)) {
snprintf(shell_cmd, sizeof(shell_cmd) - 1, "/system/bin/netcfg %s down", ifname);
} else {
snprintf(shell_cmd, sizeof(shell_cmd) - 1, "ifconfig %s down", ifname); //for android 6.0 and above
}
#else
#ifdef USE_DHCLIENT
if (dhclient_alive) {
system("killall dhclient");
dhclient_alive = 0;
}
#endif
if (dibbler_client_alive) {
system("killall dibbler-client");
dibbler_client_alive = 0;
}
snprintf(shell_cmd, sizeof(shell_cmd) - 1, "ifconfig %s down", ifname);
#endif
ql_system(shell_cmd);
snprintf(reset_ip, sizeof(reset_ip) - 1, "ifconfig %s 0.0.0.0", ifname);
ql_system(reset_ip);
}

158
quectel-CM/util.c Executable file
View File

@ -0,0 +1,158 @@
#include "QMIThread.h"
#include <sys/time.h>
#if defined(__STDC__)
#include <stdarg.h>
#define __V(x) x
#else
#include <varargs.h>
#define __V(x) (va_alist) va_dcl
#define const
#define volatile
#endif
#ifdef ANDROID
#define LOG_TAG "NDIS"
#include "../ql-log.h"
#else
#include <syslog.h>
#endif
#ifndef ANDROID //defined in atchannel.c
static void setTimespecRelative(struct timespec *p_ts, long long msec)
{
struct timeval tv;
gettimeofday(&tv, (struct timezone *) NULL);
/* what's really funny about this is that I know
pthread_cond_timedwait just turns around and makes this
a relative time again */
p_ts->tv_sec = tv.tv_sec + (msec / 1000);
p_ts->tv_nsec = (tv.tv_usec + (msec % 1000) * 1000L ) * 1000L;
}
int pthread_cond_timeout_np(pthread_cond_t *cond,
pthread_mutex_t * mutex,
unsigned msecs) {
if (msecs != 0) {
struct timespec ts;
setTimespecRelative(&ts, msecs);
return pthread_cond_timedwait(cond, mutex, &ts);
} else {
return pthread_cond_wait(cond, mutex);
}
}
#endif
static const char * get_time(void) {
static char time_buf[50];
struct timeval tv;
time_t time;
suseconds_t millitm;
struct tm *ti;
gettimeofday (&tv, NULL);
time= tv.tv_sec;
millitm = (tv.tv_usec + 500) / 1000;
if (millitm == 1000) {
++time;
millitm = 0;
}
ti = localtime(&time);
sprintf(time_buf, "[%02d-%02d_%02d:%02d:%02d:%03d]", ti->tm_mon+1, ti->tm_mday, ti->tm_hour, ti->tm_min, ti->tm_sec, (int)millitm);
return time_buf;
}
FILE *logfilefp = NULL;
static pthread_mutex_t printfMutex = PTHREAD_MUTEX_INITIALIZER;
static char line[1024];
void dbg_time (const char *fmt, ...) {
va_list args;
va_start(args, fmt);
pthread_mutex_lock(&printfMutex);
#ifdef ANDROID
vsnprintf(line, sizeof(line), fmt, args);
RLOGD("%s", line);
#else
#ifdef LINUX_RIL_SHLIB
line[0] = '\0';
#else
snprintf(line, sizeof(line), "%s ", get_time());
#endif
vsnprintf(line + strlen(line), sizeof(line) - strlen(line), fmt, args);
fprintf(stdout, "%s\n", line);
#endif
if (logfilefp) {
fprintf(logfilefp, "%s\n", line);
}
pthread_mutex_unlock(&printfMutex);
}
const int i = 1;
#define is_bigendian() ( (*(char*)&i) == 0 )
USHORT le16_to_cpu(USHORT v16) {
USHORT tmp = v16;
if (is_bigendian()) {
unsigned char *s = (unsigned char *)(&v16);
unsigned char *d = (unsigned char *)(&tmp);
d[0] = s[1];
d[1] = s[0];
}
return tmp;
}
UINT le32_to_cpu (UINT v32) {
UINT tmp = v32;
if (is_bigendian()) {
unsigned char *s = (unsigned char *)(&v32);
unsigned char *d = (unsigned char *)(&tmp);
d[0] = s[3];
d[1] = s[2];
d[2] = s[1];
d[3] = s[0];
}
return tmp;
}
UINT ql_swap32(UINT v32) {
UINT tmp = v32;
{
unsigned char *s = (unsigned char *)(&v32);
unsigned char *d = (unsigned char *)(&tmp);
d[0] = s[3];
d[1] = s[2];
d[2] = s[1];
d[3] = s[0];
}
return tmp;
}
USHORT cpu_to_le16(USHORT v16) {
USHORT tmp = v16;
if (is_bigendian()) {
unsigned char *s = (unsigned char *)(&v16);
unsigned char *d = (unsigned char *)(&tmp);
d[0] = s[1];
d[1] = s[0];
}
return tmp;
}
UINT cpu_to_le32 (UINT v32) {
UINT tmp = v32;
if (is_bigendian()) {
unsigned char *s = (unsigned char *)(&v32);
unsigned char *d = (unsigned char *)(&tmp);
d[0] = s[3];
d[1] = s[2];
d[2] = s[1];
d[3] = s[0];
}
return tmp;
}

54
quectel-CM/util.h Executable file
View File

@ -0,0 +1,54 @@
/*
* Copyright (C) 2010 The Android Open Source Project
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef _UTILS_H_
#define _UTILS_H_
#include <stddef.h>
struct listnode
{
struct listnode *next;
struct listnode *prev;
};
#define node_to_item(node, container, member) \
(container *) (((char*) (node)) - offsetof(container, member))
#define list_declare(name) \
struct listnode name = { \
.next = &name, \
.prev = &name, \
}
#define list_for_each(node, list) \
for (node = (list)->next; node != (list); node = node->next)
#define list_for_each_reverse(node, list) \
for (node = (list)->prev; node != (list); node = node->prev)
void list_init(struct listnode *list);
void list_add_tail(struct listnode *list, struct listnode *item);
void list_add_head(struct listnode *head, struct listnode *item);
void list_remove(struct listnode *item);
#define list_empty(list) ((list) == (list)->next)
#define list_head(list) ((list)->next)
#define list_tail(list) ((list)->prev)
int epoll_register(int epoll_fd, int fd, unsigned int events);
int epoll_deregister(int epoll_fd, int fd);
#endif