1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-30 15:52:12 +01:00

OP-958: uncrustify sources

This commit is contained in:
Oleg Semyonov 2013-05-25 01:23:02 +03:00
parent f6d2f152b9
commit d1dd944bc3
13 changed files with 596 additions and 637 deletions

View File

@ -41,11 +41,10 @@ class RawHIDReadThread;
class RawHIDWriteThread;
/**
* The actual IO device that will be used to communicate
* with the board.
*/
class OPHID_EXPORT RawHID : public QIODevice
{
* The actual IO device that will be used to communicate
* with the board.
*/
class OPHID_EXPORT RawHID : public QIODevice {
Q_OBJECT
friend class RawHIDReadThread;
@ -72,10 +71,10 @@ protected:
virtual qint64 bytesAvailable() const;
virtual qint64 bytesToWrite() const;
//! Callback from the read thread to open the device
// Callback from the read thread to open the device
bool openDevice();
//! Callback from teh read thread to close the device
// Callback from teh read thread to close the device
bool closeDevice();
QString serialNumber;
@ -92,4 +91,3 @@ protected:
};
#endif // OPHID_H

View File

@ -28,39 +28,37 @@
#ifndef OPHID_CONST_H
#define OPHID_CONST_H
#define printf qDebug
#define printf qDebug
#define OPHID_DEBUG_ON 1
#ifdef OPHID_DEBUG_ON
#define OPHID_DEBUG(fmt, args...) qDebug("[DEBUG] "fmt, ## args)
#define OPHID_TRACE(fmt, args...) qDebug("[TRACE] %s:%s:%d: "fmt, __FILE__, __func__, __LINE__, ## args)
#define OPHID_ERROR(fmt, args...) qDebug("[ERROR] %s:%s:%d: "fmt, __FILE__, __func__, __LINE__, ## args)
#define OPHID_WARNING(fmt, args...) qDebug("[WARNING] "fmt, ## args)
#define OPHID_DEBUG(fmt, args ...) qDebug("[DEBUG] "fmt,##args)
#define OPHID_TRACE(fmt, args ...) qDebug("[TRACE] %s:%s:%d: "fmt, __FILE__, __func__, __LINE__,##args)
#define OPHID_ERROR(fmt, args ...) qDebug("[ERROR] %s:%s:%d: "fmt, __FILE__, __func__, __LINE__,##args)
#define OPHID_WARNING(fmt, args ...) qDebug("[WARNING] "fmt,##args)
#else
#define OPHID_DEBUG(fmt, args...)
#define OPHID_TRACE(fmt, args...)
#define OPHID_ERROR(fmt, args...)
#define OPHID_WARNING(fmt, args...)
#define OPHID_DEBUG(fmt, args ...)
#define OPHID_TRACE(fmt, args ...)
#define OPHID_ERROR(fmt, args ...)
#define OPHID_WARNING(fmt, args ...)
#endif
// USB
#define USB_MAX_DEVICES 10
#define USB_VID 0x20A0
#define USB_PID 0x4117
#define USB_USAGE_PAGE 0xFF9C
#define USB_USAGE 0x0001
#define USB_DEV_SERIAL_LEN 24
#define USB_PID_ANY -1
#define USB_MAX_STRING_SIZE 255
#define USB_MAX_DEVICES 10
#define USB_VID 0x20A0
#define USB_PID 0x4117
#define USB_USAGE_PAGE 0xFF9C
#define USB_USAGE 0x0001
#define USB_DEV_SERIAL_LEN 24
#define USB_PID_ANY -1
#define USB_MAX_STRING_SIZE 255
// ERROR
#define OPHID_NO_ERROR 0
#define OPHID_ERROR_RET -1
#define OPHID_ERROR_POINTER -2
#define OPHID_ERROR_PARAMETER -3
#define OPHID_ERROR_HANDLE -4
#define OPHID_ERROR_INIT -5
#define OPHID_NO_ERROR 0
#define OPHID_ERROR_RET -1
#define OPHID_ERROR_POINTER -2
#define OPHID_ERROR_PARAMETER -3
#define OPHID_ERROR_HANDLE -4
#define OPHID_ERROR_INIT -5
#endif // OPHID_CONST_H

View File

@ -10,18 +10,18 @@
* @brief Impliments a HID USB connection to the flight hardware as a QIODevice
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
@ -37,4 +37,3 @@
#endif
#endif // OPHID_GLOBAL_H

View File

@ -41,10 +41,8 @@
#include "opHID_global.h"
class OPHID_EXPORT opHID_hidapi: public QObject
{
Q_OBJECT
class OPHID_EXPORT opHID_hidapi : public QObject {
Q_OBJECT
public:
@ -64,7 +62,7 @@ public:
private:
int enumerate(struct hid_device_info **current_device_pptr, int *devices_found);
int enumerate(struct hid_device_info * *current_device_pptr, int *devices_found);
hid_device *handle;
@ -78,4 +76,4 @@ signals:
void deviceUnplugged(int);
};
#endif
#endif // ifndef OPHID_HIDAPI_H

View File

@ -10,18 +10,18 @@
* @brief Impliments a HID USB connection to the flight hardware as a QIODevice
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
@ -42,12 +42,11 @@ class RawHIDConnection;
/**
* Define a connection via the IConnection interface
* Plugin will add a instance of this class to the pool,
* so the connection manager can use it.
*/
class OPHID_EXPORT RawHIDConnection: public Core::IConnection
{
* Define a connection via the IConnection interface
* Plugin will add a instance of this class to the pool,
* so the connection manager can use it.
*/
class OPHID_EXPORT RawHIDConnection : public Core::IConnection {
Q_OBJECT
public:
@ -63,7 +62,10 @@ public:
virtual void suspendPolling();
virtual void resumePolling();
bool deviceOpened() { return (RawHidHandle != NULL); } // Pip
bool deviceOpened()
{
return RawHidHandle != NULL;
} // Pip
protected slots:
void onDeviceConnected();
@ -75,13 +77,12 @@ private:
protected:
QMutex m_enumMutex;
USBMonitor* m_usbMonitor;
USBMonitor *m_usbMonitor;
bool m_deviceOpened;
};
class OPHID_EXPORT RawHIDPlugin
: public ExtensionSystem::IPlugin
{
: public ExtensionSystem::IPlugin {
Q_OBJECT
public:
@ -93,9 +94,7 @@ public:
private:
RawHIDConnection *hidConnection;
USBMonitor* m_usbMonitor;
USBMonitor *m_usbMonitor;
};
#endif // OPHID_PLUGIN_H

View File

@ -34,28 +34,28 @@
#include <QMutex>
// Arch dependent
#if defined( Q_OS_MAC)
#if defined(Q_OS_MAC)
#include <IOKit/IOKitLib.h>
#include <IOKit/hid/IOHIDLib.h>
#elif defined(Q_OS_UNIX)
#include <libudev.h>
#include <QSocketNotifier>
#elif defined (Q_OS_WIN32)
#elif defined(Q_OS_WIN32)
#ifndef _WIN32_WINNT
#define _WIN32_WINNT 0x0500
#define _WIN32_WINNT 0x0500
#endif
#ifndef _WIN32_WINDOWS
#define _WIN32_WINDOWS 0x0500
#endif
#ifndef WINVER
#define WINVER 0x0500
#define WINVER 0x0500
#endif
#include <windows.h>
#include <dbt.h>
#include <setupapi.h>
#include <ddk/hidsdi.h>
#include <ddk/hidclass.h>
#endif
#endif // if defined(Q_OS_MAC)
#ifdef Q_OS_WIN
@ -63,60 +63,59 @@
#include <QWidget>
class USBMonitor;
class USBRegistrationWidget : public QWidget
{
class USBRegistrationWidget : public QWidget {
Q_OBJECT
public:
USBRegistrationWidget( USBMonitor* qese ) {
USBRegistrationWidget(USBMonitor *qese)
{
this->qese = qese;
}
~USBRegistrationWidget( ) {}
~USBRegistrationWidget() {}
protected:
USBMonitor* qese;
bool winEvent( MSG* message, long* result );
USBMonitor *qese;
bool winEvent(MSG *message, long *result);
};
#endif
#endif
struct USBPortInfo {
//QString friendName; ///< Friendly name.
//QString physName;
//QString enumName; ///< It seems its the only one with meaning
// QString friendName; ///< Friendly name.
// QString physName;
// QString enumName; ///< It seems its the only one with meaning
QString serialNumber; // As a string as it can be anything, really...
QString manufacturer;
QString product;
#if defined(Q_OS_WIN32)
QString devicePath; //only has meaning on windows
QString devicePath; // only has meaning on windows
#elif defined(Q_OS_MAC)
IOHIDDeviceRef dev_handle;
#endif
int UsagePage;
int Usage;
int vendorID; ///< Vendor ID.
int productID; ///< Product ID
int vendorID; ///< Vendor ID.
int productID; ///< Product ID
int bcdDevice;
};
/**
* A monitoring thread which will wait for device events.
*/
* A monitoring thread which will wait for device events.
*/
class OPHID_EXPORT USBMonitor : public QThread
{
class OPHID_EXPORT USBMonitor : public QThread {
Q_OBJECT
public:
enum RunState {
Bootloader = 0x01,
Running = 0x02
Running = 0x02
};
enum USBConstants {
idVendor_OpenPilot = 0x20a0,
idProduct_OpenPilot = 0x415a,
idVendor_OpenPilot = 0x20a0,
idProduct_OpenPilot = 0x415a,
idProduct_CopterControl = 0x415b,
idProduct_PipXtreme = 0x415c
idProduct_PipXtreme = 0x415c
};
static USBMonitor *instance();
@ -125,54 +124,54 @@ public:
~USBMonitor();
QList<USBPortInfo> availableDevices();
QList<USBPortInfo> availableDevices(int vid, int pid, int boardModel, int runState);
#if defined (Q_OS_WIN32)
LRESULT onDeviceChangeWin( WPARAM wParam, LPARAM lParam );
#if defined(Q_OS_WIN32)
LRESULT onDeviceChangeWin(WPARAM wParam, LPARAM lParam);
#endif
signals:
/*!
A new device has been connected to the system.
A new device has been connected to the system.
setUpNotifications() must be called first to enable event-driven device notifications.
Currently only implemented on Windows and OS X.
\param info The device that has been discovered.
*/
void deviceDiscovered( const USBPortInfo & info );
setUpNotifications() must be called first to enable event-driven device notifications.
Currently only implemented on Windows and OS X.
\param info The device that has been discovered.
*/
void deviceDiscovered(const USBPortInfo & info);
#ifdef __APPLE__
void deviceDiscovered();
void deviceDiscovered();
#endif // __APPLE__
/*!
A device has been disconnected from the system.
/*!
A device has been disconnected from the system.
setUpNotifications() must be called first to enable event-driven device notifications.
Currently only implemented on Windows and OS X.
\param info The device that was disconnected.
*/
void deviceRemoved( const USBPortInfo & info );
setUpNotifications() must be called first to enable event-driven device notifications.
Currently only implemented on Windows and OS X.
\param info The device that was disconnected.
*/
void deviceRemoved(const USBPortInfo & info);
#ifdef __APPLE__
void deviceRemoved();
void deviceRemoved();
#endif // __APPLE__
private slots:
/**
Callback available for whenever the system that is put in place gets
an event
Callback available for whenever the system that is put in place gets
an event
*/
void deviceEventReceived();
private:
//! Mutex for modifying the list of available devices
QMutex * listMutex;
// ! Mutex for modifying the list of available devices
QMutex *listMutex;
//! List of known devices maintained by callbacks
// ! List of known devices maintained by callbacks
QList<USBPortInfo> knowndevices;
Q_DISABLE_COPY(USBMonitor)
static USBMonitor *m_instance;
static USBMonitor * m_instance;
// Depending on the OS, we'll need different things:
#if defined( Q_OS_MAC)
#if defined(Q_OS_MAC)
static void attach_callback(void *context, IOReturn r, void *hid_mgr, IOHIDDeviceRef dev);
static void detach_callback(void *context, IOReturn r, void *hid_mgr, IOHIDDeviceRef dev);
void addDevice(USBPortInfo info);
@ -183,10 +182,10 @@ private:
struct udev_monitor *monitor;
QSocketNotifier *monitorNotifier;
USBPortInfo makePortInfo(struct udev_device *dev);
#elif defined (Q_OS_WIN32)
#elif defined(Q_OS_WIN32)
GUID guid_hid;
void setUpNotifications();
/*!
/*!
* Get specific property from registry.
* \param devInfo pointer to the device information set that contains the interface
* and its underlying device. Returned by SetupDiGetClassDevs() function.
@ -196,21 +195,19 @@ private:
* \return property string.
*/
static QString getDeviceProperty(HDEVINFO devInfo, PSP_DEVINFO_DATA devData, DWORD property);
static int infoFromHandle(const GUID & guid,USBPortInfo & info,HDEVINFO & devInfo,DWORD & index);
static void enumerateDevicesWin( const GUID & guidDev, QList<USBPortInfo>* infoList );
static int infoFromHandle(const GUID & guid, USBPortInfo & info, HDEVINFO & devInfo, DWORD & index);
static void enumerateDevicesWin(const GUID & guidDev, QList<USBPortInfo> *infoList);
bool matchAndDispatchChangedDevice(const QString & deviceID, const GUID & guid, WPARAM wParam);
#ifdef QT_GUI_LIB
USBRegistrationWidget* notificationWidget;
#endif
USBRegistrationWidget *notificationWidget;
#endif
#endif // if defined(Q_OS_MAC)
#ifdef __APPLE__
protected:
bool m_terminate;
bool m_terminate;
void run();
void run();
#endif // __APPLE__
};
#endif // OPHID_USBMON_H

View File

@ -31,8 +31,7 @@
#include <QObject>
#include "opHID_usbmon.h"
class OPHID_EXPORT USBSignalFilter : public QObject
{
class OPHID_EXPORT USBSignalFilter : public QObject {
Q_OBJECT
private:
@ -52,4 +51,3 @@ public:
};
#endif // OPHID_USBSIGNAL_H

View File

@ -36,22 +36,20 @@
class IConnection;
//timeout value used when we want to return directly without waiting
static const int READ_TIMEOUT = 200;
static const int READ_SIZE = 64;
// timeout value used when we want to return directly without waiting
static const int READ_TIMEOUT = 200;
static const int READ_SIZE = 64;
static const int WRITE_TIMEOUT = 1000;
static const int WRITE_SIZE = 64;
static const int WRITE_SIZE = 64;
// *********************************************************************************
/**
* Thread to desynchronize reading from the device
*/
class RawHIDReadThread : public QThread
{
* Thread to desynchronize reading from the device
*/
class RawHIDReadThread : public QThread {
public:
RawHIDReadThread(RawHID *hid);
virtual ~RawHIDReadThread();
@ -63,7 +61,8 @@ public:
qint64 getBytesAvailable();
public slots:
void terminate() {
void terminate()
{
m_running = false;
}
@ -71,7 +70,7 @@ protected:
void run();
/** QByteArray might not be the most efficient way to implement
a circular buffer but it's good enough and very simple */
a circular buffer but it's good enough and very simple */
QByteArray m_readBuffer;
/** A mutex to protect read buffer */
@ -89,10 +88,9 @@ protected:
// *********************************************************************************
/**
* This class is nearly the same than RawHIDReadThread but for writing
*/
class RawHIDWriteThread : public QThread
{
* This class is nearly the same than RawHIDReadThread but for writing
*/
class RawHIDWriteThread : public QThread {
public:
RawHIDWriteThread(RawHID *hid);
virtual ~RawHIDWriteThread();
@ -104,7 +102,8 @@ public:
qint64 getBytesToWrite();
public slots:
void terminate() {
void terminate()
{
m_running = false;
}
@ -112,7 +111,7 @@ protected:
void run();
/** QByteArray might not be the most efficient way to implement
a circular buffer but it's good enough and very simple */
a circular buffer but it's good enough and very simple */
QByteArray m_writeBuffer;
/** A mutex to protect read buffer */
@ -145,9 +144,10 @@ RawHIDReadThread::RawHIDReadThread(RawHID *hid)
RawHIDReadThread::~RawHIDReadThread()
{
m_running = false;
//wait for the thread to terminate
if(wait(10000) == false)
// wait for the thread to terminate
if (wait(10000) == false) {
qDebug() << "Cannot terminate RawHIDReadThread";
}
}
void RawHIDReadThread::run()
@ -156,35 +156,29 @@ void RawHIDReadThread::run()
m_running = m_hid->openDevice();
while(m_running)
{
//here we use a temporary buffer so we don't need to lock
//the mutex while we are reading from the device
while (m_running) {
// here we use a temporary buffer so we don't need to lock
// the mutex while we are reading from the device
// Want to read in regular chunks that match the packet size the device
// is using. In this case it is 64 bytes (the interrupt packet limit)
// although it would be nice if the device had a different report to
// configure this
char buffer[READ_SIZE] = {0};
char buffer[READ_SIZE] = { 0 };
int ret = hiddev->receive(hidno, buffer, READ_SIZE, READ_TIMEOUT);
if(ret > 0) //read some data
{
if (ret > 0) { // read some data
QMutexLocker lock(&m_readBufMtx);
// Note: Preprocess the USB packets in this OS independent code
// First byte is report ID, second byte is the number of valid bytes
m_readBuffer.append(&buffer[2], buffer[1]);
emit m_hid->readyRead();
}
else if(ret == 0) //nothing read
{
}
else // < 0 => error
{
//TODO! make proper error handling, this only quick hack for unplug freeze
m_running=false;
} else if (ret == 0) { // nothing read
} else { // < 0 => error
// TODO! make proper error handling, this only quick hack for unplug freeze
m_running = false;
}
}
m_hid->closeDevice();
@ -207,6 +201,7 @@ int RawHIDReadThread::getReadData(char *data, int size)
qint64 RawHIDReadThread::getBytesAvailable()
{
QMutexLocker lock(&m_readBufMtx);
return m_readBuffer.size();
}
@ -215,66 +210,60 @@ RawHIDWriteThread::RawHIDWriteThread(RawHID *hid)
hiddev(&hid->dev),
hidno(hid->m_deviceNo),
m_running(true)
{
}
{}
// *********************************************************************************
RawHIDWriteThread::~RawHIDWriteThread()
{
m_running = false;
//wait for the thread to terminate
if(wait(10000) == false)
// wait for the thread to terminate
if (wait(10000) == false) {
qDebug() << "Cannot terminate RawHIDReadThread";
}
}
void RawHIDWriteThread::run()
{
while(m_running)
{
char buffer[WRITE_SIZE] = {0};
while (m_running) {
char buffer[WRITE_SIZE] = { 0 };
m_writeBufMtx.lock();
int size = qMin(WRITE_SIZE-2, m_writeBuffer.size());
while(size <= 0)
{
//wait on new data to write condition, the timeout
//enable the thread to shutdown properly
int size = qMin(WRITE_SIZE - 2, m_writeBuffer.size());
while (size <= 0) {
// wait on new data to write condition, the timeout
// enable the thread to shutdown properly
m_newDataToWrite.wait(&m_writeBufMtx, 200);
if(!m_running)
if (!m_running) {
return;
}
size = m_writeBuffer.size();
}
//NOTE: data size is limited to 2 bytes less than the
//usb packet size (64 bytes for interrupt) to make room
//for the reportID and valid data length
size = qMin(WRITE_SIZE-2, m_writeBuffer.size());
// NOTE: data size is limited to 2 bytes less than the
// usb packet size (64 bytes for interrupt) to make room
// for the reportID and valid data length
size = qMin(WRITE_SIZE - 2, m_writeBuffer.size());
memcpy(&buffer[2], m_writeBuffer.constData(), size);
buffer[1] = size; //valid data length
buffer[0] = 2; //reportID
buffer[1] = size; // valid data length
buffer[0] = 2; // reportID
m_writeBufMtx.unlock();
// must hold lock through the send to know how much was sent
int ret = hiddev->send(hidno, buffer, WRITE_SIZE, WRITE_TIMEOUT);
if(ret > 0)
{
//only remove the size actually written to the device
if (ret > 0) {
// only remove the size actually written to the device
QMutexLocker lock(&m_writeBufMtx);
m_writeBuffer.remove(0, size);
emit m_hid->bytesWritten(ret - 2);
}
else if(ret < 0) // < 0 => error
{
//TODO! make proper error handling, this only quick hack for unplug freeze
m_running=false;
} else if (ret < 0) { // < 0 => error
// TODO! make proper error handling, this only quick hack for unplug freeze
m_running = false;
qDebug() << "Error writing to device (" << ret << ")";
}
else
{
} else {
qDebug() << "No data written to device ??";
}
}
@ -285,7 +274,7 @@ int RawHIDWriteThread::pushDataToWrite(const char *data, int size)
QMutexLocker lock(&m_writeBufMtx);
m_writeBuffer.append(data, size);
m_newDataToWrite.wakeOne(); //signal that new data arrived
m_newDataToWrite.wakeOne(); // signal that new data arrived
return size;
}
@ -299,12 +288,12 @@ qint64 RawHIDWriteThread::getBytesToWrite()
// *********************************************************************************
RawHID::RawHID(const QString &deviceName)
:QIODevice(),
: QIODevice(),
serialNumber(deviceName),
m_deviceNo(-1),
m_readThread(NULL),
m_writeThread(NULL),
m_mutex(NULL)
m_writeThread(NULL),
m_mutex(NULL)
{
OPHID_TRACE("IN");
@ -334,18 +323,19 @@ RawHID::RawHID(const QString &deviceName)
* system code is registered in that thread instead of the calling
* thread (usually UI)
*/
bool RawHID::openDevice() {
bool RawHID::openDevice()
{
OPHID_TRACE("IN");
uint32_t opened = dev.open(USB_MAX_DEVICES, USB_VID, USB_PID_ANY, USB_USAGE_PAGE, USB_USAGE);
OPHID_DEBUG("opened %d devices", opened);
for (uint32_t i=0; i < opened; i++) {
if (serialNumber == dev.getserial(i))
for (uint32_t i = 0; i < opened; i++) {
if (serialNumber == dev.getserial(i)) {
m_deviceNo = i;
else
} else {
dev.close(i);
}
}
// Now things are opened or not (from read thread) allow the constructor to complete
@ -353,8 +343,7 @@ bool RawHID::openDevice() {
// Leave if we have not found one device
// It should be the one we are looking for
if (!opened)
{
if (!opened) {
OPHID_TRACE("OUT");
return false;
}
@ -370,8 +359,8 @@ bool RawHID::openDevice() {
* It is uses as a callback from the read thread so that the USB
* system code is unregistered from that thread\
*/
bool RawHID::closeDevice() {
bool RawHID::closeDevice()
{
OPHID_TRACE("IN");
dev.close(m_deviceNo);
@ -383,19 +372,21 @@ bool RawHID::closeDevice() {
RawHID::~RawHID()
{
// OPHID_TRACE("IN");
// OPHID_TRACE("IN");
// If the read thread exists then the device is open
if (m_readThread)
if (m_readThread) {
close();
}
// OPHID_TRACE("OUT");
// OPHID_TRACE("OUT");
}
void RawHID::onDeviceUnplugged(int num)
{
if (num != m_deviceNo)
if (num != m_deviceNo) {
return;
}
// The USB device has been unplugged
close();
@ -405,15 +396,20 @@ bool RawHID::open(OpenMode mode)
{
QMutexLocker locker(m_mutex);
if (m_deviceNo < 0)
if (m_deviceNo < 0) {
return false;
}
QIODevice::open(mode);
Q_ASSERT(m_readThread);
Q_ASSERT(m_writeThread);
if (m_readThread) m_readThread->start();
if (m_writeThread) m_writeThread->start();
if (m_readThread) {
m_readThread->start();
}
if (m_writeThread) {
m_writeThread->start();
}
return true;
}
@ -424,8 +420,7 @@ void RawHID::close()
emit aboutToClose();
if (m_writeThread)
{
if (m_writeThread) {
OPHID_DEBUG("Terminating write thread");
m_writeThread->terminate();
delete m_writeThread;
@ -434,8 +429,7 @@ void RawHID::close()
}
if (m_readThread)
{
if (m_readThread) {
OPHID_DEBUG("Terminating read thread");
m_readThread->terminate();
delete m_readThread;
@ -459,8 +453,9 @@ qint64 RawHID::bytesAvailable() const
{
QMutexLocker locker(m_mutex);
if (!m_readThread)
if (!m_readThread) {
return -1;
}
return m_readThread->getBytesAvailable() + QIODevice::bytesAvailable();
}
@ -469,8 +464,9 @@ qint64 RawHID::bytesToWrite() const
{
QMutexLocker locker(m_mutex);
if (!m_writeThread)
if (!m_writeThread) {
return -1;
}
return m_writeThread->getBytesToWrite() + QIODevice::bytesToWrite();
}
@ -479,8 +475,9 @@ qint64 RawHID::readData(char *data, qint64 maxSize)
{
QMutexLocker locker(m_mutex);
if (!m_readThread || !data)
if (!m_readThread || !data) {
return -1;
}
return m_readThread->getReadData(data, maxSize);
}
@ -489,9 +486,9 @@ qint64 RawHID::writeData(const char *data, qint64 maxSize)
{
QMutexLocker locker(m_mutex);
if (!m_writeThread || !data)
if (!m_writeThread || !data) {
return -1;
}
return m_writeThread->pushDataToWrite(data, maxSize);
}

View File

@ -34,11 +34,11 @@
#include "opHID_hidapi.h"
/**
* \brief Constructor
*
* \note
*
*/
* \brief Constructor
*
* \note
*
*/
opHID_hidapi::opHID_hidapi()
{
OPHID_TRACE("IN");
@ -46,19 +46,20 @@ opHID_hidapi::opHID_hidapi()
handle = NULL;
// Make sure hidapi lib is ready
if (hid_init())
if (hid_init()) {
OPHID_ERROR("Lib initialization (hidpai).");
}
OPHID_TRACE("OUT");
}
/**
* \brief Destructor
*
* \note This does not handle the cleanup of hidapi lib
*
*/
* \brief Destructor
*
* \note This does not handle the cleanup of hidapi lib
*
*/
opHID_hidapi::~opHID_hidapi()
{
OPHID_TRACE("IN");
@ -68,33 +69,33 @@ opHID_hidapi::~opHID_hidapi()
/**
* \brief Enumerate the list of HID device with our vendor id
*
* \note Why don't we use the one from within the hidapi directly
* in caller? because later we will do more parsing herer.
* WARNING: our vendor id is harcoded here (not good idea).
*
* \param[out] current_device_pptr Pointer to the list of device
* \param[out] devices_found Number of devices found.
* \return error.
* \retval 0 on success.
*/
int opHID_hidapi::enumerate(struct hid_device_info **current_device_pptr, int *devices_found)
* \brief Enumerate the list of HID device with our vendor id
*
* \note Why don't we use the one from within the hidapi directly
* in caller? because later we will do more parsing herer.
* WARNING: our vendor id is harcoded here (not good idea).
*
* \param[out] current_device_pptr Pointer to the list of device
* \param[out] devices_found Number of devices found.
* \return error.
* \retval 0 on success.
*/
int opHID_hidapi::enumerate(struct hid_device_info * *current_device_pptr, int *devices_found)
{
int retry = 5;
*devices_found = 0;
struct hid_device_info *current_device_ptr = NULL;
OPHID_TRACE("IN");
while(retry--)
{
// Enumerate
while (retry--) {
// Enumerate
*current_device_pptr = hid_enumerate(USB_VID, 0x0);
// Display the list of devices found (for debug)
current_device_ptr = *current_device_pptr;
current_device_ptr = *current_device_pptr;
while (current_device_ptr) {
OPHID_DEBUG("HID Device Found");
@ -106,8 +107,9 @@ int opHID_hidapi::enumerate(struct hid_device_info **current_device_pptr, int *d
(*devices_found)++;
}
if (*devices_found)
if (*devices_found) {
break;
}
}
OPHID_TRACE("OUT");
@ -116,90 +118,80 @@ int opHID_hidapi::enumerate(struct hid_device_info **current_device_pptr, int *d
/**
* \brief Open HID device using hidapi library
*
* \note This function does \b not support opening multiple devices at once.
*
* \param[in] vid USB vendor id of the device to open (-1 for any).
* \param[in] pid USB product id of the device to open (-1 for any).
* \return Number of opened device.
* \retval 0 or 1.
*/
* \brief Open HID device using hidapi library
*
* \note This function does \b not support opening multiple devices at once.
*
* \param[in] vid USB vendor id of the device to open (-1 for any).
* \param[in] pid USB product id of the device to open (-1 for any).
* \return Number of opened device.
* \retval 0 or 1.
*/
int opHID_hidapi::open(int max, int vid, int pid, int usage_page, int usage)
{
int devices_found = false;
struct hid_device_info *current_device_ptr = NULL;
struct hid_device_info *last_device_ptr = NULL;
struct hid_device_info **current_device_pptr = &current_device_ptr;
struct hid_device_info *current_device_ptr = NULL;
struct hid_device_info *last_device_ptr = NULL;
struct hid_device_info * *current_device_pptr = &current_device_ptr;
OPHID_TRACE("IN");
OPHID_DEBUG("max: %d, vid: 0x%X, pid: 0x%X, usage_page: %d, usage: %d.", max, vid, pid, usage_page, usage);
if (handle)
{
if (handle) {
OPHID_WARNING("HID device seems already open.");
}
// This is a hack to prevent changing all the callers (for now)
if (vid == -1)
if (vid == -1) {
vid = 0;
if (pid == -1)
}
if (pid == -1) {
pid = 0;
}
// If caller knows which one to look for open it right away
if (vid != 0 && pid != 0)
{
if (vid != 0 && pid != 0) {
handle = hid_open(vid, pid, NULL);
if (!handle)
{
if (!handle) {
OPHID_ERROR("Unable to open device.");
devices_found = false;
}
else
{
} else {
OPHID_DEBUG("HID Device Found");
OPHID_DEBUG(" type:............VID(%04hx).PID(%04hx)", vid, pid);
devices_found = true;
}
}
else
{
} else {
// Get the list of available hid devices
if (enumerate(current_device_pptr, &devices_found) != OPHID_NO_ERROR)
{
if (enumerate(current_device_pptr, &devices_found) != OPHID_NO_ERROR) {
OPHID_ERROR("Error during enumeration");
return 0;
}
if (devices_found)
{
if (devices_found) {
// Look for the last one in the list
// WARNING: for now this prevent to have devices chained
last_device_ptr = current_device_ptr;
while (last_device_ptr->next)
while (last_device_ptr->next) {
last_device_ptr = last_device_ptr->next;
}
OPHID_DEBUG("Opening device VID(%04hx).PID(%04hx)",
last_device_ptr->vendor_id,
last_device_ptr->product_id);
OPHID_DEBUG("Opening device VID(%04hx).PID(%04hx)",
last_device_ptr->vendor_id,
last_device_ptr->product_id);
handle = hid_open(last_device_ptr->vendor_id,
last_device_ptr->product_id,
last_device_ptr->product_id,
NULL);
hid_free_enumeration(current_device_ptr);
if (!handle)
{
OPHID_ERROR("Unable to open device.");
if (!handle) {
OPHID_ERROR("Unable to open device.");
devices_found = false;
}
}
else
{
} else {
OPHID_WARNING("Unable to find any HID device.");
}
}
@ -208,23 +200,23 @@ int opHID_hidapi::open(int max, int vid, int pid, int usage_page, int usage)
OPHID_TRACE("OUT");
return devices_found;
return devices_found;
}
/**
* \brief Read an Input report from a HID device.
*
* \note This function does \b not block for now.
* Tests show that it does not need to.
*
* \param[in] num Id of the device to receive packet (NOT supported).
* \param[in] buf Pointer to the bufer to write the received packet to.
* \param[in] len Size of the buffer.
* \param[in] timeout Not supported.
* \return Number of bytes received, or -1 on error.
* \retval -1 for error or bytes received.
*/
* \brief Read an Input report from a HID device.
*
* \note This function does \b not block for now.
* Tests show that it does not need to.
*
* \param[in] num Id of the device to receive packet (NOT supported).
* \param[in] buf Pointer to the bufer to write the received packet to.
* \param[in] len Size of the buffer.
* \param[in] timeout Not supported.
* \return Number of bytes received, or -1 on error.
* \retval -1 for error or bytes received.
*/
int opHID_hidapi::receive(int num, void *buf, int len, int timeout)
{
Q_UNUSED(num);
@ -232,50 +224,46 @@ int opHID_hidapi::receive(int num, void *buf, int len, int timeout)
int bytes_read = 0;
if (!buf)
{
if (!buf) {
OPHID_ERROR("Unexpected parameter value (ptr).");
return OPHID_ERROR_POINTER;
}
if (!len)
{
if (!len) {
OPHID_ERROR("Unexpected parameter value (incorrect lenght).");
return OPHID_ERROR_PARAMETER;
}
if (handle == NULL)
{
if (handle == NULL) {
OPHID_ERROR("Handle invalid.");
return OPHID_ERROR_HANDLE;
}
hid_read_Mtx.lock();
bytes_read = hid_read(handle, (unsigned char*)buf, len);
bytes_read = hid_read(handle, (unsigned char *)buf, len);
hid_read_Mtx.unlock();
// hidapi lib does not expose the libusb errors.
if (bytes_read == -1)
{
if (bytes_read == -1) {
OPHID_ERROR("hidapi: %d", bytes_read);
}
return bytes_read;
}
/**
* \brief Write an Output report to a HID device.
*
* \note timeout is 1000ms for control transfer and
* 1000 ms for interrupt transfer.
*
* \param[in] num Id of the device to receive packet (NOT supported).
* \param[in] buf Pointer to the bufer to send.
* \param[in] len Size of the buffer.
* \param[in] timeout (not supported).
* \return Number of bytes received, or -1 on error.
* \retval -1 for error or bytes received.
*/
* \brief Write an Output report to a HID device.
*
* \note timeout is 1000ms for control transfer and
* 1000 ms for interrupt transfer.
*
* \param[in] num Id of the device to receive packet (NOT supported).
* \param[in] buf Pointer to the bufer to send.
* \param[in] len Size of the buffer.
* \param[in] timeout (not supported).
* \return Number of bytes received, or -1 on error.
* \retval -1 for error or bytes received.
*/
int opHID_hidapi::send(int num, void *buf, int len, int timeout)
{
Q_UNUSED(num);
@ -284,39 +272,33 @@ int opHID_hidapi::send(int num, void *buf, int len, int timeout)
int bytes_written = 0;
int retry = 5;
if (!buf)
{
OPHID_ERROR("Unexpected parameter value (ptr).");
if (!buf) {
OPHID_ERROR("Unexpected parameter value (ptr).");
return OPHID_ERROR_POINTER;
}
if (!len)
{
if (!len) {
OPHID_ERROR("Unexpected parameter value (incorrect lenght).");
return OPHID_ERROR_PARAMETER;
}
if (handle == NULL)
{
if (handle == NULL) {
OPHID_ERROR("Handle invalid.");
return OPHID_ERROR_HANDLE;
}
// hidapi has a timeout hardcoded to 1000ms, retry 5 times
while(retry--)
{
while (retry--) {
hid_write_Mtx.lock();
bytes_written = hid_write(handle, (const unsigned char*)buf, len);
bytes_written = hid_write(handle, (const unsigned char *)buf, len);
hid_write_Mtx.unlock();
if (bytes_written >= 0)
{
if (bytes_written >= 0) {
break;
}
}
// hidapi lib does not expose the libusb errors.
if (bytes_written < 0)
{
if (bytes_written < 0) {
OPHID_ERROR("hidapi: %d", bytes_written);
}
@ -325,16 +307,16 @@ int opHID_hidapi::send(int num, void *buf, int len, int timeout)
/**
* \brief Return the serial number of a device.
*
* \note This function does \b not handle multiple
* HID devices. Only the serial number of the
* current HID device will supported.
*
* \param[in] num Id of the device to request SN (NOT supported).
* \return Serial number
* \retval string
*/
* \brief Return the serial number of a device.
*
* \note This function does \b not handle multiple
* HID devices. Only the serial number of the
* current HID device will supported.
*
* \param[in] num Id of the device to request SN (NOT supported).
* \return Serial number
* \retval string
*/
QString opHID_hidapi::getserial(int num)
{
Q_UNUSED(num);
@ -342,43 +324,41 @@ QString opHID_hidapi::getserial(int num)
OPHID_TRACE("IN");
wchar_t buf[USB_MAX_STRING_SIZE];
if (handle == NULL)
{
if (handle == NULL) {
OPHID_ERROR("Handle invalid.");
return QString("");
}
if (hid_get_serial_number_string(handle, buf, USB_MAX_STRING_SIZE) < 0)
{
if (hid_get_serial_number_string(handle, buf, USB_MAX_STRING_SIZE) < 0) {
OPHID_ERROR("Unable to read serial number string.");
return QString("");
}
OPHID_TRACE("OUT");
return QString().fromWCharArray(buf);
}
/**
* \brief Close a HID device
*
* \note This function does \b not handle multiple
* HID devices currently.
*
* \param[in] num Id of the device to close (NOT supported).
*/
* \brief Close a HID device
*
* \note This function does \b not handle multiple
* HID devices currently.
*
* \param[in] num Id of the device to close (NOT supported).
*/
void opHID_hidapi::close(int num)
{
Q_UNUSED(num);
OPHID_TRACE("IN");
if (handle)
hid_close(handle);
if (handle) {
hid_close(handle);
}
handle = NULL;
OPHID_TRACE("OUT");
}

View File

@ -10,18 +10,18 @@
* @brief Impliments a HID USB connection to the flight hardware as a QIODevice
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
@ -37,49 +37,50 @@
/**
* \brief Constructor
*
* \note
*
*/
* \brief Constructor
*
* \note
*
*/
RawHIDConnection::RawHIDConnection()
{
RawHidHandle = NULL;
RawHidHandle = NULL;
enablePolling = true;
m_usbMonitor = USBMonitor::instance();
m_usbMonitor = USBMonitor::instance();
#ifndef __APPLE__
connect(m_usbMonitor, SIGNAL(deviceDiscovered(USBPortInfo)), this, SLOT(onDeviceConnected()));
connect(m_usbMonitor, SIGNAL(deviceRemoved(USBPortInfo)), this, SLOT(onDeviceDisconnected()));
connect(m_usbMonitor, SIGNAL(deviceDiscovered(USBPortInfo)), this, SLOT(onDeviceConnected()));
connect(m_usbMonitor, SIGNAL(deviceRemoved(USBPortInfo)), this, SLOT(onDeviceDisconnected()));
#else
connect(m_usbMonitor, SIGNAL(deviceDiscovered()), this, SLOT(onDeviceConnected()));
connect(m_usbMonitor, SIGNAL(deviceRemoved()), this, SLOT(onDeviceDisconnected()));
connect(m_usbMonitor, SIGNAL(deviceDiscovered()), this, SLOT(onDeviceConnected()));
connect(m_usbMonitor, SIGNAL(deviceRemoved()), this, SLOT(onDeviceDisconnected()));
#endif
}
/**
* \brief Destructor
*
* \note
*
*/
* \brief Destructor
*
* \note
*
*/
RawHIDConnection::~RawHIDConnection()
{
if (RawHidHandle)
if (RawHidHandle->isOpen())
RawHidHandle->close();
if (RawHidHandle) {
if (RawHidHandle->isOpen()) {
RawHidHandle->close();
}
}
}
/**
* \brief New device plugged
*
* \note The USB monitor tells us a new device appeared
*
*/
* \brief New device plugged
*
* \note The USB monitor tells us a new device appeared
*
*/
void RawHIDConnection::onDeviceConnected()
{
emit availableDevChanged(this);
@ -87,35 +88,36 @@ void RawHIDConnection::onDeviceConnected()
/**
* \brief Device unplugged
*
* \note The USB monitor tells us a new device disappeared
*
*/
* \brief Device unplugged
*
* \note The USB monitor tells us a new device disappeared
*
*/
void RawHIDConnection::onDeviceDisconnected()
{
qDebug() << "onDeviceDisconnected()";
if (enablePolling)
if (enablePolling) {
emit availableDevChanged(this);
}
}
/**
* \brief Available devices
*
* \return List of all currently available devices
*/
* \brief Available devices
*
* \return List of all currently available devices
*/
QList < Core::IConnection::device> RawHIDConnection::availableDevices()
{
QList < Core::IConnection::device> devices;
QList<USBPortInfo> portsList = m_usbMonitor->availableDevices(USBMonitor::idVendor_OpenPilot, -1, -1,USBMonitor::Running);
QList<USBPortInfo> portsList = m_usbMonitor->availableDevices(USBMonitor::idVendor_OpenPilot, -1, -1, USBMonitor::Running);
// We currently list devices by their serial number
device dev;
foreach(USBPortInfo prt, portsList) {
dev.name=prt.serialNumber;
dev.displayName=prt.product;
dev.name = prt.serialNumber;
dev.displayName = prt.product;
devices.append(dev);
}
return devices;
@ -123,22 +125,22 @@ QList < Core::IConnection::device> RawHIDConnection::availableDevices()
/**
* \brief Open device
*
* \param[in] deviceName String name of the device to open
* \return initialized handle
*/
* \brief Open device
*
* \param[in] deviceName String name of the device to open
* \return initialized handle
*/
QIODevice *RawHIDConnection::openDevice(const QString &deviceName)
{
OPHID_TRACE("IN");
if (RawHidHandle)
if (RawHidHandle) {
closeDevice(deviceName);
}
RawHidHandle = new RawHID(deviceName);
if (!RawHidHandle)
{
if (!RawHidHandle) {
OPHID_ERROR("Could not instentiate HID device");
}
@ -149,18 +151,17 @@ QIODevice *RawHIDConnection::openDevice(const QString &deviceName)
/**
* \brief Close device
*
* \param[in] deviceName String name of the device to close
*/
* \brief Close device
*
* \param[in] deviceName String name of the device to close
*/
void RawHIDConnection::closeDevice(const QString &deviceName)
{
OPHID_TRACE("IN");
Q_UNUSED(deviceName);
if (RawHidHandle)
{
if (RawHidHandle) {
OPHID_DEBUG("Closing device");
RawHidHandle->close();
delete RawHidHandle;
@ -172,10 +173,10 @@ void RawHIDConnection::closeDevice(const QString &deviceName)
/**
* \brief Get connection name
*
* \return name of the connection
*/
* \brief Get connection name
*
* \return name of the connection
*/
QString RawHIDConnection::connectionName()
{
return QString("Raw HID USB");
@ -183,10 +184,10 @@ QString RawHIDConnection::connectionName()
/**
* \brief Get shorter connection name
*
* \return shorter name of the connection
*/
* \brief Get shorter connection name
*
* \return shorter name of the connection
*/
QString RawHIDConnection::shortName()
{
return QString("USB");
@ -194,10 +195,10 @@ QString RawHIDConnection::shortName()
/**
* \brief Suspend polling
*
* \note Tells the Raw HID plugin to stop polling for USB devices
*/
* \brief Suspend polling
*
* \note Tells the Raw HID plugin to stop polling for USB devices
*/
void RawHIDConnection::suspendPolling()
{
enablePolling = false;
@ -205,10 +206,10 @@ void RawHIDConnection::suspendPolling()
/**
* \brief Resume polling
*
* \note Tells the Raw HID plugin to resume polling for USB devices
*/
* \brief Resume polling
*
* \note Tells the Raw HID plugin to resume polling for USB devices
*/
void RawHIDConnection::resumePolling()
{
enablePolling = true;
@ -216,23 +217,23 @@ void RawHIDConnection::resumePolling()
/**
* \brief Plugin Constructor
*
* \note
*
*/
* \brief Plugin Constructor
*
* \note
*
*/
RawHIDPlugin::RawHIDPlugin()
{
hidConnection = NULL; // Pip
hidConnection = NULL; // Pip
}
/**
* \brief Plugin Destructor
*
* \note
*
*/
* \brief Plugin Destructor
*
* \note
*
*/
RawHIDPlugin::~RawHIDPlugin()
{
m_usbMonitor->quit();
@ -241,28 +242,28 @@ RawHIDPlugin::~RawHIDPlugin()
/**
* \brief Instantiate a connection
*
* \note
*
*/
* \brief Instantiate a connection
*
* \note
*
*/
void RawHIDPlugin::extensionsInitialized()
{
hidConnection = new RawHIDConnection();
addAutoReleasedObject(hidConnection);
//temp for test
//addAutoReleasedObject(new RawHIDTestThread);
// temp for test
// addAutoReleasedObject(new RawHIDTestThread);
}
/**
* \brief instantiate the udev monotor engine
*
* \note
*
*/
bool RawHIDPlugin::initialize(const QStringList & arguments, QString * errorString)
* \brief instantiate the udev monotor engine
*
* \note
*
*/
bool RawHIDPlugin::initialize(const QStringList & arguments, QString *errorString)
{
Q_UNUSED(arguments);
Q_UNUSED(errorString);
@ -274,4 +275,3 @@ bool RawHIDPlugin::initialize(const QStringList & arguments, QString * errorStri
}
Q_EXPORT_PLUGIN(RawHIDPlugin)

View File

@ -31,14 +31,14 @@
/**
* \brief Display device info
*
* \note USB strings are Unicode, UCS2
* encoded, but the strings returned from
* udev_device_get_sysattr_value() are UTF-8 encoded.
*
* \param[in] dev To display the information of.
*/
* \brief Display device info
*
* \note USB strings are Unicode, UCS2
* encoded, but the strings returned from
* udev_device_get_sysattr_value() are UTF-8 encoded.
*
* \param[in] dev To display the information of.
*/
void printPortInfo(struct udev_device *dev)
{
OPHID_DEBUG(" Node: %s", udev_device_get_devnode(dev));
@ -46,77 +46,74 @@ void printPortInfo(struct udev_device *dev)
OPHID_DEBUG(" Devtype: %s", udev_device_get_devtype(dev));
OPHID_DEBUG(" Action: %s", udev_device_get_action(dev));
OPHID_DEBUG(" VID/PID/bcdDevice : %s %s %s",
udev_device_get_sysattr_value(dev,"idVendor"),
udev_device_get_sysattr_value(dev, "idVendor"),
udev_device_get_sysattr_value(dev, "idProduct"),
udev_device_get_sysattr_value(dev,"bcdDevice"));
udev_device_get_sysattr_value(dev, "bcdDevice"));
OPHID_DEBUG(" %s - %s",
udev_device_get_sysattr_value(dev,"manufacturer"),
udev_device_get_sysattr_value(dev,"product"));
udev_device_get_sysattr_value(dev, "manufacturer"),
udev_device_get_sysattr_value(dev, "product"));
OPHID_DEBUG(" serial: %s",
udev_device_get_sysattr_value(dev, "serial"));
}
/**
* \brief Handle event
*
* \note
*
*/
void USBMonitor::deviceEventReceived() {
* \brief Handle event
*
* \note
*
*/
void USBMonitor::deviceEventReceived()
{
qDebug() << "Device event";
struct udev_device *dev;
dev = udev_monitor_receive_device(this->monitor);
if (dev) {
printf("------- Got Device Event");
QString action = QString(udev_device_get_action(dev));
QString action = QString(udev_device_get_action(dev));
QString devtype = QString(udev_device_get_devtype(dev));
if (action == "add" && devtype == "usb_device") {
printPortInfo(dev);
emit deviceDiscovered(makePortInfo(dev));
} else if (action == "remove" && devtype == "usb_device"){
} else if (action == "remove" && devtype == "usb_device") {
printPortInfo(dev);
emit deviceRemoved(makePortInfo(dev));
}
udev_device_unref(dev);
}
else {
} else {
printf("No Device from receive_device(). An error occured.");
}
}
/**
* \brief Return USB monitor instance
*
* \note .
*
* \return instance.
* \retval USBMonitor pointer.
*/
USBMonitor* USBMonitor::instance()
* \brief Return USB monitor instance
*
* \note .
*
* \return instance.
* \retval USBMonitor pointer.
*/
USBMonitor *USBMonitor::instance()
{
return m_instance;
}
USBMonitor* USBMonitor::m_instance = 0;
USBMonitor *USBMonitor::m_instance = 0;
/**
* \brief Initialize udev monitor (contructor).
*
* \note
*
*/
USBMonitor::USBMonitor(QObject *parent): QThread(parent) {
m_instance = this;
* \brief Initialize udev monitor (contructor).
*
* \note
*
*/
USBMonitor::USBMonitor(QObject *parent) : QThread(parent)
{
m_instance = this;
this->context = udev_new();
@ -135,11 +132,11 @@ USBMonitor::USBMonitor(QObject *parent): QThread(parent) {
/**
* \brief Destructor
*
* \note
*
*/
* \brief Destructor
*
* \note
*
*/
USBMonitor::~USBMonitor()
{
quit();
@ -147,13 +144,13 @@ USBMonitor::~USBMonitor()
/**
* \brief Returns a list of all currently available devices
*
* \note
*
* \return List of all currently available devices
* \retval Qlist
*/
* \brief Returns a list of all currently available devices
*
* \note
*
* \return List of all currently available devices
* \retval Qlist
*/
QList<USBPortInfo> USBMonitor::availableDevices()
{
QList<USBPortInfo> devicesList;
@ -162,20 +159,21 @@ QList<USBPortInfo> USBMonitor::availableDevices()
struct udev_device *dev;
enumerate = udev_enumerate_new(this->context);
udev_enumerate_add_match_subsystem(enumerate,"usb");
//udev_enumerate_add_match_sysattr(enumerate, "idVendor", "20a0");
udev_enumerate_add_match_subsystem(enumerate, "usb");
// udev_enumerate_add_match_sysattr(enumerate, "idVendor", "20a0");
udev_enumerate_scan_devices(enumerate);
devices = udev_enumerate_get_list_entry(enumerate);
// Will use the 'native' udev functions to loop:
udev_list_entry_foreach(dev_list_entry,devices) {
udev_list_entry_foreach(dev_list_entry, devices) {
const char *path;
/* Get the filename of the /sys entry for the device
and create a udev_device object (dev) representing it */
and create a udev_device object (dev) representing it */
path = udev_list_entry_get_name(dev_list_entry);
dev = udev_device_new_from_syspath(this->context, path);
if (QString(udev_device_get_devtype(dev)) == "usb_device")
dev = udev_device_new_from_syspath(this->context, path);
if (QString(udev_device_get_devtype(dev)) == "usb_device") {
devicesList.append(makePortInfo(dev));
}
udev_device_unref(dev);
}
// free the enumerator object
@ -186,42 +184,43 @@ QList<USBPortInfo> USBMonitor::availableDevices()
/**
* \brief Search for particular devices
*
* \note Be a bit more picky and ask only for a specific type of device:
* On OpenPilot, the bcdDeviceLSB indicates the run state: bootloader or running.
* bcdDeviceMSB indicates the board model.
*
* \param[in] vid USB vendor id of the device.
* \param[in] pid USB product id of the device.
* \param[in] bcdDeviceMSB MSB of the device in bcd format.
* \param[in] bcdDeviceLSB LSB of the device in bcd format.
* \return List of available devices
* \retval QList.
*/
* \brief Search for particular devices
*
* \note Be a bit more picky and ask only for a specific type of device:
* On OpenPilot, the bcdDeviceLSB indicates the run state: bootloader or running.
* bcdDeviceMSB indicates the board model.
*
* \param[in] vid USB vendor id of the device.
* \param[in] pid USB product id of the device.
* \param[in] bcdDeviceMSB MSB of the device in bcd format.
* \param[in] bcdDeviceLSB LSB of the device in bcd format.
* \return List of available devices
* \retval QList.
*/
QList<USBPortInfo> USBMonitor::availableDevices(int vid, int pid, int bcdDeviceMSB, int bcdDeviceLSB)
{
QList<USBPortInfo> allPorts = availableDevices();
QList<USBPortInfo> thePortsWeWant;
foreach (USBPortInfo port, allPorts) {
if((port.vendorID==vid || vid==-1) && (port.productID==pid || pid==-1) && ((port.bcdDevice>>8)==bcdDeviceMSB || bcdDeviceMSB==-1) &&
( (port.bcdDevice&0x00ff) ==bcdDeviceLSB || bcdDeviceLSB==-1))
foreach(USBPortInfo port, allPorts) {
if ((port.vendorID == vid || vid == -1) && (port.productID == pid || pid == -1) && ((port.bcdDevice >> 8) == bcdDeviceMSB || bcdDeviceMSB == -1) &&
((port.bcdDevice & 0x00ff) == bcdDeviceLSB || bcdDeviceLSB == -1)) {
thePortsWeWant.append(port);
}
}
return thePortsWeWant;
}
/**
* \brief Initialize port information of a specific device.
*
* \note
*
* \param[in] dev Udev device.
* \return Port info
* \retval USBPortInfo structure filled
*/
* \brief Initialize port information of a specific device.
*
* \note
*
* \param[in] dev Udev device.
* \return Port info
* \retval USBPortInfo structure filled
*/
USBPortInfo USBMonitor::makePortInfo(struct udev_device *dev)
{
USBPortInfo prtInfo;
@ -231,15 +230,14 @@ USBPortInfo USBMonitor::makePortInfo(struct udev_device *dev)
printPortInfo(dev);
#endif
prtInfo.vendorID = QString(udev_device_get_sysattr_value(dev, "idVendor")).toInt(&ok, 16);
prtInfo.productID = QString(udev_device_get_sysattr_value(dev, "idProduct")).toInt(&ok, 16);
prtInfo.vendorID = QString(udev_device_get_sysattr_value(dev, "idVendor")).toInt(&ok, 16);
prtInfo.productID = QString(udev_device_get_sysattr_value(dev, "idProduct")).toInt(&ok, 16);
prtInfo.serialNumber = QString(udev_device_get_sysattr_value(dev, "serial"));
prtInfo.manufacturer = QString(udev_device_get_sysattr_value(dev,"manufacturer"));
prtInfo.product = QString(udev_device_get_sysattr_value(dev,"product"));
// prtInfo.UsagePage = QString(udev_device_get_sysattr_value(dev,""));
// prtInfo.Usage = QString(udev_device_get_sysattr_value(dev,""));
prtInfo.bcdDevice = QString(udev_device_get_sysattr_value(dev,"bcdDevice")).toInt(&ok, 16);
prtInfo.manufacturer = QString(udev_device_get_sysattr_value(dev, "manufacturer"));
prtInfo.product = QString(udev_device_get_sysattr_value(dev, "product"));
// prtInfo.UsagePage = QString(udev_device_get_sysattr_value(dev,""));
// prtInfo.Usage = QString(udev_device_get_sysattr_value(dev,""));
prtInfo.bcdDevice = QString(udev_device_get_sysattr_value(dev, "bcdDevice")).toInt(&ok, 16);
return prtInfo;
}

View File

@ -37,7 +37,7 @@
#define OP_LOOPMODE_NAME_MAC "Open_Pilot_Loop_Mode"
#define printf qDebug
#define printf qDebug
// ! Local helper functions
static bool HID_GetIntProperty(IOHIDDeviceRef dev, CFStringRef property, int *value);
@ -48,25 +48,25 @@ static bool HID_GetStrProperty(IOHIDDeviceRef dev, CFStringRef property, QString
*/
USBMonitor::USBMonitor(QObject *parent) : QThread(parent)
{
m_instance = this;
hid_manager = NULL;
listMutex = new QMutex();
knowndevices.clear();
m_instance = this;
hid_manager = NULL;
listMutex = new QMutex();
knowndevices.clear();
m_terminate = false;
m_terminate = false;
start();
}
USBMonitor::~USBMonitor()
{
m_terminate = true;
m_terminate = true;
// if(hid_manager != NULL)
// IOHIDManagerUnscheduleFromRunLoop(hid_manager, CFRunLoopGetCurrent(), kCFRunLoopDefaultMode);
// quit();
// quit();
while (hid_manager != 0) {
this->sleep(10);
}
while (hid_manager != 0) {
this->sleep(10);
}
}
void USBMonitor::deviceEventReceived()
@ -90,7 +90,7 @@ void USBMonitor::removeDevice(IOHIDDeviceRef dev)
QMutexLocker locker(listMutex);
knowndevices.removeAt(i);
emit deviceRemoved(port);
emit deviceRemoved();
emit deviceRemoved();
return;
}
}
@ -113,9 +113,9 @@ void USBMonitor::addDevice(USBPortInfo info)
{
QMutexLocker locker(listMutex);
knowndevices.append(info);
emit deviceDiscovered(info);
emit deviceDiscovered();
knowndevices.append(info);
emit deviceDiscovered(info);
emit deviceDiscovered();
}
void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHIDDeviceRef dev)
@ -187,38 +187,38 @@ QList<USBPortInfo> USBMonitor::availableDevices(int vid, int pid, int bcdDeviceM
void USBMonitor::run()
{
IOReturn ret;
IOReturn ret;
hid_manager = IOHIDManagerCreate(kCFAllocatorDefault, kIOHIDOptionsTypeNone);
if (hid_manager == NULL || CFGetTypeID(hid_manager) != IOHIDManagerGetTypeID()) {
if (hid_manager) {
CFRelease(hid_manager);
}
assert(0);
}
hid_manager = IOHIDManagerCreate(kCFAllocatorDefault, kIOHIDOptionsTypeNone);
if (hid_manager == NULL || CFGetTypeID(hid_manager) != IOHIDManagerGetTypeID()) {
if (hid_manager) {
CFRelease(hid_manager);
}
assert(0);
}
// No matching filter
IOHIDManagerSetDeviceMatching(hid_manager, NULL);
// No matching filter
IOHIDManagerSetDeviceMatching(hid_manager, NULL);
CFRunLoopRef loop = CFRunLoopGetCurrent();
// set up a callbacks for device attach & detach
IOHIDManagerScheduleWithRunLoop(hid_manager, loop, kCFRunLoopDefaultMode);
IOHIDManagerRegisterDeviceMatchingCallback(hid_manager, attach_callback, this);
IOHIDManagerRegisterDeviceRemovalCallback(hid_manager, detach_callback, this);
ret = IOHIDManagerOpen(hid_manager, kIOHIDOptionsTypeNone);
if (ret != kIOReturnSuccess) {
IOHIDManagerUnscheduleFromRunLoop(hid_manager, loop, kCFRunLoopDefaultMode);
CFRelease(hid_manager);
return;
}
CFRunLoopRef loop = CFRunLoopGetCurrent();
// set up a callbacks for device attach & detach
IOHIDManagerScheduleWithRunLoop(hid_manager, loop, kCFRunLoopDefaultMode);
IOHIDManagerRegisterDeviceMatchingCallback(hid_manager, attach_callback, this);
IOHIDManagerRegisterDeviceRemovalCallback(hid_manager, detach_callback, this);
ret = IOHIDManagerOpen(hid_manager, kIOHIDOptionsTypeNone);
if (ret != kIOReturnSuccess) {
IOHIDManagerUnscheduleFromRunLoop(hid_manager, loop, kCFRunLoopDefaultMode);
CFRelease(hid_manager);
return;
}
while(!m_terminate) {
CFRunLoopRunInMode(kCFRunLoopDefaultMode, 1, false);
}
IOHIDManagerUnscheduleFromRunLoop(hid_manager, loop, kCFRunLoopDefaultMode);
CFRelease(hid_manager);
while (!m_terminate) {
CFRunLoopRunInMode(kCFRunLoopDefaultMode, 1, false);
}
IOHIDManagerUnscheduleFromRunLoop(hid_manager, loop, kCFRunLoopDefaultMode);
CFRelease(hid_manager);
hid_manager = NULL;
hid_manager = NULL;
}
/**

View File

@ -30,36 +30,35 @@
/**
* \brief trigger device discovered signal
*
* \note
*
* \param[in] port.
*/
* \brief trigger device discovered signal
*
* \note
*
* \param[in] port.
*/
void USBSignalFilter::m_deviceDiscovered(USBPortInfo port)
{
if((port.vendorID==m_vid || m_vid==-1) &&
(port.productID==m_pid || m_pid==-1) &&
((port.bcdDevice>>8)==m_boardModel || m_boardModel==-1) &&
((port.bcdDevice&0x00ff) ==m_runState || m_runState==-1))
{
qDebug()<<"USBSignalFilter emit device discovered";
if ((port.vendorID == m_vid || m_vid == -1) &&
(port.productID == m_pid || m_pid == -1) &&
((port.bcdDevice >> 8) == m_boardModel || m_boardModel == -1) &&
((port.bcdDevice & 0x00ff) == m_runState || m_runState == -1)) {
qDebug() << "USBSignalFilter emit device discovered";
emit deviceDiscovered();
}
}
/**
* \brief Constructor
*
* \note
*
* \param[in] vid USB vendor id of the device to open (-1 for any).
* \param[in] pid USB product id of the device to open (-1 for any).
* \param[in] boardModel.
* \param[in] runState.
*/
USBSignalFilter::USBSignalFilter(int vid, int pid, int boardModel, int runState):
* \brief Constructor
*
* \note
*
* \param[in] vid USB vendor id of the device to open (-1 for any).
* \param[in] pid USB product id of the device to open (-1 for any).
* \param[in] boardModel.
* \param[in] runState.
*/
USBSignalFilter::USBSignalFilter(int vid, int pid, int boardModel, int runState) :
m_vid(vid),
m_pid(pid),
m_boardModel(boardModel),
@ -68,8 +67,6 @@ USBSignalFilter::USBSignalFilter(int vid, int pid, int boardModel, int runState)
connect(USBMonitor::instance(),
SIGNAL(deviceDiscovered(USBPortInfo)),
this,
SLOT(m_deviceDiscovered(USBPortInfo)),
Qt::QueuedConnection);
SLOT(m_deviceDiscovered(USBPortInfo)),
Qt::QueuedConnection);
}