Merge branch 'xxxajk'

This commit is contained in:
Oleg Mazurov 2013-08-09 15:44:24 -06:00
commit eefb971656
32 changed files with 1521 additions and 591 deletions

View file

@ -115,14 +115,16 @@ uint8_t BTD::Init(uint8_t parent, uint8_t port, bool lowspeed) {
bAddress = 0; bAddress = 0;
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nsetAddr: "), 0x80); Notify(PSTR("\r\nsetAddr: "), 0x80);
#endif
D_PrintHex<uint8_t > (rcode, 0x80); D_PrintHex<uint8_t > (rcode, 0x80);
#endif
return rcode; return rcode;
} }
#ifdef EXTRADEBUG #ifdef EXTRADEBUG
Notify(PSTR("\r\nAddr: "), 0x80); Notify(PSTR("\r\nAddr: "), 0x80);
D_PrintHex<uint8_t > (bAddress, 0x80); D_PrintHex<uint8_t > (bAddress, 0x80);
#endif #endif
delay(300); // Spec says you should wait at least 200ms
p->lowspeed = false; p->lowspeed = false;
//get pointer to assigned address record //get pointer to assigned address record
@ -157,7 +159,7 @@ uint8_t BTD::Init(uint8_t parent, uint8_t port, bool lowspeed) {
if (my_bdaddr[0] == 0x00 && my_bdaddr[1] == 0x00 && my_bdaddr[2] == 0x00 && my_bdaddr[3] == 0x00 && my_bdaddr[4] == 0x00 && my_bdaddr[5] == 0x00) { if (my_bdaddr[0] == 0x00 && my_bdaddr[1] == 0x00 && my_bdaddr[2] == 0x00 && my_bdaddr[3] == 0x00 && my_bdaddr[4] == 0x00 && my_bdaddr[5] == 0x00) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nPlease plug in the dongle before trying to pair with the PS3 Controller\n\rOr set the Bluetooth address in the constructor of the PS3BT class"), 0x80); Notify(PSTR("\r\nPlease plug in the dongle before trying to pair with the PS3 Controller\n\ror set the Bluetooth address in the constructor of the PS3BT class"), 0x80);
#endif #endif
} else { } else {
if (PID == PS3_PID || PID == PS3NAVIGATION_PID) if (PID == PS3_PID || PID == PS3NAVIGATION_PID)

19
BTD.h
View file

@ -194,6 +194,23 @@ public:
virtual bool isReady() { virtual bool isReady() {
return bPollEnable; return bPollEnable;
}; };
/**
* Used by the USB core to check what this driver support.
* @param klass The device's USB class.
* @return Returns true if the device's USB class matches this driver.
*/
virtual boolean DEVCLASSOK(uint8_t klass) { return (klass == USB_CLASS_WIRELESS_CTRL); }
/**
* Used by the USB core to check what this driver support.
* Used to set the Bluetooth address into the PS3 controllers.
* @param vid The device's VID.
* @param pid The device's PID.
* @return Returns true if the device's VID and PID matches this driver.
*/
virtual boolean VIDPIDOK(uint16_t vid, uint16_t pid) {
return (vid == PS3_VID && (pid == PS3_PID || pid == PS3NAVIGATION_PID || pid == PS3MOVE_PID));
};
/**@}*/ /**@}*/
/** @name UsbConfigXtracter implementation */ /** @name UsbConfigXtracter implementation */
@ -450,7 +467,7 @@ private:
uint8_t hcibuf[BULK_MAXPKTSIZE]; //General purpose buffer for hci data uint8_t hcibuf[BULK_MAXPKTSIZE]; //General purpose buffer for hci data
uint8_t l2capinbuf[BULK_MAXPKTSIZE]; //General purpose buffer for l2cap in data uint8_t l2capinbuf[BULK_MAXPKTSIZE]; //General purpose buffer for l2cap in data
uint8_t l2capoutbuf[BULK_MAXPKTSIZE]; //General purpose buffer for l2cap out data uint8_t l2capoutbuf[14]; //General purpose buffer for l2cap out data
/* State machines */ /* State machines */
void HCI_event_task(); // Poll the HCI event pipe void HCI_event_task(); // Poll the HCI event pipe

View file

@ -459,9 +459,6 @@ void PS3BT::L2CAP_task() {
if (remote_name[0] == 'M') { // First letter in Motion Controller ('M') if (remote_name[0] == 'M') { // First letter in Motion Controller ('M')
for (uint8_t i = 0; i < BULK_MAXPKTSIZE; i++) // Reset l2cap in buffer as it sometimes read it as a button has been pressed for (uint8_t i = 0; i < BULK_MAXPKTSIZE; i++) // Reset l2cap in buffer as it sometimes read it as a button has been pressed
l2capinbuf[i] = 0; l2capinbuf[i] = 0;
ButtonState = 0;
OldButtonState = 0;
l2cap_state = L2CAP_HID_PS3_LED; l2cap_state = L2CAP_HID_PS3_LED;
} else } else
l2cap_state = L2CAP_HID_ENABLE_SIXAXIS; l2cap_state = L2CAP_HID_ENABLE_SIXAXIS;
@ -502,12 +499,9 @@ void PS3BT::Run() {
if (millis() - timer > 1000) { // loop 1 second before sending the command if (millis() - timer > 1000) { // loop 1 second before sending the command
for (uint8_t i = 0; i < BULK_MAXPKTSIZE; i++) // Reset l2cap in buffer as it sometimes read it as a button has been pressed for (uint8_t i = 0; i < BULK_MAXPKTSIZE; i++) // Reset l2cap in buffer as it sometimes read it as a button has been pressed
l2capinbuf[i] = 0; l2capinbuf[i] = 0;
ButtonState = 0;
OldButtonState = 0;
enable_sixaxis();
for (uint8_t i = 15; i < 19; i++) for (uint8_t i = 15; i < 19; i++)
l2capinbuf[i] = 0x7F; // Set the analog joystick values to center position l2capinbuf[i] = 0x7F; // Set the analog joystick values to center position
enable_sixaxis();
l2cap_state = L2CAP_HID_PS3_LED; l2cap_state = L2CAP_HID_PS3_LED;
timer = millis(); timer = millis();
} }
@ -516,25 +510,27 @@ void PS3BT::Run() {
case L2CAP_HID_PS3_LED: case L2CAP_HID_PS3_LED:
if (millis() - timer > 1000) { // loop 1 second before sending the command if (millis() - timer > 1000) { // loop 1 second before sending the command
if (remote_name[0] == 'P') { // First letter in PLAYSTATION(R)3 Controller ('P') if (remote_name[0] == 'P') { // First letter in PLAYSTATION(R)3 Controller ('P')
setLedOn(LED1);
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nDualshock 3 Controller Enabled\r\n"), 0x80); Notify(PSTR("\r\nDualshock 3 Controller Enabled\r\n"), 0x80);
#endif #endif
PS3Connected = true; PS3Connected = true;
} else if (remote_name[0] == 'N') { // First letter in Navigation Controller ('N') } else if (remote_name[0] == 'N') { // First letter in Navigation Controller ('N')
setLedOn(LED1); // This just turns LED constantly on, on the Navigation controller
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nNavigation Controller Enabled\r\n"), 0x80); Notify(PSTR("\r\nNavigation Controller Enabled\r\n"), 0x80);
#endif #endif
PS3NavigationConnected = true; PS3NavigationConnected = true;
} else if (remote_name[0] == 'M') { // First letter in Motion Controller ('M') } else if (remote_name[0] == 'M') { // First letter in Motion Controller ('M')
moveSetBulb(Red);
timerBulbRumble = millis(); timerBulbRumble = millis();
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nMotion Controller Enabled\r\n"), 0x80); Notify(PSTR("\r\nMotion Controller Enabled\r\n"), 0x80);
#endif #endif
PS3MoveConnected = true; PS3MoveConnected = true;
} }
ButtonState = 0; // Clear all values
OldButtonState = 0;
ButtonClickState = 0;
onInit(); // Turn on the LED on the controller
l2cap_state = L2CAP_DONE; l2cap_state = L2CAP_DONE;
} }
break; break;
@ -659,3 +655,14 @@ void PS3BT::moveSetRumble(uint8_t rumble) {
HIDMove_Command(HIDMoveBuffer, HID_BUFFERSIZE); HIDMove_Command(HIDMoveBuffer, HID_BUFFERSIZE);
} }
void PS3BT::onInit() {
if (pFuncOnInit)
pFuncOnInit(); // Call the user function
else {
if (PS3MoveConnected)
moveSetBulb(Red);
else // Dualshock 3 or Navigation controller
setLedOn(LED1);
}
}

26
PS3BT.h
View file

@ -207,19 +207,35 @@ public:
* @param rumble The desired value in the range from 64-255. * @param rumble The desired value in the range from 64-255.
*/ */
void moveSetRumble(uint8_t rumble); void moveSetRumble(uint8_t rumble);
/**
* Used to call your own function when the controller is successfully initialized.
* @param funcOnInit Function to call.
*/
void attachOnInit(void (*funcOnInit)(void)) {
pFuncOnInit = funcOnInit;
};
/**@}*/ /**@}*/
/** Variable used to indicate if the normal playstation controller is successfully connected. */ /** Variable used to indicate if the normal Playstation controller is successfully connected. */
bool PS3Connected; bool PS3Connected;
/** Variable used to indicate if the move controller is successfully connected. */ /** Variable used to indicate if the Move controller is successfully connected. */
bool PS3MoveConnected; bool PS3MoveConnected;
/** Variable used to indicate if the navigation controller is successfully connected. */ /** Variable used to indicate if the Navigation controller is successfully connected. */
bool PS3NavigationConnected; bool PS3NavigationConnected;
private: private:
/* mandatory members */ /* Mandatory members */
BTD *pBtd; BTD *pBtd;
/**
* Called when the controller is successfully initialized.
* Use attachOnInit(void (*funcOnInit)(void)) to call your own function.
* This is useful for instance if you want to set the LEDs in a specific way.
*/
void onInit();
void (*pFuncOnInit)(void); // Pointer to function called in onInit()
void L2CAP_task(); // L2CAP state machine void L2CAP_task(); // L2CAP state machine
/* Variables filled from HCI event management */ /* Variables filled from HCI event management */
@ -229,7 +245,7 @@ private:
/* variables used by high level L2CAP task */ /* variables used by high level L2CAP task */
uint8_t l2cap_state; uint8_t l2cap_state;
uint16_t l2cap_event_flag; // L2CAP flags of received bluetooth events uint16_t l2cap_event_flag; // L2CAP flags of received Bluetooth events
unsigned long timer; unsigned long timer;

View file

@ -120,14 +120,16 @@ uint8_t PS3USB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
bAddress = 0; bAddress = 0;
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nsetAddr: "), 0x80); Notify(PSTR("\r\nsetAddr: "), 0x80);
#endif
D_PrintHex<uint8_t > (rcode, 0x80); D_PrintHex<uint8_t > (rcode, 0x80);
#endif
return rcode; return rcode;
} }
#ifdef EXTRADEBUG #ifdef EXTRADEBUG
Notify(PSTR("\r\nAddr: "), 0x80); Notify(PSTR("\r\nAddr: "), 0x80);
D_PrintHex<uint8_t > (bAddress, 0x80); D_PrintHex<uint8_t > (bAddress, 0x80);
#endif #endif
delay(300); // Spec says you should wait at least 200ms
p->lowspeed = false; p->lowspeed = false;
//get pointer to assigned address record //get pointer to assigned address record
@ -183,10 +185,7 @@ uint8_t PS3USB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
#endif #endif
PS3NavigationConnected = true; PS3NavigationConnected = true;
} }
/* Set internal bluetooth address and request for data */ enable_sixaxis(); // The PS3 controller needs a special command before it starts sending data
setBdaddr(my_bdaddr);
enable_sixaxis();
setLedOn(LED1);
// Needed for PS3 Dualshock and Navigation commands to work // Needed for PS3 Dualshock and Navigation commands to work
for (uint8_t i = 0; i < PS3_REPORT_BUFFER_SIZE; i++) for (uint8_t i = 0; i < PS3_REPORT_BUFFER_SIZE; i++)
@ -199,11 +198,13 @@ uint8_t PS3USB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
Notify(PSTR("\r\nMotion Controller Connected"), 0x80); Notify(PSTR("\r\nMotion Controller Connected"), 0x80);
#endif #endif
PS3MoveConnected = true; PS3MoveConnected = true;
setMoveBdaddr(my_bdaddr); // Set internal bluetooth address
moveSetBulb(Red);
writeBuf[0] = 0x02; // Set report ID, this is needed for Move commands to work writeBuf[0] = 0x02; // Set report ID, this is needed for Move commands to work
} }
if (my_bdaddr[0] != 0x00 || my_bdaddr[1] != 0x00 || my_bdaddr[2] != 0x00 || my_bdaddr[3] != 0x00 || my_bdaddr[4] != 0x00 || my_bdaddr[5] != 0x00) {
if (PS3MoveConnected)
setMoveBdaddr(my_bdaddr); // Set internal Bluetooth address
else
setBdaddr(my_bdaddr); // Set internal Bluetooth address
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nBluetooth Address was set to: "), 0x80); Notify(PSTR("\r\nBluetooth Address was set to: "), 0x80);
@ -213,6 +214,8 @@ uint8_t PS3USB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
} }
D_PrintHex<uint8_t > (my_bdaddr[0], 0x80); D_PrintHex<uint8_t > (my_bdaddr[0], 0x80);
#endif #endif
}
onInit();
bPollEnable = true; bPollEnable = true;
Notify(PSTR("\r\n"), 0x80); Notify(PSTR("\r\n"), 0x80);
@ -538,3 +541,14 @@ void PS3USB::setMoveBdaddr(uint8_t* BDADDR) {
//bmRequest = Host to device (0x00) | Class (0x20) | Interface (0x01) = 0x21, bRequest = Set Report (0x09), Report ID (0x05), Report Type (Feature 0x03), interface (0x00), datalength, datalength, data) //bmRequest = Host to device (0x00) | Class (0x20) | Interface (0x01) = 0x21, bRequest = Set Report (0x09), Report ID (0x05), Report Type (Feature 0x03), interface (0x00), datalength, datalength, data)
pUsb->ctrlReq(bAddress, epInfo[PS3_CONTROL_PIPE].epAddr, bmREQ_HID_OUT, HID_REQUEST_SET_REPORT, 0x05, 0x03, 0x00, 11, 11, buf, NULL); pUsb->ctrlReq(bAddress, epInfo[PS3_CONTROL_PIPE].epAddr, bmREQ_HID_OUT, HID_REQUEST_SET_REPORT, 0x05, 0x03, 0x00, 11, 11, buf, NULL);
} }
void PS3USB::onInit() {
if (pFuncOnInit)
pFuncOnInit(); // Call the user function
else {
if (PS3MoveConnected)
moveSetBulb(Red);
else // Dualshock 3 or Navigation controller
setLedOn(LED1);
}
}

View file

@ -104,6 +104,16 @@ public:
virtual bool isReady() { virtual bool isReady() {
return bPollEnable; return bPollEnable;
}; };
/**
* Used by the USB core to check what this driver support.
* @param vid The device's VID.
* @param pid The device's PID.
* @return Returns true if the device's VID and PID matches this driver.
*/
virtual boolean VIDPIDOK(uint16_t vid, uint16_t pid) {
return (vid == PS3_VID && (pid == PS3_PID || pid == PS3NAVIGATION_PID || pid == PS3MOVE_PID));
};
/**@}*/ /**@}*/
/** /**
@ -224,6 +234,14 @@ public:
* @param rumble The desired value in the range from 64-255. * @param rumble The desired value in the range from 64-255.
*/ */
void moveSetRumble(uint8_t rumble); void moveSetRumble(uint8_t rumble);
/**
* Used to call your own function when the controller is successfully initialized.
* @param funcOnInit Function to call.
*/
void attachOnInit(void (*funcOnInit)(void)) {
pFuncOnInit = funcOnInit;
};
/**@}*/ /**@}*/
/** Variable used to indicate if the normal playstation controller is successfully connected. */ /** Variable used to indicate if the normal playstation controller is successfully connected. */
@ -242,6 +260,14 @@ protected:
EpInfo epInfo[PS3_MAX_ENDPOINTS]; EpInfo epInfo[PS3_MAX_ENDPOINTS];
private: private:
/**
* Called when the controller is successfully initialized.
* Use attachOnInit(void (*funcOnInit)(void)) to call your own function.
* This is useful for instance if you want to set the LEDs in a specific way.
*/
void onInit();
void (*pFuncOnInit)(void); // Pointer to function called in onInit()
bool bPollEnable; bool bPollEnable;
uint32_t timer; // used to continuously set PS3 Move controller Bulb and rumble values uint32_t timer; // used to continuously set PS3 Move controller Bulb and rumble values

View file

@ -22,7 +22,7 @@ For more information about the hardware see the [Hardware Manual](http://www.cir
* __Alexei Glushchenko, Circuits@Home__ - <alex-gl@mail.ru> * __Alexei Glushchenko, Circuits@Home__ - <alex-gl@mail.ru>
* Developers of the USB Core, HID, FTDI, ADK, ACM, and PL2303 libraries * Developers of the USB Core, HID, FTDI, ADK, ACM, and PL2303 libraries
* __Kristian Lauszus, TKJ Electronics__ - <kristianl@tkjelectronics.com> * __Kristian Lauszus, TKJ Electronics__ - <kristianl@tkjelectronics.com>
* Developer of the BTD, SPP, PS3, Wii, and Xbox libraries * Developer of the [BTD](#bluetooth-libraries), [SPP](#spp-library), [PS3](#ps3-library), [Wii](#wii-library), and [Xbox](#xbox-library) libraries
* __Andrew Kroll__ - <xxxajk@gmail.com> * __Andrew Kroll__ - <xxxajk@gmail.com>
* Major contributor to mass storage code * Major contributor to mass storage code
@ -53,23 +53,27 @@ For more information visit the following site: <http://arduino.cc/en/Guide/Libra
Documentation for the library can be found at the following link: <http://felis.github.com/USB_Host_Shield_2.0/>. Documentation for the library can be found at the following link: <http://felis.github.com/USB_Host_Shield_2.0/>.
### Enable debugging
By default serial debugging is disabled. To turn it on uncomment ```DEBUG_USB_HOST``` in [message.h](message.h).
### Arduino ADK ### Arduino ADK
To use this library with the official [Arduino ADK](http://arduino.cc/en/Main/ArduinoBoardADK) uncomment the following line in [avrpins.h](https://github.com/felis/USB_Host_Shield_2.0/blob/master/avrpins.h): To use this library with the official [Arduino ADK](http://arduino.cc/en/Main/ArduinoBoardADK) uncomment the following line in [avrpins.h](avrpins.h):
<code> ```
\#define BOARD\_MEGA_ADK #define BOARD_MEGA_ADK
</code> ```
### [Bluetooth libraries](https://github.com/felis/USB_Host_Shield_2.0/blob/master/BTD.cpp) ### [Bluetooth libraries](BTD.cpp)
The [BTD library](https://github.com/felis/USB_Host_Shield_2.0/blob/master/BTD.cpp) is a general purpose library for an ordinary Bluetooth dongle. The [BTD library](BTD.cpp) is a general purpose library for an ordinary Bluetooth dongle.
This library make it easy to add support for different Bluetooth services like a PS3 or a Wii controller or SPP which is a virtual serial port via Bluetooth. This library make it easy to add support for different Bluetooth services like a PS3 or a Wii controller or SPP which is a virtual serial port via Bluetooth.
Some different examples can be found in the [example directory](https://github.com/felis/USB_Host_Shield_2.0/tree/master/examples/Bluetooth). Some different examples can be found in the [example directory](examples/Bluetooth).
The BTD library will also make it possible to use multiple services at once, the following example sketch is an example of this: The BTD library will also make it possible to use multiple services at once, the following example sketch is an example of this:
<https://github.com/felis/USB_Host_Shield_2.0/blob/master/examples/Bluetooth/PS3SPP/PS3SPP.ino> <https://github.com/felis/USB_Host_Shield_2.0/blob/master/examples/Bluetooth/PS3SPP/PS3SPP.ino>
### [SPP library](https://github.com/felis/USB_Host_Shield_2.0/blob/master/SPP.cpp) ### [SPP library](SPP.cpp)
SPP stands for "Serial Port Profile" and is a Bluetooth protocol that implements a virtual comport which allows you to send data back and forth from your computer/phone to your Arduino via Bluetooth. SPP stands for "Serial Port Profile" and is a Bluetooth protocol that implements a virtual comport which allows you to send data back and forth from your computer/phone to your Arduino via Bluetooth.
It has been tested successfully on Windows, Mac OS X, Linux, and Android. It has been tested successfully on Windows, Mac OS X, Linux, and Android.
@ -84,7 +88,7 @@ It enables me to see the Bluetooth communication between my Mac and any device.
### PS3 Library ### PS3 Library
These libraries consist of the [PS3BT](https://github.com/felis/USB_Host_Shield_2.0/blob/master/PS3BT.cpp) and [PS3USB](https://github.com/felis/USB_Host_Shield_2.0/blob/master/PS3USB.cpp). These libraries allows you to use a Dualshock 3, Navigation or a Motion controller with the USB Host Shield both via Bluetooth and USB. These libraries consist of the [PS3BT](PS3BT.cpp) and [PS3USB](PS3USB.cpp). These libraries allows you to use a Dualshock 3, Navigation or a Motion controller with the USB Host Shield both via Bluetooth and USB.
In order to use your Playstation controller via Bluetooth you have to set the Bluetooth address of the dongle internally to your PS3 Controller. This can be achieved by plugging the controller in via USB and letting the library set it automatically. In order to use your Playstation controller via Bluetooth you have to set the Bluetooth address of the dongle internally to your PS3 Controller. This can be achieved by plugging the controller in via USB and letting the library set it automatically.
@ -110,15 +114,30 @@ Also a big thanks all the people behind these sites about the Motion controller:
* <https://github.com/thp/psmoveapi> * <https://github.com/thp/psmoveapi>
* <http://code.google.com/p/moveonpc/> * <http://code.google.com/p/moveonpc/>
### Xbox 360 Library ### Xbox Libraries
The library supports both the original Xbox controller via USB and the Xbox 360 controller both via USB and wirelessly.
#### Xbox library
The [XBOXOLD](XBOXOLD.cpp) class implements support for the original Xbox controller via USB.
All the information are from the following sites:
* <https://github.com/torvalds/linux/blob/master/Documentation/input/xpad.txt>
* <https://github.com/torvalds/linux/blob/master/drivers/input/joystick/xpad.c>
* <http://euc.jp/periphs/xbox-controller.ja.html>
* <https://github.com/Grumbel/xboxdrv/blob/master/PROTOCOL#L15>
#### Xbox 360 Library
The library support one Xbox 360 via USB or up to four Xbox 360 controllers wirelessly by using a [Xbox 360 wireless receiver](http://blog.tkjelectronics.dk/wp-content/uploads/xbox360-wireless-receiver.jpg). The library support one Xbox 360 via USB or up to four Xbox 360 controllers wirelessly by using a [Xbox 360 wireless receiver](http://blog.tkjelectronics.dk/wp-content/uploads/xbox360-wireless-receiver.jpg).
To use it via USB use the [XBOXUSB](https://github.com/felis/USB_Host_Shield_2.0/blob/master/XBOXUSB.cpp) library or to use it wirelessly use the [XBOXRECV](https://github.com/felis/USB_Host_Shield_2.0/blob/master/XBOXRECV.cpp) library. To use it via USB use the [XBOXUSB](XBOXUSB.cpp) library or to use it wirelessly use the [XBOXRECV](XBOXRECV.cpp) library.
__Note that a Wireless controller can NOT be used via USB!__ __Note that a Wireless controller can NOT be used via USB!__
Examples code can be found in the [examples directory](https://github.com/felis/USB_Host_Shield_2.0/tree/master/examples/Xbox). Examples code can be found in the [examples directory](examples/Xbox).
Also see the following blog posts: Also see the following blog posts:
@ -132,23 +151,23 @@ All the information regarding the Xbox 360 controller protocol are form these si
* <http://tattiebogle.net/index.php/ProjectRoot/Xbox360Controller/WirelessUsbInfo> * <http://tattiebogle.net/index.php/ProjectRoot/Xbox360Controller/WirelessUsbInfo>
* <https://github.com/Grumbel/xboxdrv/blob/master/PROTOCOL> * <https://github.com/Grumbel/xboxdrv/blob/master/PROTOCOL>
### [Wii library](https://github.com/felis/USB_Host_Shield_2.0/blob/master/Wii.cpp) ### [Wii library](Wii.cpp)
The [Wii](https://github.com/felis/USB_Host_Shield_2.0/blob/master/Wii.cpp) library support the Wiimote, but also the Nunchuch and Motion Plus extensions via Bluetooth. The Wii U Pro Controller is also supported via Bluetooth. The [Wii](Wii.cpp) library support the Wiimote, but also the Nunchuch and Motion Plus extensions via Bluetooth. The Wii U Pro Controller is also supported via Bluetooth.
First you have to pair with the controller, this is done automatically by the library if you create the instance like so: First you have to pair with the controller, this is done automatically by the library if you create the instance like so:
<code> ```
WII Wii(&Btd,PAIR); WII Wii(&Btd,PAIR);
</code> ```
And then press 1 & 2 at once on the Wiimote or press sync if you are using a Wii U Pro Controller. And then press 1 & 2 at once on the Wiimote or press sync if you are using a Wii U Pro Controller.
After that you can simply create the instance like so: After that you can simply create the instance like so:
<code> ```
WII Wii(&Btd); WII Wii(&Btd);
</code> ```
Then just press any button any button on the Wiimote and it will connect to the dongle. Then just press any button any button on the Wiimote and it will connect to the dongle.

View file

@ -231,7 +231,7 @@ void SPP::ACLData(uint8_t* l2capinbuf) {
} }
#ifdef EXTRADEBUG #ifdef EXTRADEBUG
else { else {
Notify(PSTR("\r\nUnknown PDU: ")); Notify(PSTR("\r\nUnknown PDU: "), 0x80);
D_PrintHex<uint8_t > (l2capinbuf[8], 0x80); D_PrintHex<uint8_t > (l2capinbuf[8], 0x80);
} }
#endif #endif

View file

@ -692,12 +692,10 @@ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) {
for (devConfigIndex = 0; devConfigIndex < USB_NUMDEVICES; devConfigIndex++) { for (devConfigIndex = 0; devConfigIndex < USB_NUMDEVICES; devConfigIndex++) {
if (!devConfig[devConfigIndex]) continue; // no driver if (!devConfig[devConfigIndex]) continue; // no driver
if (devConfig[devConfigIndex]->GetAddress()) continue; // consumed if (devConfig[devConfigIndex]->GetAddress()) continue; // consumed
if (devConfig[devConfigIndex]->VIDPIDOK(vid, pid)) { if (devConfig[devConfigIndex]->VIDPIDOK(vid, pid) || devConfig[devConfigIndex]->DEVCLASSOK(klass)) {
rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed); rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed);
if (rcode != USB_DEV_CONFIG_ERROR_DEVICE_NOT_SUPPORTED)
break; break;
} else if (devConfig[devConfigIndex]->DEVCLASSOK(klass)) {
rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed);
if (!rcode) break;
} }
} }
@ -710,6 +708,7 @@ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) {
for (devConfigIndex = 0; devConfigIndex < USB_NUMDEVICES; devConfigIndex++) { for (devConfigIndex = 0; devConfigIndex < USB_NUMDEVICES; devConfigIndex++) {
if (!devConfig[devConfigIndex]) continue; if (!devConfig[devConfigIndex]) continue;
if (devConfig[devConfigIndex]->GetAddress()) continue; // consumed if (devConfig[devConfigIndex]->GetAddress()) continue; // consumed
if (devConfig[devConfigIndex]->VIDPIDOK(vid, pid) || devConfig[devConfigIndex]->DEVCLASSOK(klass)) continue; // If this is true it means it must have returned USB_DEV_CONFIG_ERROR_DEVICE_NOT_SUPPORTED above
rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed); rcode = AttemptConfig(devConfigIndex, parent, port, lowspeed);
//printf("ERROR ENUMERATING %2.2x\r\n", rcode); //printf("ERROR ENUMERATING %2.2x\r\n", rcode);

65
Wii.cpp
View file

@ -14,9 +14,7 @@
Web : http://www.tkjelectronics.com Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com e-mail : kristianl@tkjelectronics.com
IR camera support added by: IR camera support added by Allan Glover (adglover9.81@gmail.com) and Kristian Lauszus
Allan Glover
adglover9.81@gmail.com
*/ */
#include "Wii.h" #include "Wii.h"
@ -109,7 +107,7 @@ void WII::Reset() {
activateNunchuck = false; activateNunchuck = false;
motionValuesReset = false; motionValuesReset = false;
activeConnection = false; activeConnection = false;
pBtd->motionPlusInside = false; motionPlusInside = false;
pBtd->wiiUProController = false; pBtd->wiiUProController = false;
wiiUProControllerConnected = false; wiiUProControllerConnected = false;
l2cap_event_flag = 0; // Reset flags l2cap_event_flag = 0; // Reset flags
@ -117,13 +115,17 @@ void WII::Reset() {
} }
void WII::disconnect() { // Use this void to disconnect any of the controllers void WII::disconnect() { // Use this void to disconnect any of the controllers
if (motionPlusConnected && !pBtd->motionPlusInside) { // Disable the Motion Plus extension if (!motionPlusInside) { // The old Wiimote needs a delay after the first command or it will automatically reconnect
if (motionPlusConnected) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nDeactivating Motion Plus"), 0x80); Notify(PSTR("\r\nDeactivating Motion Plus"), 0x80);
#endif #endif
initExtension1(); // This will disable the Motion Plus extension initExtension1(); // This will disable the Motion Plus extension
} }
//First the HID interrupt channel has to be disconencted, then the HID control channel and finally the HCI connection timer = millis() + 1000; // We have to wait for the message before the rest of the channels can be deactivated
} else
timer = millis(); // Don't wait
// First the HID interrupt channel has to be disconnected, then the HID control channel and finally the HCI connection
pBtd->l2cap_disconnection_request(hci_handle, 0x0A, interrupt_scid, interrupt_dcid); pBtd->l2cap_disconnection_request(hci_handle, 0x0A, interrupt_scid, interrupt_dcid);
Reset(); Reset();
l2cap_state = L2CAP_INTERRUPT_DISCONNECT; l2cap_state = L2CAP_INTERRUPT_DISCONNECT;
@ -133,6 +135,7 @@ void WII::ACLData(uint8_t* l2capinbuf) {
if (!pBtd->l2capConnectionClaimed && pBtd->incomingWii && !wiimoteConnected && !activeConnection) { if (!pBtd->l2capConnectionClaimed && pBtd->incomingWii && !wiimoteConnected && !activeConnection) {
if (l2capinbuf[8] == L2CAP_CMD_CONNECTION_REQUEST) { if (l2capinbuf[8] == L2CAP_CMD_CONNECTION_REQUEST) {
if ((l2capinbuf[12] | (l2capinbuf[13] << 8)) == HID_CTRL_PSM) { if ((l2capinbuf[12] | (l2capinbuf[13] << 8)) == HID_CTRL_PSM) {
motionPlusInside = pBtd->motionPlusInside;
pBtd->incomingWii = false; pBtd->incomingWii = false;
pBtd->l2capConnectionClaimed = true; // Claim that the incoming connection belongs to this service pBtd->l2capConnectionClaimed = true; // Claim that the incoming connection belongs to this service
activeConnection = true; activeConnection = true;
@ -254,7 +257,6 @@ void WII::ACLData(uint8_t* l2capinbuf) {
#endif #endif
} else if (l2capinbuf[6] == interrupt_dcid[0] && l2capinbuf[7] == interrupt_dcid[1]) { // l2cap_interrupt } else if (l2capinbuf[6] == interrupt_dcid[0] && l2capinbuf[7] == interrupt_dcid[1]) { // l2cap_interrupt
//Notify(PSTR("\r\nL2CAP Interrupt"), 0x80); //Notify(PSTR("\r\nL2CAP Interrupt"), 0x80);
if (wiimoteConnected) {
if (l2capinbuf[8] == 0xA1) { // HID_THDR_DATA_INPUT if (l2capinbuf[8] == 0xA1) { // HID_THDR_DATA_INPUT
if ((l2capinbuf[9] >= 0x20 && l2capinbuf[9] <= 0x22) || (l2capinbuf[9] >= 0x30 && l2capinbuf[9] <= 0x37) || l2capinbuf[9] == 0x3e || l2capinbuf[9] == 0x3f) { // These reports include the buttons if ((l2capinbuf[9] >= 0x20 && l2capinbuf[9] <= 0x22) || (l2capinbuf[9] >= 0x30 && l2capinbuf[9] <= 0x37) || l2capinbuf[9] == 0x3e || l2capinbuf[9] == 0x3f) { // These reports include the buttons
if ((l2capinbuf[9] >= 0x20 && l2capinbuf[9] <= 0x22) || l2capinbuf[9] == 0x31 || l2capinbuf[9] == 0x33) // These reports have no extensions bytes if ((l2capinbuf[9] >= 0x20 && l2capinbuf[9] <= 0x22) || l2capinbuf[9] == 0x31 || l2capinbuf[9] == 0x33) // These reports have no extensions bytes
@ -291,13 +293,16 @@ void WII::ACLData(uint8_t* l2capinbuf) {
} }
switch (l2capinbuf[9]) { switch (l2capinbuf[9]) {
case 0x20: // Status Information - (a1) 20 BB BB LF 00 00 VV case 0x20: // Status Information - (a1) 20 BB BB LF 00 00 VV
#ifdef EXTRADEBUG
Notify(PSTR("\r\nStatus report was received"), 0x80);
#endif
wiiState = l2capinbuf[12]; // (0x01: Battery is nearly empty), (0x02: An Extension Controller is connected), (0x04: Speaker enabled), (0x08: IR enabled), (0x10: LED1, 0x20: LED2, 0x40: LED3, 0x80: LED4) wiiState = l2capinbuf[12]; // (0x01: Battery is nearly empty), (0x02: An Extension Controller is connected), (0x04: Speaker enabled), (0x08: IR enabled), (0x10: LED1, 0x20: LED2, 0x40: LED3, 0x80: LED4)
batteryLevel = l2capinbuf[15]; // Update battery level batteryLevel = l2capinbuf[15]; // Update battery level
if (l2capinbuf[12] & 0x01) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
if (l2capinbuf[12] & 0x01)
Notify(PSTR("\r\nWARNING: Battery is nearly empty"), 0x80); Notify(PSTR("\r\nWARNING: Battery is nearly empty"), 0x80);
#endif #endif
} if (checkExtension) { // If this is false it means that the user must have called getBatteryLevel()
if (l2capinbuf[12] & 0x02) { // Check if a extension is connected if (l2capinbuf[12] & 0x02) { // Check if a extension is connected
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
if (!unknownExtensionConnected) if (!unknownExtensionConnected)
@ -326,12 +331,13 @@ void WII::ACLData(uint8_t* l2capinbuf) {
#endif #endif
nunchuckConnected = false; // It must be the Nunchuck controller then nunchuckConnected = false; // It must be the Nunchuck controller then
l2cap_event_flag &= ~WII_FLAG_NUNCHUCK_CONNECTED; l2cap_event_flag &= ~WII_FLAG_NUNCHUCK_CONNECTED;
setLedStatus(); onInit();
setReportMode(false, 0x31); // If there is no extension connected we will read the button and accelerometer setReportMode(false, 0x31); // If there is no extension connected we will read the buttons and accelerometer
} else { } else
setReportMode(false, 0x31); // If there is no extension connected we will read the button and accelerometer setReportMode(false, 0x31); // If there is no extension connected we will read the buttons and accelerometer
}
} }
} else
checkExtension = true; // Check for extensions by default
break; break;
case 0x21: // Read Memory Data case 0x21: // Read Memory Data
if ((l2capinbuf[12] & 0x0F) == 0) { // No error if ((l2capinbuf[12] & 0x0F) == 0) { // No error
@ -351,6 +357,7 @@ void WII::ACLData(uint8_t* l2capinbuf) {
Notify(PSTR("\r\nMotion Plus activated in normal mode"), 0x80); Notify(PSTR("\r\nMotion Plus activated in normal mode"), 0x80);
#endif #endif
motionPlusConnected = true; motionPlusConnected = true;
setReportMode(false, 0x35); // Also read the extension
} else if (l2capinbuf[16] == 0x00 && l2capinbuf[17] == 0xA4 && l2capinbuf[18] == 0x20 && l2capinbuf[19] == 0x05 && l2capinbuf[20] == 0x05) { } else if (l2capinbuf[16] == 0x00 && l2capinbuf[17] == 0xA4 && l2capinbuf[18] == 0x20 && l2capinbuf[19] == 0x05 && l2capinbuf[20] == 0x05) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nMotion Plus activated in Nunchuck pass-through mode"), 0x80); Notify(PSTR("\r\nMotion Plus activated in Nunchuck pass-through mode"), 0x80);
@ -358,6 +365,7 @@ void WII::ACLData(uint8_t* l2capinbuf) {
activateNunchuck = false; activateNunchuck = false;
motionPlusConnected = true; motionPlusConnected = true;
nunchuckConnected = true; nunchuckConnected = true;
setReportMode(false, 0x35); // Also read the extension
} else if (l2capinbuf[16] == 0x00 && l2capinbuf[17] == 0xA6 && l2capinbuf[18] == 0x20 && (l2capinbuf[19] == 0x00 || l2capinbuf[19] == 0x04 || l2capinbuf[19] == 0x05 || l2capinbuf[19] == 0x07) && l2capinbuf[20] == 0x05) { } else if (l2capinbuf[16] == 0x00 && l2capinbuf[17] == 0xA6 && l2capinbuf[18] == 0x20 && (l2capinbuf[19] == 0x00 || l2capinbuf[19] == 0x04 || l2capinbuf[19] == 0x05 || l2capinbuf[19] == 0x07) && l2capinbuf[20] == 0x05) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nInactive Wii Motion Plus"), 0x80); Notify(PSTR("\r\nInactive Wii Motion Plus"), 0x80);
@ -573,7 +581,6 @@ void WII::ACLData(uint8_t* l2capinbuf) {
} }
} }
} }
}
L2CAP_task(); L2CAP_task();
} }
} }
@ -647,7 +654,6 @@ void WII::L2CAP_task() {
#endif #endif
pBtd->connectToWii = false; pBtd->connectToWii = false;
pBtd->pairWithWii = false; pBtd->pairWithWii = false;
wiimoteConnected = true;
stateCounter = 0; stateCounter = 0;
l2cap_state = L2CAP_CHECK_MOTION_PLUS_STATE; l2cap_state = L2CAP_CHECK_MOTION_PLUS_STATE;
} }
@ -656,7 +662,7 @@ void WII::L2CAP_task() {
/* The next states are in run() */ /* The next states are in run() */
case L2CAP_INTERRUPT_DISCONNECT: case L2CAP_INTERRUPT_DISCONNECT:
if (l2cap_disconnect_response_interrupt_flag) { if (l2cap_disconnect_response_interrupt_flag && millis() > timer) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nDisconnected Interrupt Channel"), 0x80); Notify(PSTR("\r\nDisconnected Interrupt Channel"), 0x80);
#endif #endif
@ -681,11 +687,15 @@ void WII::L2CAP_task() {
} }
void WII::Run() { void WII::Run() {
if (l2cap_state == L2CAP_INTERRUPT_DISCONNECT && millis() > timer)
L2CAP_task(); // Call the rest of the disconnection routine after we have waited long enough
switch (l2cap_state) { switch (l2cap_state) {
case L2CAP_WAIT: case L2CAP_WAIT:
if (pBtd->connectToWii && !pBtd->l2capConnectionClaimed && !wiimoteConnected && !activeConnection) { if (pBtd->connectToWii && !pBtd->l2capConnectionClaimed && !wiimoteConnected && !activeConnection) {
pBtd->l2capConnectionClaimed = true; pBtd->l2capConnectionClaimed = true;
activeConnection = true; activeConnection = true;
motionPlusInside = pBtd->motionPlusInside;
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nSend HID Control Connection Request"), 0x80); Notify(PSTR("\r\nSend HID Control Connection Request"), 0x80);
#endif #endif
@ -779,7 +789,8 @@ void WII::Run() {
case L2CAP_LED_STATE: case L2CAP_LED_STATE:
if (nunchuck_connected_flag) if (nunchuck_connected_flag)
nunchuckConnected = true; nunchuckConnected = true;
setLedStatus(); wiimoteConnected = true;
onInit();
l2cap_state = L2CAP_DONE; l2cap_state = L2CAP_DONE;
break; break;
@ -824,7 +835,7 @@ void WII::Run() {
else if (stateCounter == 400) else if (stateCounter == 400)
readExtensionType(); // Check if it has been activated readExtensionType(); // Check if it has been activated
else if (stateCounter == 450) { else if (stateCounter == 450) {
//setLedStatus(); onInit();
stateCounter = 0; stateCounter = 0;
unknownExtensionConnected = false; unknownExtensionConnected = false;
} }
@ -839,7 +850,7 @@ void WII::Run() {
/************************************************************/ /************************************************************/
void WII::HID_Command(uint8_t* data, uint8_t nbytes) { void WII::HID_Command(uint8_t* data, uint8_t nbytes) {
if (pBtd->motionPlusInside) if (motionPlusInside)
pBtd->L2CAP_Command(hci_handle, data, nbytes, interrupt_scid[0], interrupt_scid[1]); // It's the new wiimote with the Motion Plus Inside pBtd->L2CAP_Command(hci_handle, data, nbytes, interrupt_scid[0], interrupt_scid[1]); // It's the new wiimote with the Motion Plus Inside
else else
pBtd->L2CAP_Command(hci_handle, data, nbytes, control_scid[0], control_scid[1]); pBtd->L2CAP_Command(hci_handle, data, nbytes, control_scid[0], control_scid[1]);
@ -905,6 +916,12 @@ void WII::setLedStatus() {
HID_Command(HIDBuffer, 3); HID_Command(HIDBuffer, 3);
} }
uint8_t WII::getBatteryLevel() {
checkExtension = false; // This is needed so the library knows that the status response is a response to this function
statusRequest(); // This will update the battery level
return batteryLevel;
};
void WII::setReportMode(bool continuous, uint8_t mode) { void WII::setReportMode(bool continuous, uint8_t mode) {
uint8_t cmd_buf[4]; uint8_t cmd_buf[4];
cmd_buf[0] = 0xA2; // HID BT DATA_request (0xA0) | Report Type (Output 0x02) cmd_buf[0] = 0xA2; // HID BT DATA_request (0xA0) | Report Type (Output 0x02)
@ -1062,6 +1079,14 @@ uint16_t WII::getAnalogHat(AnalogHat a) {
return output; return output;
} }
} }
void WII::onInit() {
if (pFuncOnInit)
pFuncOnInit(); // Call the user function
else
setLedStatus();
}
/************************************************************/ /************************************************************/
/* The following functions are for the IR camera */ /* The following functions are for the IR camera */
/************************************************************/ /************************************************************/

41
Wii.h
View file

@ -14,9 +14,7 @@
Web : http://www.tkjelectronics.com Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com e-mail : kristianl@tkjelectronics.com
IR camera support added by: IR camera support added by Allan Glover (adglover9.81@gmail.com) and Kristian Lauszus
Allan Glover
adglover9.81@gmail.com
*/ */
#ifndef _wii_h_ #ifndef _wii_h_
@ -215,17 +213,11 @@ public:
*/ */
void setLedStatus(); void setLedStatus();
/**
* Call this to update battery level and Wiimote state
*/
void statusRequest();
/** /**
* Return the battery level of the Wiimote. * Return the battery level of the Wiimote.
* @return The battery level in the range 0-255. * @return The battery level in the range 0-255.
*/ */
uint8_t getBatteryLevel() { uint8_t getBatteryLevel();
return batteryLevel;
};
/** /**
* Return the Wiimote state. * Return the Wiimote state.
* @return See: http://wiibrew.org/wiki/Wiimote#0x20:_Status. * @return See: http://wiibrew.org/wiki/Wiimote#0x20:_Status.
@ -233,6 +225,14 @@ public:
uint8_t getWiiState() { uint8_t getWiiState() {
return wiiState; return wiiState;
}; };
/**
* Used to call your own function when the controller is successfully initialized.
* @param funcOnInit Function to call.
*/
void attachOnInit(void (*funcOnInit)(void)) {
pFuncOnInit = funcOnInit;
};
/**@}*/ /**@}*/
/**@{*/ /**@{*/
@ -418,8 +418,15 @@ public:
#endif #endif
private: private:
/* Mandatory members */ BTD *pBtd; // Pointer to BTD instance
BTD *pBtd;
/**
* Called when the controller is successfully initialized.
* Use attachOnInit(void (*funcOnInit)(void)) to call your own function.
* This is useful for instance if you want to set the LEDs in a specific way.
*/
void onInit();
void (*pFuncOnInit)(void); // Pointer to function called in onInit()
void L2CAP_task(); // L2CAP state machine void L2CAP_task(); // L2CAP state machine
@ -427,9 +434,9 @@ private:
uint16_t hci_handle; uint16_t hci_handle;
bool activeConnection; // Used to indicate if it's already has established a connection bool activeConnection; // Used to indicate if it's already has established a connection
/* variables used by high level L2CAP task */ /* Variables used by high level L2CAP task */
uint8_t l2cap_state; uint8_t l2cap_state;
uint16_t l2cap_event_flag; // l2cap flags of received bluetooth events uint16_t l2cap_event_flag; // l2cap flags of received Bluetooth events
uint32_t ButtonState; uint32_t ButtonState;
uint32_t OldButtonState; uint32_t OldButtonState;
@ -441,6 +448,8 @@ private:
uint16_t stateCounter; uint16_t stateCounter;
bool unknownExtensionConnected; bool unknownExtensionConnected;
bool extensionConnected; bool extensionConnected;
bool checkExtension; // Set to false when getBatteryLevel() is called otherwise if should be true
bool motionPlusInside; // True if it's a new Wiimote with the Motion Plus extension build into it
/* L2CAP Channels */ /* L2CAP Channels */
uint8_t control_scid[2]; // L2CAP source CID for HID_Control uint8_t control_scid[2]; // L2CAP source CID for HID_Control
@ -457,6 +466,8 @@ private:
void initExtension1(); void initExtension1();
void initExtension2(); void initExtension2();
void statusRequest(); // Used to update the Wiimote state and battery level
void readData(uint32_t offset, uint16_t size, bool EEPROM); void readData(uint32_t offset, uint16_t size, bool EEPROM);
void readExtensionType(); void readExtensionType();
void readCalData(); void readCalData();
@ -476,7 +487,7 @@ private:
uint8_t batteryLevel; uint8_t batteryLevel;
#ifdef WIICAMERA #ifdef WIICAMERA
/* Private function and variables for the readings from teh IR Camera */ /* Private function and variables for the readings from the IR Camera */
void enableIRCamera1(); // Sets bit 2 of output report 13 void enableIRCamera1(); // Sets bit 2 of output report 13
void enableIRCamera2(); // Sets bit 2 of output report 1A void enableIRCamera2(); // Sets bit 2 of output report 1A
void writeSensitivityBlock1(); void writeSensitivityBlock1();

334
XBOXOLD.cpp Normal file
View file

@ -0,0 +1,334 @@
/* Copyright (C) 2013 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#include "XBOXOLD.h"
// To enable serial debugging uncomment "#define DEBUG_USB_HOST" in message.h
//#define EXTRADEBUG // Uncomment to get even more debugging data
//#define PRINTREPORT // Uncomment to print the report send by the Xbox controller
/** Buttons on the controllers */
const uint8_t XBOXOLDBUTTONS[] PROGMEM = {
0x01, // UP
0x08, // RIGHT
0x02, // DOWN
0x04, // LEFT
0x20, // BACK
0x10, // START
0x40, // L3
0x80, // R3
// A, B, X, Y, BLACK, WHITE, L1, and R1 are analog buttons
4, // BLACK
5, // WHTIE
6, // L1
7, // R1
1, // B
0, // A
2, // X
3, // Y
};
XBOXOLD::XBOXOLD(USB *p) :
pUsb(p), // pointer to USB class instance - mandatory
bAddress(0), // device address - mandatory
bPollEnable(false) { // don't start polling before dongle is connected
for (uint8_t i = 0; i < XBOX_MAX_ENDPOINTS; i++) {
epInfo[i].epAddr = 0;
epInfo[i].maxPktSize = (i) ? 0 : 8;
epInfo[i].epAttribs = 0;
epInfo[i].bmNakPower = (i) ? USB_NAK_NOWAIT : USB_NAK_MAX_POWER;
}
if (pUsb) // register in USB subsystem
pUsb->RegisterDeviceClass(this); //set devConfig[] entry
}
uint8_t XBOXOLD::Init(uint8_t parent, uint8_t port, bool lowspeed) {
uint8_t buf[sizeof (USB_DEVICE_DESCRIPTOR)];
uint8_t rcode;
UsbDevice *p = NULL;
EpInfo *oldep_ptr = NULL;
uint16_t PID;
uint16_t VID;
// get memory address of USB device address pool
AddressPool &addrPool = pUsb->GetAddressPool();
#ifdef EXTRADEBUG
Notify(PSTR("\r\nXBOXUSB Init"), 0x80);
#endif
// check if address has already been assigned to an instance
if (bAddress) {
#ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nAddress in use"), 0x80);
#endif
return USB_ERROR_CLASS_INSTANCE_ALREADY_IN_USE;
}
// Get pointer to pseudo device with address 0 assigned
p = addrPool.GetUsbDevicePtr(0);
if (!p) {
#ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nAddress not found"), 0x80);
#endif
return USB_ERROR_ADDRESS_NOT_FOUND_IN_POOL;
}
if (!p->epinfo) {
#ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nepinfo is null"), 0x80);
#endif
return USB_ERROR_EPINFO_IS_NULL;
}
// Save old pointer to EP_RECORD of address 0
oldep_ptr = p->epinfo;
// Temporary assign new pointer to epInfo to p->epinfo in order to avoid toggle inconsistence
p->epinfo = epInfo;
p->lowspeed = lowspeed;
// Get device descriptor
rcode = pUsb->getDevDescr(0, 0, sizeof (USB_DEVICE_DESCRIPTOR), (uint8_t*)buf); // Get device descriptor - addr, ep, nbytes, data
// Restore p->epinfo
p->epinfo = oldep_ptr;
if (rcode)
goto FailGetDevDescr;
VID = ((USB_DEVICE_DESCRIPTOR*)buf)->idVendor;
PID = ((USB_DEVICE_DESCRIPTOR*)buf)->idProduct;
if ((VID != XBOX_VID && VID != MADCATZ_VID && VID != JOYTECH_VID) || (PID != XBOX_OLD_PID1 && PID != XBOX_OLD_PID2 && PID != XBOX_OLD_PID3 && PID != XBOX_OLD_PID4)) // Check if VID and PID match
goto FailUnknownDevice;
// Allocate new address according to device class
bAddress = addrPool.AllocAddress(parent, false, port);
if (!bAddress)
return USB_ERROR_OUT_OF_ADDRESS_SPACE_IN_POOL;
// Extract Max Packet Size from device descriptor
epInfo[0].maxPktSize = (uint8_t)((USB_DEVICE_DESCRIPTOR*)buf)->bMaxPacketSize0;
// Assign new address to the device
rcode = pUsb->setAddr(0, 0, bAddress);
if (rcode) {
p->lowspeed = false;
addrPool.FreeAddress(bAddress);
bAddress = 0;
#ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nsetAddr: "), 0x80);
D_PrintHex<uint8_t > (rcode, 0x80);
#endif
return rcode;
}
#ifdef EXTRADEBUG
Notify(PSTR("\r\nAddr: "), 0x80);
D_PrintHex<uint8_t > (bAddress, 0x80);
#endif
delay(300); // Spec says you should wait at least 200ms
p->lowspeed = false;
//get pointer to assigned address record
p = addrPool.GetUsbDevicePtr(bAddress);
if (!p)
return USB_ERROR_ADDRESS_NOT_FOUND_IN_POOL;
p->lowspeed = lowspeed;
// Assign epInfo to epinfo pointer - only EP0 is known
rcode = pUsb->setEpInfoEntry(bAddress, 1, epInfo);
if (rcode)
goto FailSetDevTblEntry;
/* The application will work in reduced host mode, so we can save program and data
memory space. After verifying the VID we will use known values for the
configuration values for device, interface, endpoints and HID for the XBOX controllers */
/* Initialize data structures for endpoints of device */
epInfo[ XBOX_INPUT_PIPE ].epAddr = 0x01; // XBOX report endpoint
epInfo[ XBOX_INPUT_PIPE ].epAttribs = EP_INTERRUPT;
epInfo[ XBOX_INPUT_PIPE ].bmNakPower = USB_NAK_NOWAIT; // Only poll once for interrupt endpoints
epInfo[ XBOX_INPUT_PIPE ].maxPktSize = EP_MAXPKTSIZE;
epInfo[ XBOX_INPUT_PIPE ].bmSndToggle = bmSNDTOG0;
epInfo[ XBOX_INPUT_PIPE ].bmRcvToggle = bmRCVTOG0;
epInfo[ XBOX_OUTPUT_PIPE ].epAddr = 0x02; // XBOX output endpoint
epInfo[ XBOX_OUTPUT_PIPE ].epAttribs = EP_INTERRUPT;
epInfo[ XBOX_OUTPUT_PIPE ].bmNakPower = USB_NAK_NOWAIT; // Only poll once for interrupt endpoints
epInfo[ XBOX_OUTPUT_PIPE ].maxPktSize = EP_MAXPKTSIZE;
epInfo[ XBOX_OUTPUT_PIPE ].bmSndToggle = bmSNDTOG0;
epInfo[ XBOX_OUTPUT_PIPE ].bmRcvToggle = bmRCVTOG0;
rcode = pUsb->setEpInfoEntry(bAddress, 3, epInfo);
if (rcode)
goto FailSetDevTblEntry;
delay(200); // Give time for address change
rcode = pUsb->setConf(bAddress, epInfo[ XBOX_CONTROL_PIPE ].epAddr, 1);
if (rcode)
goto FailSetConfDescr;
#ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nXbox Controller Connected\r\n"), 0x80);
#endif
if (pFuncOnInit)
pFuncOnInit(); // Call the user function
XboxConnected = true;
bPollEnable = true;
return 0; // Successful configuration
/* Diagnostic messages */
FailGetDevDescr:
#ifdef DEBUG_USB_HOST
NotifyFailGetDevDescr();
goto Fail;
#endif
FailSetDevTblEntry:
#ifdef DEBUG_USB_HOST
NotifyFailSetDevTblEntry();
goto Fail;
#endif
FailSetConfDescr:
#ifdef DEBUG_USB_HOST
NotifyFailSetConfDescr();
goto Fail;
#endif
FailUnknownDevice:
#ifdef DEBUG_USB_HOST
NotifyFailUnknownDevice(VID, PID);
#endif
rcode = USB_DEV_CONFIG_ERROR_DEVICE_NOT_SUPPORTED;
Fail:
#ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nXbox Init Failed, error code: "), 0x80);
NotifyFail(rcode);
#endif
Release();
return rcode;
}
/* Performs a cleanup after failed Init() attempt */
uint8_t XBOXOLD::Release() {
XboxConnected = false;
pUsb->GetAddressPool().FreeAddress(bAddress);
bAddress = 0;
bPollEnable = false;
return 0;
}
uint8_t XBOXOLD::Poll() {
if (!bPollEnable)
return 0;
uint16_t BUFFER_SIZE = EP_MAXPKTSIZE;
pUsb->inTransfer(bAddress, epInfo[ XBOX_INPUT_PIPE ].epAddr, &BUFFER_SIZE, readBuf); // input on endpoint 1
readReport();
#ifdef PRINTREPORT
printReport(BUFFER_SIZE); // Uncomment "#define PRINTREPORT" to print the report send by the Xbox controller
#endif
return 0;
}
void XBOXOLD::readReport() {
ButtonState = readBuf[2];
for (uint8_t i = 0; i < sizeof(buttonValues); i++)
buttonValues[i] = readBuf[i + 4]; // A, B, X, Y, BLACK, WHITE, L1, and R1
hatValue[LeftHatX] = (int16_t)(((uint16_t)readBuf[12] << 8) | readBuf[13]);
hatValue[LeftHatY] = (int16_t)(((uint16_t)readBuf[14] << 8) | readBuf[15]);
hatValue[RightHatX] = (int16_t)(((uint16_t)readBuf[16] << 8) | readBuf[17]);
hatValue[RightHatY] = (int16_t)(((uint16_t)readBuf[18] << 8) | readBuf[19]);
//Notify(PSTR("\r\nButtonState"), 0x80);
//PrintHex<uint8_t>(ButtonState, 0x80);
if (ButtonState != OldButtonState || memcmp(buttonValues, oldButtonValues, sizeof(buttonValues)) != 0) {
ButtonClickState = ButtonState & ~OldButtonState; // Update click state variable
OldButtonState = ButtonState;
for (uint8_t i = 0; i < sizeof(buttonValues); i++) {
if (oldButtonValues[i] == 0 && buttonValues[i] != 0)
buttonClicked[i] = true; // Update A, B, X, Y, BLACK, WHITE, L1, and R1 click state
oldButtonValues[i] = buttonValues[i];
}
}
}
void XBOXOLD::printReport(uint16_t length) { //Uncomment "#define PRINTREPORT" to print the report send by the Xbox controller
#ifdef PRINTREPORT
if (readBuf == NULL)
return;
for (uint8_t i = 0; i < length; i++) {
D_PrintHex<uint8_t > (readBuf[i], 0x80);
Notify(PSTR(" "), 0x80);
}
Notify(PSTR("\r\n"), 0x80);
#endif
}
uint8_t XBOXOLD::getButtonPress(Button b) {
if (b == A || b == B || b == X || b == Y || b == BLACK || b == WHITE || b == L1 || b == R1) // A, B, X, Y, BLACK, WHITE, L1, and R1 are analog buttons
return buttonValues[pgm_read_byte(&XBOXOLDBUTTONS[(uint8_t)b])]; // Analog buttons
return (ButtonState & pgm_read_byte(&XBOXOLDBUTTONS[(uint8_t)b])); // Digital buttons
}
bool XBOXOLD::getButtonClick(Button b) {
uint8_t button;
if (b == A || b == B || b == X || b == Y || b == BLACK || b == WHITE || b == L1 || b == R1) { // A, B, X, Y, BLACK, WHITE, L1, and R1 are analog buttons
button = pgm_read_byte(&XBOXOLDBUTTONS[(uint8_t)b]);
if (buttonClicked[button])
buttonClicked[button] = false;
return buttonClicked[button];
}
button = pgm_read_byte(&XBOXOLDBUTTONS[(uint8_t)b]); // Digital buttons
bool click = (ButtonClickState & button);
ButtonClickState &= ~button; // clear "click" event
return click;
}
int16_t XBOXOLD::getAnalogHat(AnalogHat a) {
return hatValue[a];
}
/* Xbox Controller commands */
void XBOXOLD::XboxCommand(uint8_t* data, uint16_t nbytes) {
//bmRequest = Host to device (0x00) | Class (0x20) | Interface (0x01) = 0x21, bRequest = Set Report (0x09), Report ID (0x00), Report Type (Output 0x02), interface (0x00), datalength, datalength, data)
pUsb->ctrlReq(bAddress, epInfo[XBOX_CONTROL_PIPE].epAddr, bmREQ_HID_OUT, HID_REQUEST_SET_REPORT, 0x00, 0x02, 0x00, nbytes, nbytes, data, NULL);
}
void XBOXOLD::setRumbleOn(uint8_t lValue, uint8_t rValue) {
uint8_t writeBuf[6];
writeBuf[0] = 0x00;
writeBuf[1] = 0x06;
writeBuf[2] = 0x00;
writeBuf[3] = rValue; // small weight
writeBuf[4] = 0x00;
writeBuf[5] = lValue; // big weight
XboxCommand(writeBuf, 6);
}

198
XBOXOLD.h Normal file
View file

@ -0,0 +1,198 @@
/* Copyright (C) 2013 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#ifndef _xboxold_h_
#define _xboxold_h_
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include "Usb.h"
#include "controllerEnums.h"
/* Data Xbox taken from descriptors */
#define EP_MAXPKTSIZE 32 // Max size for data via USB
/* Endpoint types */
#define EP_INTERRUPT 0x03
/* Names we give to the 3 Xbox pipes */
#define XBOX_CONTROL_PIPE 0
#define XBOX_INPUT_PIPE 1
#define XBOX_OUTPUT_PIPE 2
// PID and VID of the different devices
#define XBOX_VID 0x045E // Microsoft Corporation
#define MADCATZ_VID 0x1BAD // For unofficial Mad Catz controllers
#define JOYTECH_VID 0x162E // For unofficial Joytech controllers
#define XBOX_OLD_PID1 0x0202 // Original Microsoft Xbox controller (US)
#define XBOX_OLD_PID2 0x0285 // Original Microsoft Xbox controller (Japan)
#define XBOX_OLD_PID3 0x0287 // Microsoft Microsoft Xbox Controller S
#define XBOX_OLD_PID4 0x0289 // Smaller Microsoft Xbox controller (US)
// Used in control endpoint header for HID Commands
#define bmREQ_HID_OUT USB_SETUP_HOST_TO_DEVICE|USB_SETUP_TYPE_CLASS|USB_SETUP_RECIPIENT_INTERFACE
#define HID_REQUEST_SET_REPORT 0x09
#define XBOX_MAX_ENDPOINTS 3
/** This class implements support for a the original Xbox controller via USB. */
class XBOXOLD : public USBDeviceConfig {
public:
/**
* Constructor for the XBOXOLD class.
* @param pUsb Pointer to USB class instance.
*/
XBOXOLD(USB *pUsb);
/** @name USBDeviceConfig implementation */
/**
* Initialize the Xbox Controller.
* @param parent Hub number.
* @param port Port number on the hub.
* @param lowspeed Speed of the device.
* @return 0 on success.
*/
virtual uint8_t Init(uint8_t parent, uint8_t port, bool lowspeed);
/**
* Release the USB device.
* @return 0 on success.
*/
virtual uint8_t Release();
/**
* Poll the USB Input endpoins and run the state machines.
* @return 0 on success.
*/
virtual uint8_t Poll();
/**
* Get the device address.
* @return The device address.
*/
virtual uint8_t GetAddress() {
return bAddress;
};
/**
* Used to check if the controller has been initialized.
* @return True if it's ready.
*/
virtual bool isReady() {
return bPollEnable;
};
/**
* Used by the USB core to check what this driver support.
* @param vid The device's VID.
* @param pid The device's PID.
* @return Returns true if the device's VID and PID matches this driver.
*/
virtual boolean VIDPIDOK(uint16_t vid, uint16_t pid) {
return ((vid == XBOX_VID || vid == MADCATZ_VID || vid == JOYTECH_VID) && (pid == XBOX_OLD_PID1 || pid == XBOX_OLD_PID2 || pid == XBOX_OLD_PID3 || pid == XBOX_OLD_PID4));
};
/**@}*/
/** @name Xbox Controller functions */
/**
* getButtonPress(Button b) will return true as long as the button is held down.
*
* While getButtonClick(Button b) will only return it once.
*
* So you instance if you need to increase a variable once you would use getButtonClick(Button b),
* but if you need to drive a robot forward you would use getButtonPress(Button b).
* @param b ::Button to read.
* @return getButtonClick(Button b) will return a bool, but getButtonPress(Button b)
* will return a byte if reading ::L2 or ::R2.
*/
uint8_t getButtonPress(Button b);
bool getButtonClick(Button b);
/**@}*/
/** @name Xbox Controller functions */
/**
* Return the analog value from the joysticks on the controller.
* @param a Either ::LeftHatX, ::LeftHatY, ::RightHatX or ::RightHatY.
* @return Returns a signed 16-bit integer.
*/
int16_t getAnalogHat(AnalogHat a);
/** Turn rumble off the controller. */
void setRumbleOff() {
setRumbleOn(0, 0);
};
/**
* Turn rumble on.
* @param lValue Left motor (big weight) inside the controller.
* @param rValue Right motor (small weight) inside the controller.
*/
void setRumbleOn(uint8_t lValue, uint8_t rValue);
/**
* Used to call your own function when the controller is successfully initialized.
* @param funcOnInit Function to call.
*/
void attachOnInit(void (*funcOnInit)(void)) {
pFuncOnInit = funcOnInit;
};
/**@}*/
/** True if a Xbox controller is connected. */
bool XboxConnected;
protected:
/** Pointer to USB class instance. */
USB *pUsb;
/** Device address. */
uint8_t bAddress;
/** Endpoint info structure. */
EpInfo epInfo[XBOX_MAX_ENDPOINTS];
private:
/**
* Called when the controller is successfully initialized.
* Use attachOnInit(void (*funcOnInit)(void)) to call your own function.
* This is useful for instance if you want to set the LEDs in a specific way.
*/
void (*pFuncOnInit)(void); // Pointer to function called in onInit()
bool bPollEnable;
/* Variables to store the digital buttons */
uint8_t ButtonState;
uint8_t OldButtonState;
uint8_t ButtonClickState;
/* Variables to store the analog buttons */
uint8_t buttonValues[8]; // A, B, X, Y, BLACK, WHITE, L1, and R1
uint8_t oldButtonValues[8];
bool buttonClicked[8];
int16_t hatValue[4]; // Joystick values
uint8_t readBuf[EP_MAXPKTSIZE]; // General purpose buffer for input data
void readReport(); // Read incoming data
void printReport(uint16_t length); // Print incoming date
/* Private commands */
void XboxCommand(uint8_t* data, uint16_t nbytes);
};
#endif

View file

@ -94,9 +94,9 @@ uint8_t XBOXRECV::Init(uint8_t parent, uint8_t port, bool lowspeed) {
VID = ((USB_DEVICE_DESCRIPTOR*)buf)->idVendor; VID = ((USB_DEVICE_DESCRIPTOR*)buf)->idVendor;
PID = ((USB_DEVICE_DESCRIPTOR*)buf)->idProduct; PID = ((USB_DEVICE_DESCRIPTOR*)buf)->idProduct;
if (VID != XBOX_VID && VID != MADCATZ_VID) // We just check if it's a xbox receiver using the Vendor ID if (VID != XBOX_VID && VID != MADCATZ_VID) // We just check if it's a Xbox receiver using the Vendor ID
goto FailUnknownDevice; goto FailUnknownDevice;
else if (PID != XBOX_WIRELESS_RECEIVER_PID && PID != XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID) { else if (PID != XBOX_WIRELESS_RECEIVER_PID && PID != XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID) { // Check the PID as well
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nYou'll need a wireless receiver for this libary to work"), 0x80); Notify(PSTR("\r\nYou'll need a wireless receiver for this libary to work"), 0x80);
#endif #endif
@ -128,6 +128,8 @@ uint8_t XBOXRECV::Init(uint8_t parent, uint8_t port, bool lowspeed) {
Notify(PSTR("\r\nAddr: "), 0x80); Notify(PSTR("\r\nAddr: "), 0x80);
D_PrintHex<uint8_t > (bAddress, 0x80); D_PrintHex<uint8_t > (bAddress, 0x80);
#endif #endif
delay(300); // Spec says you should wait at least 200ms
p->lowspeed = false; p->lowspeed = false;
//get pointer to assigned address record //get pointer to assigned address record
@ -310,7 +312,7 @@ void XBOXRECV::readReport(uint8_t controller) {
#endif #endif
if (Xbox360Connected[controller]) { if (Xbox360Connected[controller]) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
char* str = 0; const char* str = 0;
switch (readBuf[1]) { switch (readBuf[1]) {
case 0x80: str = PSTR(" as controller\r\n"); case 0x80: str = PSTR(" as controller\r\n");
break; break;
@ -322,18 +324,7 @@ void XBOXRECV::readReport(uint8_t controller) {
Notify(PSTR(": connected"), 0x80); Notify(PSTR(": connected"), 0x80);
Notify(str, 0x80); Notify(str, 0x80);
#endif #endif
LED led; onInit(controller);
switch (controller) {
case 0: led = LED1;
break;
case 1: led = LED2;
break;
case 2: led = LED3;
break;
case 3: led = LED4;
break;
}
setLedOn(led, controller);
} }
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
else else
@ -529,3 +520,20 @@ void XBOXRECV::setRumbleOn(uint8_t lValue, uint8_t rValue, uint8_t controller) {
XboxCommand(controller, writeBuf, 7); XboxCommand(controller, writeBuf, 7);
} }
void XBOXRECV::onInit(uint8_t controller) {
if (pFuncOnInit)
pFuncOnInit(); // Call the user function
else {
LED led;
if (controller == 0)
led = LED1;
else if (controller == 1)
led = LED2;
else if (controller == 2)
led = LED3;
else
led = LED4;
setLedOn(led, controller);
}
}

View file

@ -48,11 +48,12 @@
// PID and VID of the different devices // PID and VID of the different devices
#define XBOX_VID 0x045E // Microsoft Corporation #define XBOX_VID 0x045E // Microsoft Corporation
#define MADCATZ_VID 0x1BAD // For unofficial Mad Catz receivers
#define JOYTECH_VID 0x162E // For unofficial Joytech controllers
#define XBOX_WIRELESS_RECEIVER_PID 0x0719 // Microsoft Wireless Gaming Receiver #define XBOX_WIRELESS_RECEIVER_PID 0x0719 // Microsoft Wireless Gaming Receiver
#define XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID 0x0291 // Third party Wireless Gaming Receiver #define XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID 0x0291 // Third party Wireless Gaming Receiver
#define MADCATZ_VID 0x1BAD // For unofficial Mad Catz receivers
#define XBOX_MAX_ENDPOINTS 9 #define XBOX_MAX_ENDPOINTS 9
/** /**
@ -103,6 +104,16 @@ public:
virtual bool isReady() { virtual bool isReady() {
return bPollEnable; return bPollEnable;
}; };
/**
* Used by the USB core to check what this driver support.
* @param vid The device's VID.
* @param pid The device's PID.
* @return Returns true if the device's VID and PID matches this driver.
*/
virtual boolean VIDPIDOK(uint16_t vid, uint16_t pid) {
return ((vid == XBOX_VID || vid == MADCATZ_VID || vid == JOYTECH_VID) && (pid == XBOX_WIRELESS_RECEIVER_PID || pid == XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID));
};
/**@}*/ /**@}*/
/** @name Xbox Controller functions */ /** @name Xbox Controller functions */
@ -200,6 +211,14 @@ public:
* @return True if a button has changed. * @return True if a button has changed.
*/ */
bool buttonChanged(uint8_t controller = 0); bool buttonChanged(uint8_t controller = 0);
/**
* Used to call your own function when the controller is successfully initialized.
* @param funcOnInit Function to call.
*/
void attachOnInit(void (*funcOnInit)(void)) {
pFuncOnInit = funcOnInit;
};
/**@}*/ /**@}*/
/** True if a wireless receiver is connected. */ /** True if a wireless receiver is connected. */
@ -216,6 +235,15 @@ protected:
EpInfo epInfo[XBOX_MAX_ENDPOINTS]; EpInfo epInfo[XBOX_MAX_ENDPOINTS];
private: private:
/**
* Called when the controller is successfully initialized.
* Use attachOnInit(void (*funcOnInit)(void)) to call your own function.
* This is useful for instance if you want to set the LEDs in a specific way.
* @param controller The initialized controller.
*/
void onInit(uint8_t controller);
void (*pFuncOnInit)(void); // Pointer to function called in onInit()
bool bPollEnable; bool bPollEnable;
/* Variables to store the buttons */ /* Variables to store the buttons */
@ -232,7 +260,7 @@ private:
unsigned long timer; // Timing for checkStatus() signals unsigned long timer; // Timing for checkStatus() signals
uint8_t readBuf[EP_MAXPKTSIZE]; // General purpose buffer for input data uint8_t readBuf[EP_MAXPKTSIZE]; // General purpose buffer for input data
uint8_t writeBuf[EP_MAXPKTSIZE]; // General purpose buffer for output data uint8_t writeBuf[7]; // General purpose buffer for output data
void readReport(uint8_t controller); // read incoming data void readReport(uint8_t controller); // read incoming data
void printReport(uint8_t controller, uint8_t nBytes); // print incoming date - Uncomment for debugging void printReport(uint8_t controller, uint8_t nBytes); // print incoming date - Uncomment for debugging

View file

@ -92,7 +92,7 @@ uint8_t XBOXUSB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
VID = ((USB_DEVICE_DESCRIPTOR*)buf)->idVendor; VID = ((USB_DEVICE_DESCRIPTOR*)buf)->idVendor;
PID = ((USB_DEVICE_DESCRIPTOR*)buf)->idProduct; PID = ((USB_DEVICE_DESCRIPTOR*)buf)->idProduct;
if (VID != XBOX_VID && VID != MADCATZ_VID && VID != JOYTECH_VID) // We just check if it's a xbox controller using the Vendor ID if (VID != XBOX_VID && VID != MADCATZ_VID && VID != JOYTECH_VID) // Check VID
goto FailUnknownDevice; goto FailUnknownDevice;
if (PID == XBOX_WIRELESS_PID) { if (PID == XBOX_WIRELESS_PID) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
@ -104,7 +104,8 @@ uint8_t XBOXUSB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
Notify(PSTR("\r\nThis library only supports Xbox 360 controllers via USB"), 0x80); Notify(PSTR("\r\nThis library only supports Xbox 360 controllers via USB"), 0x80);
#endif #endif
goto FailUnknownDevice; goto FailUnknownDevice;
} } else if (PID != XBOX_WIRED_PID) // Check PID
goto FailUnknownDevice;
// Allocate new address according to device class // Allocate new address according to device class
bAddress = addrPool.AllocAddress(parent, false, port); bAddress = addrPool.AllocAddress(parent, false, port);
@ -123,14 +124,16 @@ uint8_t XBOXUSB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
bAddress = 0; bAddress = 0;
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nsetAddr: "), 0x80); Notify(PSTR("\r\nsetAddr: "), 0x80);
#endif
D_PrintHex<uint8_t > (rcode, 0x80); D_PrintHex<uint8_t > (rcode, 0x80);
#endif
return rcode; return rcode;
} }
#ifdef EXTRADEBUG #ifdef EXTRADEBUG
Notify(PSTR("\r\nAddr: "), 0x80); Notify(PSTR("\r\nAddr: "), 0x80);
D_PrintHex<uint8_t > (bAddress, 0x80); D_PrintHex<uint8_t > (bAddress, 0x80);
#endif #endif
delay(300); // Spec says you should wait at least 200ms
p->lowspeed = false; p->lowspeed = false;
//get pointer to assigned address record //get pointer to assigned address record
@ -176,12 +179,12 @@ uint8_t XBOXUSB::Init(uint8_t parent, uint8_t port, bool lowspeed) {
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
Notify(PSTR("\r\nXbox 360 Controller Connected\r\n"), 0x80); Notify(PSTR("\r\nXbox 360 Controller Connected\r\n"), 0x80);
#endif #endif
setLedOn(LED1); onInit();
Xbox360Connected = true; Xbox360Connected = true;
bPollEnable = true; bPollEnable = true;
return 0; // successful configuration return 0; // Successful configuration
/* diagnostic messages */ /* Diagnostic messages */
FailGetDevDescr: FailGetDevDescr:
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
NotifyFailGetDevDescr(); NotifyFailGetDevDescr();
@ -345,3 +348,10 @@ void XBOXUSB::setRumbleOn(uint8_t lValue, uint8_t rValue) {
XboxCommand(writeBuf, 8); XboxCommand(writeBuf, 8);
} }
void XBOXUSB::onInit() {
if (pFuncOnInit)
pFuncOnInit(); // Call the user function
else
setLedOn(LED1);
}

View file

@ -40,13 +40,14 @@
// PID and VID of the different devices // PID and VID of the different devices
#define XBOX_VID 0x045E // Microsoft Corporation #define XBOX_VID 0x045E // Microsoft Corporation
#define MADCATZ_VID 0x1BAD // For unofficial Mad Catz controllers
#define JOYTECH_VID 0x162E // For unofficial Joytech controllers
#define XBOX_WIRED_PID 0x028E // Microsoft 360 Wired controller
#define XBOX_WIRELESS_PID 0x028F // Wireless controller only support charging #define XBOX_WIRELESS_PID 0x028F // Wireless controller only support charging
#define XBOX_WIRELESS_RECEIVER_PID 0x0719 // Microsoft Wireless Gaming Receiver #define XBOX_WIRELESS_RECEIVER_PID 0x0719 // Microsoft Wireless Gaming Receiver
#define XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID 0x0291 // Third party Wireless Gaming Receiver #define XBOX_WIRELESS_RECEIVER_THIRD_PARTY_PID 0x0291 // Third party Wireless Gaming Receiver
#define MADCATZ_VID 0x1BAD // For unofficial Mad Catz controllers
#define JOYTECH_VID 0x162E // For unofficial Joytech controllers
#define XBOX_REPORT_BUFFER_SIZE 14 // Size of the input report buffer #define XBOX_REPORT_BUFFER_SIZE 14 // Size of the input report buffer
// Used in control endpoint header for HID Commands // Used in control endpoint header for HID Commands
@ -99,6 +100,16 @@ public:
virtual bool isReady() { virtual bool isReady() {
return bPollEnable; return bPollEnable;
}; };
/**
* Used by the USB core to check what this driver support.
* @param vid The device's VID.
* @param pid The device's PID.
* @return Returns true if the device's VID and PID matches this driver.
*/
virtual boolean VIDPIDOK(uint16_t vid, uint16_t pid) {
return ((vid == XBOX_VID || vid == MADCATZ_VID || vid == JOYTECH_VID) && pid == XBOX_WIRED_PID);
};
/**@}*/ /**@}*/
/** @name Xbox Controller functions */ /** @name Xbox Controller functions */
@ -168,6 +179,14 @@ public:
* @param lm See ::LEDMode. * @param lm See ::LEDMode.
*/ */
void setLedMode(LEDMode lm); void setLedMode(LEDMode lm);
/**
* Used to call your own function when the controller is successfully initialized.
* @param funcOnInit Function to call.
*/
void attachOnInit(void (*funcOnInit)(void)) {
pFuncOnInit = funcOnInit;
};
/**@}*/ /**@}*/
/** True if a Xbox 360 controller is connected. */ /** True if a Xbox 360 controller is connected. */
@ -182,6 +201,14 @@ protected:
EpInfo epInfo[XBOX_MAX_ENDPOINTS]; EpInfo epInfo[XBOX_MAX_ENDPOINTS];
private: private:
/**
* Called when the controller is successfully initialized.
* Use attachOnInit(void (*funcOnInit)(void)) to call your own function.
* This is useful for instance if you want to set the LEDs in a specific way.
*/
void onInit();
void (*pFuncOnInit)(void); // Pointer to function called in onInit()
bool bPollEnable; bool bPollEnable;
/* Variables to store the buttons */ /* Variables to store the buttons */
@ -195,7 +222,7 @@ private:
bool R2Clicked; bool R2Clicked;
uint8_t readBuf[EP_MAXPKTSIZE]; // General purpose buffer for input data uint8_t readBuf[EP_MAXPKTSIZE]; // General purpose buffer for input data
uint8_t writeBuf[EP_MAXPKTSIZE]; // General purpose buffer for output data uint8_t writeBuf[8]; // General purpose buffer for output data
void readReport(); // read incoming data void readReport(); // read incoming data
void printReport(); // print incoming date - Uncomment for debugging void printReport(); // print incoming date - Uncomment for debugging

20
adk.cpp
View file

@ -58,14 +58,18 @@ ready(false) {
} }
} }
uint8_t ADK::ConfigureDevice(uint8_t parent, uint8_t port, bool lowspeed) {
return Init(parent, port, lowspeed); // Just call Init. Yes, really!
}
/* Connection initialization of an Android phone */ /* Connection initialization of an Android phone */
uint8_t ADK::Init(uint8_t parent, uint8_t port, bool lowspeed) { uint8_t ADK::Init(uint8_t parent, uint8_t port, bool lowspeed) {
uint8_t buf[sizeof (USB_DEVICE_DESCRIPTOR)]; uint8_t buf[sizeof (USB_DEVICE_DESCRIPTOR)];
uint8_t rcode; uint8_t rcode;
uint8_t num_of_conf; // number of configurations
UsbDevice *p = NULL; UsbDevice *p = NULL;
EpInfo *oldep_ptr = NULL; EpInfo *oldep_ptr = NULL;
uint8_t num_of_conf; // number of configurations
// get memory address of USB device address pool // get memory address of USB device address pool
AddressPool &addrPool = pUsb->GetAddressPool(); AddressPool &addrPool = pUsb->GetAddressPool();
@ -114,7 +118,6 @@ uint8_t ADK::Init(uint8_t parent, uint8_t port, bool lowspeed) {
// Extract Max Packet Size from device descriptor // Extract Max Packet Size from device descriptor
epInfo[0].maxPktSize = (uint8_t)((USB_DEVICE_DESCRIPTOR*)buf)->bMaxPacketSize0; epInfo[0].maxPktSize = (uint8_t)((USB_DEVICE_DESCRIPTOR*)buf)->bMaxPacketSize0;
// Assign new address to the device // Assign new address to the device
rcode = pUsb->setAddr(0, 0, bAddress); rcode = pUsb->setAddr(0, 0, bAddress);
if (rcode) { if (rcode) {
@ -126,6 +129,8 @@ uint8_t ADK::Init(uint8_t parent, uint8_t port, bool lowspeed) {
}//if (rcode... }//if (rcode...
//USBTRACE2("\r\nAddr:", bAddress); //USBTRACE2("\r\nAddr:", bAddress);
// Spec says you should wait at least 200ms.
delay(300);
p->lowspeed = false; p->lowspeed = false;
@ -222,31 +227,32 @@ uint8_t ADK::Init(uint8_t parent, uint8_t port, bool lowspeed) {
if (rcode) { if (rcode) {
goto FailSwAcc; //init fails goto FailSwAcc; //init fails
} }
rcode = -1; rcode = USB_ERROR_CONFIG_REQUIRES_ADDITIONAL_RESET;
delay(1000); // Give Android a chance to do its reset. This is a guess, and possibly could be lower.
goto SwAttempt; //switch to accessory mode attempted goto SwAttempt; //switch to accessory mode attempted
/* diagnostic messages */ /* diagnostic messages */
FailGetDevDescr: FailGetDevDescr:
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
NotifyFailGetDevDescr(); NotifyFailGetDevDescr(rcode);
goto Fail; goto Fail;
#endif #endif
FailSetDevTblEntry: FailSetDevTblEntry:
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
NotifyFailSetDevTblEntry(); NotifyFailSetDevTblEntry(rcode);
goto Fail; goto Fail;
#endif #endif
FailGetConfDescr: FailGetConfDescr:
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
NotifyFailGetConfDescr(); NotifyFailGetConfDescr(rcode);
goto Fail; goto Fail;
#endif #endif
FailSetConfDescr: FailSetConfDescr:
#ifdef DEBUG_USB_HOST #ifdef DEBUG_USB_HOST
NotifyFailSetConfDescr(); NotifyFailSetConfDescr(rcode);
goto Fail; goto Fail;
#endif #endif

5
adk.h
View file

@ -110,6 +110,7 @@ public:
// USBDeviceConfig implementation // USBDeviceConfig implementation
virtual uint8_t ConfigureDevice(uint8_t parent, uint8_t port, bool lowspeed);
virtual uint8_t Init(uint8_t parent, uint8_t port, bool lowspeed); virtual uint8_t Init(uint8_t parent, uint8_t port, bool lowspeed);
virtual uint8_t Release(); virtual uint8_t Release();
@ -125,6 +126,10 @@ public:
return ready; return ready;
}; };
virtual boolean VIDPIDOK(uint16_t vid, uint16_t pid) {
return (vid == ADK_VID && (pid == ADK_PID || pid == ADB_PID));
};
//UsbConfigXtracter implementation //UsbConfigXtracter implementation
virtual void EndpointXtract(uint8_t conf, uint8_t iface, uint8_t alt, uint8_t proto, const USB_ENDPOINT_DESCRIPTOR *ep); virtual void EndpointXtract(uint8_t conf, uint8_t iface, uint8_t alt, uint8_t proto, const USB_ENDPOINT_DESCRIPTOR *ep);
}; //class ADK : public USBDeviceConfig ... }; //class ADK : public USBDeviceConfig ...

View file

@ -100,6 +100,8 @@ enum Button {
Y = 15, Y = 15,
XBOX = 16, XBOX = 16,
SYNC = 17, SYNC = 17,
BLACK = 8, // Available on the original Xbox controller
WHITE = 9, // Available on the original Xbox controller
/**@}*/ /**@}*/
}; };

View file

@ -11,10 +11,13 @@ BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so
PS3BT *PS3[2]; // We will use this pointer to store the two instance, you can easily make it larger if you like, but it will use a lot of RAM! PS3BT *PS3[2]; // We will use this pointer to store the two instance, you can easily make it larger if you like, but it will use a lot of RAM!
const uint8_t length = sizeof(PS3)/sizeof(PS3[0]); // Get the lenght of the array const uint8_t length = sizeof(PS3)/sizeof(PS3[0]); // Get the lenght of the array
boolean printAngle[length]; boolean printAngle[length];
boolean oldControllerState[length];
void setup() { void setup() {
for(uint8_t i=0;i<length;i++) for (uint8_t i=0;i<length;i++) {
PS3[i] = new PS3BT(&Btd); // Create the instances PS3[i] = new PS3BT(&Btd); // Create the instances
PS3[i]->attachOnInit(onInit); // onInit() is called upon a new connection - you can call the function whatever you like
}
Serial.begin(115200); Serial.begin(115200);
if (Usb.Init() == -1) { if (Usb.Init() == -1) {
@ -52,6 +55,7 @@ void loop() {
if(PS3[i]->getButtonClick(PS)) { if(PS3[i]->getButtonClick(PS)) {
Serial.print(F("\r\nPS")); Serial.print(F("\r\nPS"));
PS3[i]->disconnect(); PS3[i]->disconnect();
oldControllerState[i] = false; // Reset value
} }
else { else {
if(PS3[i]->getButtonClick(TRIANGLE)) if(PS3[i]->getButtonClick(TRIANGLE))
@ -121,3 +125,12 @@ void loop() {
//else if(PS3[i]->PS3MoveConnected) { //else if(PS3[i]->PS3MoveConnected) {
} }
} }
void onInit() {
for (uint8_t i=0;i<length;i++) {
if ((PS3[i]->PS3Connected || PS3[i]->PS3NavigationConnected) && !oldControllerState[i]) {
oldControllerState[i] = true; // Used to check which is the new controller
PS3[i]->setLedOn((LED)i); // Cast directly to LED enum - see: "controllerEnums.h"
}
}
}

View file

@ -2,13 +2,13 @@
Example sketch for the Wii libary showing the IR camera functionality. This example Example sketch for the Wii libary showing the IR camera functionality. This example
is for the Bluetooth Wii library developed for the USB shield from Circuits@Home is for the Bluetooth Wii library developed for the USB shield from Circuits@Home
Created by Allan Glover and includes much from what Kristian Lauszus wrote in the existing Created by Allan Glover and Kristian Lauszus.
Wii example. Contact Kristian: http://blog.tkjelectronics.dk/ or send email at kristianl@tkjelectronics.com. Contact Kristian: http://blog.tkjelectronics.dk/ or send an email at kristianl@tkjelectronics.com.
Contact Allan at adglover9.81@gmail.com Contact Allan at adglover9.81@gmail.com
To test the Wiimote IR camera, you will need access to an IR source. Sunlight will work but is not ideal. To test the Wiimote IR camera, you will need access to an IR source. Sunlight will work but is not ideal.
The simpleist solution is to use the Wii sensor bar, i.e. emitter bar, supplied by the Wii system. Otherwise, The simpleist solution is to use the Wii sensor bar, i.e. emitter bar, supplied by the Wii system.
wire up a IR LED yourself. Otherwise, wire up a IR LED yourself.
*/ */
#include <Wii.h> #include <Wii.h>
@ -19,7 +19,7 @@ USB Usb;
BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so
/* You can create the instance of the class in two ways */ /* You can create the instance of the class in two ways */
WII Wii(&Btd,PAIR); // This will start an inquiry and then pair with your Wiimote - you only have to do this once WII Wii(&Btd,PAIR); // This will start an inquiry and then pair with your Wiimote - you only have to do this once
//WII Wii(&Btd); // After the wiimote pairs once with the line of code above, you can simply create the instance like so and re upload and then press any button on the Wiimote //WII Wii(&Btd); // After the Wiimote pairs once with the line of code above, you can simply create the instance like so and re upload and then press any button on the Wiimote
bool printAngle; bool printAngle;
uint8_t printObjects; uint8_t printObjects;
@ -109,7 +109,7 @@ void loop() {
} }
} }
} }
if(printAngle) { // There is no extension bytes avaliable, so the Motionplus or Nunchuck can't be read if(printAngle) { // There is no extension bytes available, so the MotionPlus or Nunchuck can't be read
Serial.print(F("\r\nPitch: ")); Serial.print(F("\r\nPitch: "));
Serial.print(Wii.getPitch()); Serial.print(Wii.getPitch());
Serial.print(F("\tRoll: ")); Serial.print(F("\tRoll: "));

View file

@ -10,11 +10,14 @@ USB Usb;
BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so
WII *Wii[2]; // We will use this pointer to store the two instance, you can easily make it larger if you like, but it will use a lot of RAM! WII *Wii[2]; // We will use this pointer to store the two instance, you can easily make it larger if you like, but it will use a lot of RAM!
const uint8_t length = sizeof(Wii)/sizeof(Wii[0]); // Get the lenght of the array const uint8_t length = sizeof(Wii)/sizeof(Wii[0]); // Get the lenght of the array
bool printAngle[length]; boolean printAngle[length];
boolean oldControllerState[length];
void setup() { void setup() {
for(uint8_t i=0;i<length;i++) for (uint8_t i=0;i<length;i++) {
Wii[i] = new WII(&Btd); // You will have to pair each controller with the dongle before you can define the instances like so, just add PAIR as the second argument Wii[i] = new WII(&Btd); // You will have to pair each controller with the dongle before you can define the instances like so, just add PAIR as the second argument
Wii[i]->attachOnInit(onInit); // onInit() is called upon a new connection - you can call the function whatever you like
}
Serial.begin(115200); Serial.begin(115200);
if (Usb.Init() == -1) { if (Usb.Init() == -1) {
@ -31,7 +34,7 @@ void loop() {
if(Wii[i]->getButtonClick(HOME)) { // You can use getButtonPress to see if the button is held down if(Wii[i]->getButtonClick(HOME)) { // You can use getButtonPress to see if the button is held down
Serial.print(F("\r\nHOME")); Serial.print(F("\r\nHOME"));
Wii[i]->disconnect(); Wii[i]->disconnect();
delay(1000); // This delay is needed for some Wiimotes, so it doesn't try to reconnect right away oldControllerState[i] = false; // Reset value
} }
else { else {
if(Wii[i]->getButtonClick(LEFT)) { if(Wii[i]->getButtonClick(LEFT)) {
@ -105,3 +108,12 @@ void loop() {
} }
} }
} }
void onInit() {
for (uint8_t i=0;i<length;i++) {
if (Wii[i]->wiimoteConnected && !oldControllerState[i]) {
oldControllerState[i] = true; // Used to check which is the new controller
Wii[i]->setLedOn((LED)i); // Cast directly to LED enum - see: "controllerEnums.h"
}
}
}

View file

@ -0,0 +1,100 @@
/*
Example sketch for the original Xbox library - developed by Kristian Lauszus
For more information visit my blog: http://blog.tkjelectronics.dk/ or
send me an e-mail: kristianl@tkjelectronics.com
*/
#include <XBOXOLD.h>
#include <usbhub.h>
USB Usb;
USBHub Hub1(&Usb); // The controller has a built in hub, so this instance is needed
XBOXOLD Xbox(&Usb);
void setup() {
Serial.begin(115200);
if (Usb.Init() == -1) {
Serial.print(F("\r\nOSC did not start"));
while(1); // halt
}
Serial.print(F("\r\nXBOX Library Started"));
}
void loop() {
Usb.Task();
if(Xbox.XboxConnected) {
if(Xbox.getButtonPress(BLACK) || Xbox.getButtonPress(WHITE)) {
Serial.print("BLACK: ");
Serial.print(Xbox.getButtonPress(BLACK));
Serial.print("\tWHITE: ");
Serial.println(Xbox.getButtonPress(WHITE));
Xbox.setRumbleOn(Xbox.getButtonPress(BLACK),Xbox.getButtonPress(WHITE));
} else
Xbox.setRumbleOn(0,0);
if(Xbox.getAnalogHat(LeftHatX) > 7500 || Xbox.getAnalogHat(LeftHatX) < -7500 || Xbox.getAnalogHat(LeftHatY) > 7500 || Xbox.getAnalogHat(LeftHatY) < -7500 || Xbox.getAnalogHat(RightHatX) > 7500 || Xbox.getAnalogHat(RightHatX) < -7500 || Xbox.getAnalogHat(RightHatY) > 7500 || Xbox.getAnalogHat(RightHatY) < -7500) {
if(Xbox.getAnalogHat(LeftHatX) > 7500 || Xbox.getAnalogHat(LeftHatX) < -7500) {
Serial.print(F("LeftHatX: "));
Serial.print(Xbox.getAnalogHat(LeftHatX));
Serial.print("\t");
}
if(Xbox.getAnalogHat(LeftHatY) > 7500 || Xbox.getAnalogHat(LeftHatY) < -7500) {
Serial.print(F("LeftHatY: "));
Serial.print(Xbox.getAnalogHat(LeftHatY));
Serial.print("\t");
}
if(Xbox.getAnalogHat(RightHatX) > 7500 || Xbox.getAnalogHat(RightHatX) < -7500) {
Serial.print(F("RightHatX: "));
Serial.print(Xbox.getAnalogHat(RightHatX));
Serial.print("\t");
}
if(Xbox.getAnalogHat(RightHatY) > 7500 || Xbox.getAnalogHat(RightHatY) < -7500) {
Serial.print(F("RightHatY: "));
Serial.print(Xbox.getAnalogHat(RightHatY));
}
Serial.println();
}
if(Xbox.getButtonClick(UP))
Serial.println(F("Up"));
if(Xbox.getButtonClick(DOWN))
Serial.println(F("Down"));
if(Xbox.getButtonClick(LEFT))
Serial.println(F("Left"));
if(Xbox.getButtonClick(RIGHT))
Serial.println(F("Right"));
if(Xbox.getButtonClick(START))
Serial.println(F("Start"));
if(Xbox.getButtonClick(BACK))
Serial.println(F("Back"));
if(Xbox.getButtonClick(L3))
Serial.println(F("L3"));
if(Xbox.getButtonClick(R3))
Serial.println(F("R3"));
if(Xbox.getButtonPress(A)) {
Serial.print(F("A: "));
Serial.println(Xbox.getButtonPress(A));
}
if(Xbox.getButtonPress(B)) {
Serial.print(F("B: "));
Serial.println(Xbox.getButtonPress(B));
}
if(Xbox.getButtonPress(X)) {
Serial.print(F("X: "));
Serial.println(Xbox.getButtonPress(X));
}
if(Xbox.getButtonPress(Y)) {
Serial.print(F("Y: "));
Serial.println(Xbox.getButtonPress(Y));
}
if(Xbox.getButtonPress(L1)) {
Serial.print(F("L1: "));
Serial.println(Xbox.getButtonPress(L1));
}
if(Xbox.getButtonPress(R1)) {
Serial.print(F("R1: "));
Serial.println(Xbox.getButtonPress(R1));
}
}
delay(1);
}

@ -1 +1 @@
Subproject commit f379bae02aa3d9c3da558ba2041558b88db95bbb Subproject commit 76e5edb248b9078916cf46bdd4fd1a9e8201ca64

@ -1 +1 @@
Subproject commit 071b65b923b2656bb1e1b622de5272b4ed9a4996 Subproject commit e717f2df099491439877cc0d44a660688685dd54

View file

@ -30,6 +30,7 @@
#if WANT_HUB_TEST #if WANT_HUB_TEST
#include <usbhub.h> #include <usbhub.h>
#endif #endif
#include <RTClib.h>
#include <masstorage.h> #include <masstorage.h>
#include <message.h> #include <message.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
@ -41,9 +42,12 @@
#if HAVE_XMEM #if HAVE_XMEM
#define GOD_MODE 0 #define GOD_MODE 0
#endif #endif
static FILE mystdout; static FILE tty_stdio;
static FILE tty_stderr;
USB Usb;
#define LED 13 // the pin that the LED is attached to
int led = 13; // the pin that the LED is attached to
volatile int brightness = 0; // how bright the LED is volatile int brightness = 0; // how bright the LED is
volatile int fadeAmount = 80; // how many points to fade the LED by volatile int fadeAmount = 80; // how many points to fade the LED by
volatile uint8_t current_state = 1; volatile uint8_t current_state = 1;
@ -63,13 +67,18 @@ PCPartition *PT;
#if WANT_HUB_TEST #if WANT_HUB_TEST
#define MAX_HUBS 2 #define MAX_HUBS 2
static USBHub *Hubs[MAX_HUBS]; USBHub *Hubs[MAX_HUBS];
#endif #endif
static PFAT *Fats[_VOLUMES]; static PFAT *Fats[_VOLUMES];
static part_t parts[_VOLUMES]; static part_t parts[_VOLUMES];
static storage_t sto[_VOLUMES]; static storage_t sto[_VOLUMES];
/*make sure this is a power of two. */
#define mbxs 128
static uint8_t My_Buff_x[mbxs]; /* File read buffer */
#define prescale1 ((1 << WGM12) | (1 << CS10)) #define prescale1 ((1 << WGM12) | (1 << CS10))
#define prescale8 ((1 << WGM12) | (1 << CS11)) #define prescale8 ((1 << WGM12) | (1 << CS11))
#define prescale64 ((1 << WGM12) | (1 << CS10) | (1 << CS11)) #define prescale64 ((1 << WGM12) | (1 << CS10) | (1 << CS11))
@ -78,85 +87,99 @@ static storage_t sto[_VOLUMES];
extern "C" unsigned int freeHeap(); extern "C" unsigned int freeHeap();
/* static int tty_stderr_putc(char c, FILE *t) {
unsigned int getHeapend(){ USB_HOST_SERIAL.write(c);
extern unsigned int __heap_start;
if ((unsigned int)__brkval == 0) {
return (unsigned int)&__heap_start;
} else {
return (unsigned int)__brkval;
}
} }
unsigned int freeHeap() { static int tty_std_putc(char c, FILE *t) {
if (SP < (unsigned int)__malloc_heap_start) {
return ((unsigned int)__malloc_heap_end - getHeapend());
} else {
return (SP - getHeapend());
}
}
*/
static int my_putc(char c, FILE *t) {
Serial.write(c); Serial.write(c);
} }
static int tty_std_getc(FILE *t) {
while (!Serial.available());
return Serial.read();
}
void setup() { void setup() {
boolean serr = false;
for (int i = 0; i < _VOLUMES; i++) { for (int i = 0; i < _VOLUMES; i++) {
Fats[i] = NULL; Fats[i] = NULL;
sto[i].private_data = new pvt_t;
((pvt_t *)sto[i].private_data)->B = 255; // impossible
} }
// Set this to higher values to enable more debug information // Set this to higher values to enable more debug information
// minimum 0x00, maximum 0xff // minimum 0x00, maximum 0xff
UsbDEBUGlvl = 0x51; UsbDEBUGlvl = 0x51;
// declare pin 9 to be an output: // make LED pin as an output:
pinMode(led, OUTPUT); pinMode(LED, OUTPUT);
pinMode(2, OUTPUT); pinMode(2, OUTPUT);
// Ensure TX is off
_SFR_BYTE(UCSR0B) &= ~_BV(TXEN0);
// Initialize 'debug' serial port // Initialize 'debug' serial port
USB_HOST_SERIAL.begin(115200);
// Do not start primary Serial port if already started.
if (bit_is_clear(UCSR0B, TXEN0)) {
Serial.begin(115200); Serial.begin(115200);
serr = true;
}
//fdevopen(&my_putc, 0); // Set up stdio/stderr
// too bad we can't tinker with iob directly, oh well. tty_stdio.put = tty_std_putc;
mystdout.put = my_putc; tty_stdio.get = tty_std_getc;
mystdout.get = NULL; tty_stdio.flags = _FDEV_SETUP_RW;
mystdout.flags = _FDEV_SETUP_WRITE; tty_stdio.udata = 0;
mystdout.udata = 0; stdout = &tty_stdio;
stdout = &mystdout; stdin = &tty_stdio;
// Blink pin 9: tty_stderr.put = tty_stderr_putc;
tty_stderr.get = NULL;
tty_stderr.flags = _FDEV_SETUP_WRITE;
tty_stderr.udata = 0;
stderr = &tty_stderr;
// Blink LED
delay(500); delay(500);
analogWrite(led, 255); analogWrite(LED, 255);
delay(500); delay(500);
analogWrite(led, 0); analogWrite(LED, 0);
delay(500); delay(500);
analogWrite(led, 255);
delay(500);
analogWrite(led, 0);
delay(500);
analogWrite(led, 255);
delay(500);
analogWrite(led, 0);
printf_P(PSTR("\r\n\n\n\n\n\n\n\n\n\n\n\n\n\n\nStart\r\n")); printf_P(PSTR("\r\n\n\n\n\n\n\n\n\n\n\n\n\n\n\nStart\r\n"));
printf_P(PSTR("Current UsbDEBUGlvl %02x\r\n"), UsbDEBUGlvl); printf_P(PSTR("Current UsbDEBUGlvl %02x\r\n"), UsbDEBUGlvl);
printf_P(PSTR("'+' and '-' increase/decrease by 0x01\r\n")); printf_P(PSTR("'+' and '-' increase/decrease by 0x01\r\n"));
printf_P(PSTR("'.' and ',' increase/decrease by 0x10\r\n")); printf_P(PSTR("'.' and ',' increase/decrease by 0x10\r\n"));
printf_P(PSTR("'t' will run a 10MB write/read test and print out the time it took.\r\n")); printf_P(PSTR("'t' will run a 10MB write/read test and print out the time it took.\r\n"));
printf_P(PSTR("'e' will toggle vbus off for a few moments.\r\n")); printf_P(PSTR("'e' will toggle vbus off for a few moments.\r\n\r\n"));
printf_P(PSTR("\r\n\r\nLong filename support: " printf_P(PSTR("Long filename support: "
#if _USE_LFN #if _USE_LFN
"Enabled" "Enabled"
#else #else
"Disabled" "Disabled"
#endif #endif
"\r\n")); "\r\n"));
analogWrite(led, 255); if (serr) {
fprintf_P(stderr, PSTR("\r\n\n\n\n\n\n\n\n\n\n\n\n\n\n\nStart\r\n"));
fprintf_P(stderr, PSTR("Current UsbDEBUGlvl %02x\r\n"), UsbDEBUGlvl);
fprintf_P(stderr, PSTR("Long filename support: "
#if _USE_LFN
"Enabled"
#else
"Disabled"
#endif
"\r\n"));
}
analogWrite(LED, 255);
delay(500); delay(500);
analogWrite(led, 0); analogWrite(LED, 0);
delay(500);
analogWrite(LED, 255);
delay(500);
analogWrite(LED, 0);
delay(500);
analogWrite(LED, 255);
delay(500);
analogWrite(LED, 0);
delay(500); delay(500);
delay(100);
analogWrite(led, 255);
delay(100);
analogWrite(led, 0);
LEDnext_time = millis() + 1; LEDnext_time = millis() + 1;
#ifdef EXT_RAM #ifdef EXT_RAM
printf_P(PSTR("Total EXT RAM banks %i\r\n"), xmem::getTotalBanks()); printf_P(PSTR("Total EXT RAM banks %i\r\n"), xmem::getTotalBanks());
@ -173,7 +196,7 @@ void setup() {
printf_P(PSTR("Available heap: %u Bytes\r\n"), freeHeap()); printf_P(PSTR("Available heap: %u Bytes\r\n"), freeHeap());
} }
#endif #endif
while (Usb.Init() == -1) { while (Usb.Init(1000) == -1) {
printf_P(PSTR("No\r\n")); printf_P(PSTR("No\r\n"));
Notify(PSTR("OSC did not start."), 0x40); Notify(PSTR("OSC did not start."), 0x40);
} }
@ -263,8 +286,8 @@ ISR(TIMER3_COMPA_vect) {
if (millis() >= LEDnext_time) { if (millis() >= LEDnext_time) {
LEDnext_time = millis() + 30; LEDnext_time = millis() + 30;
// set the brightness of pin 9: // set the brightness of LED
analogWrite(led, brightness); analogWrite(LED, brightness);
// change the brightness for next time through the loop: // change the brightness for next time through the loop:
brightness = brightness + fadeAmount; brightness = brightness + fadeAmount;
@ -281,7 +304,6 @@ ISR(TIMER3_COMPA_vect) {
} }
} }
bool isfat(uint8_t t) { bool isfat(uint8_t t) {
return (t == 0x01 || t == 0x04 || t == 0x06 || t == 0x0b || t == 0x0c || t == 0x0e || t == 0x1); return (t == 0x01 || t == 0x04 || t == 0x06 || t == 0x0b || t == 0x0c || t == 0x0e || t == 0x1);
} }
@ -289,17 +311,10 @@ bool isfat(uint8_t t) {
void die(FRESULT rc) { void die(FRESULT rc) {
printf_P(PSTR("Failed with rc=%u.\r\n"), rc); printf_P(PSTR("Failed with rc=%u.\r\n"), rc);
//for (;;); //for (;;);
} }
/*make sure this is a power of two. */
#define mbxs 128
void loop() { void loop() {
uint8_t My_Buff_x[mbxs]; /* File read buffer */
FIL My_File_Object_x; /* File object */ FIL My_File_Object_x; /* File object */
DIR My_Dir_Object_x; /* Directory object */
FILINFO My_File_Info_Object_x; /* File information object */
// Print a heap status report about every 10 seconds. // Print a heap status report about every 10 seconds.
if (millis() >= HEAPnext_time) { if (millis() >= HEAPnext_time) {
@ -342,16 +357,6 @@ void loop() {
printf_P(PSTR("USB state = %x\r\n"), current_state); printf_P(PSTR("USB state = %x\r\n"), current_state);
if (current_state == USB_STATE_RUNNING) { if (current_state == USB_STATE_RUNNING) {
fadeAmount = 30; fadeAmount = 30;
/*
partsready = false;
for (int i = 0; i < cpart; i++) {
if (Fats[i] != NULL)
delete Fats[i];
}
fatready = false;
notified = false;
cpart = 0;
*/
} }
if (current_state == USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE) { if (current_state == USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE) {
fadeAmount = 80; fadeAmount = 80;
@ -365,17 +370,6 @@ void loop() {
notified = false; notified = false;
cpart = 0; cpart = 0;
} }
#if 0
if (current_state == 0xa0) {
printf_P(PSTR("VBUS off\r\n"));
// safe to do here
Usb.gpioWr(0x00);
digitalWrite(2, 0);
usbon = false;
usbon_time = millis() + 2000;
change = false;
}
#endif
last_state = current_state; last_state = current_state;
} }
@ -386,7 +380,7 @@ void loop() {
} }
// This is horrible, and needs to be moved elsewhere! // This is horrible, and needs to be moved elsewhere!
for (int B = 0; B < MAX_DRIVERS; B++) { for (int B = 0; B < MAX_USB_MS_DRIVERS; B++) {
if (!partsready && Bulk[B]->GetAddress() != NULL) { if (!partsready && Bulk[B]->GetAddress() != NULL) {
// Build a list. // Build a list.
int ML = Bulk[B]->GetbMaxLUN(); int ML = Bulk[B]->GetbMaxLUN();
@ -395,9 +389,8 @@ void loop() {
for (int i = 0; i < ML; i++) { for (int i = 0; i < ML; i++) {
if (Bulk[B]->LUNIsGood(i)) { if (Bulk[B]->LUNIsGood(i)) {
partsready = true; partsready = true;
sto[i].private_data = &info[i]; ((pvt_t *)sto[i].private_data)->lun = i;
info[i].lun = i; ((pvt_t *)sto[i].private_data)->B = B;
info[i].B = B;
sto[i].Read = *PRead; sto[i].Read = *PRead;
sto[i].Write = *PWrite; sto[i].Write = *PWrite;
sto[i].Reads = *PReads; sto[i].Reads = *PReads;
@ -477,7 +470,6 @@ void loop() {
if (fatready) { if (fatready) {
FRESULT rc; /* Result code */ FRESULT rc; /* Result code */
UINT bw, br, i; UINT bw, br, i;
ULONG ii, wt, rt, start, end;
if (!notified) { if (!notified) {
fadeAmount = 5; fadeAmount = 5;
@ -488,7 +480,7 @@ void loop() {
else { else {
printf_P(PSTR("\r\nType the file content.\r\n")); printf_P(PSTR("\r\nType the file content.\r\n"));
for (;;) { for (;;) {
rc = f_read(&My_File_Object_x, &(My_Buff_x[0]), mbxs, &br); /* Read a chunk of file */ rc = f_read(&My_File_Object_x, My_Buff_x, mbxs, &br); /* Read a chunk of file */
if (rc || !br) break; /* Error or end of file */ if (rc || !br) break; /* Error or end of file */
for (i = 0; i < br; i++) { for (i = 0; i < br; i++) {
/* Type the data */ /* Type the data */
@ -528,6 +520,13 @@ void loop() {
goto out; goto out;
} }
outdir: outdir:
{
#if _USE_LFN
char lfn[_MAX_LFN + 1];
FILINFO My_File_Info_Object_x; /* File information object */
My_File_Info_Object_x.lfname = lfn;
#endif
DIR My_Dir_Object_x; /* Directory object */
printf_P(PSTR("\r\nOpen root directory.\r\n")); printf_P(PSTR("\r\nOpen root directory.\r\n"));
rc = f_opendir(&My_Dir_Object_x, "0:/"); rc = f_opendir(&My_Dir_Object_x, "0:/");
if (rc) { if (rc) {
@ -538,6 +537,10 @@ outdir:
printf_P(PSTR("\r\nDirectory listing...\r\n")); printf_P(PSTR("\r\nDirectory listing...\r\n"));
printf_P(PSTR("Available heap: %u Bytes\r\n"), freeHeap()); printf_P(PSTR("Available heap: %u Bytes\r\n"), freeHeap());
for (;;) { for (;;) {
#if _USE_LFN
My_File_Info_Object_x.lfsize = _MAX_LFN;
#endif
rc = f_readdir(&My_Dir_Object_x, &My_File_Info_Object_x); /* Read a directory item */ rc = f_readdir(&My_Dir_Object_x, &My_File_Info_Object_x); /* Read a directory item */
if (rc || !My_File_Info_Object_x.fname[0]) break; /* Error or end of dir */ if (rc || !My_File_Info_Object_x.fname[0]) break; /* Error or end of dir */
@ -578,24 +581,24 @@ outdir:
#endif #endif
printf_P(PSTR(" %8lu %s\r\n"), My_File_Info_Object_x.fsize, &(My_File_Info_Object_x.fname[0])); printf_P(PSTR(" %8lu %s\r\n"), My_File_Info_Object_x.fsize, &(My_File_Info_Object_x.fname[0]));
} }
}
out: out:
if (rc) die(rc); if (rc) die(rc);
printf_P(PSTR("\r\nTest completed.\r\n")); printf_P(PSTR("\r\nTest completed.\r\n"));
} }
if (runtest) { if (runtest) {
ULONG ii, wt, rt, start, end;
runtest = false; runtest = false;
f_unlink("0:/10MB.bin");
printf_P(PSTR("\r\nCreate a new 10MB test file (10MB.bin).\r\n")); printf_P(PSTR("\r\nCreate a new 10MB test file (10MB.bin).\r\n"));
for (bw = 0; bw < mbxs; bw++) My_Buff_x[bw] = bw & 0xff;
rc = f_open(&My_File_Object_x, "0:/10MB.bin", FA_WRITE | FA_CREATE_ALWAYS); rc = f_open(&My_File_Object_x, "0:/10MB.bin", FA_WRITE | FA_CREATE_ALWAYS);
if (rc) goto failed; if (rc) goto failed;
for (bw = 0; bw < mbxs; bw++) My_Buff_x[bw] = bw & 0xff;
start = millis(); start = millis();
for (ii = 10485760 / mbxs; ii > 0; ii--) { for (ii = 10485760LU / mbxs; ii > 0LU; ii--) {
rc = f_write(&My_File_Object_x, &My_Buff_x[0], mbxs, &bw); rc = f_write(&My_File_Object_x, My_Buff_x, mbxs, &bw);
if (rc || !bw) goto failed; if (rc || !bw) goto failed;
} }
rc = f_close(&My_File_Object_x); rc = f_close(&My_File_Object_x);
@ -607,7 +610,7 @@ out:
start = millis(); start = millis();
if (rc) goto failed; if (rc) goto failed;
for (;;) { for (;;) {
rc = f_read(&My_File_Object_x, &My_Buff_x[0], mbxs, &bw); /* Read a chunk of file */ rc = f_read(&My_File_Object_x, My_Buff_x, mbxs, &bw); /* Read a chunk of file */
if (rc || !bw) break; /* Error or end of file */ if (rc || !bw) break; /* Error or end of file */
} }
end = millis(); end = millis();
@ -617,7 +620,6 @@ out:
rt = end - start; rt = end - start;
printf_P(PSTR("Time to read 10485760 bytes: %lu ms (%lu sec)\r\nDelete test file\r\n"), rt, (500 + rt) / 1000UL); printf_P(PSTR("Time to read 10485760 bytes: %lu ms (%lu sec)\r\nDelete test file\r\n"), rt, (500 + rt) / 1000UL);
failed: failed:
rc = f_unlink("0:/10MB.bin");
if (rc) die(rc); if (rc) die(rc);
printf_P(PSTR("10MB timing test finished.\r\n")); printf_P(PSTR("10MB timing test finished.\r\n"));
} }

@ -1 +1 @@
Subproject commit 8bcf5f90f8bd967378b6eeebd7fd943f125fbc18 Subproject commit e5f9968b42fb4970ec037290e5942e83accd4fad

View file

@ -56,10 +56,13 @@ setLedToggle KEYWORD2
moveSetBulb KEYWORD2 moveSetBulb KEYWORD2
moveSetRumble KEYWORD2 moveSetRumble KEYWORD2
attachOnInit KEYWORD2
PS3Connected KEYWORD2 PS3Connected KEYWORD2
PS3MoveConnected KEYWORD2 PS3MoveConnected KEYWORD2
PS3NavigationConnected KEYWORD2 PS3NavigationConnected KEYWORD2
isReady KEYWORD2
watingForConnection KEYWORD2 watingForConnection KEYWORD2
#################################################### ####################################################
@ -161,6 +164,7 @@ RumbleLow LITERAL1
#################################################### ####################################################
XBOXUSB KEYWORD1 XBOXUSB KEYWORD1
XBOXOLD KEYWORD1
XBOXRECV KEYWORD1 XBOXRECV KEYWORD1
#################################################### ####################################################
@ -192,6 +196,9 @@ BACK LITERAL1
XBOX LITERAL1 XBOX LITERAL1
SYNC LITERAL1 SYNC LITERAL1
BLACK LITERAL1
WHITE LITERAL1
A LITERAL1 A LITERAL1
B LITERAL1 B LITERAL1
X LITERAL1 X LITERAL1

View file

@ -95,12 +95,11 @@ void NotifyFailGetConfDescr(uint8_t reason) {
NotifyFail(reason); NotifyFail(reason);
} }
/* Will we need this in the future?
void NotifyFailSetConfDescr(uint8_t reason) { void NotifyFailSetConfDescr(uint8_t reason) {
NotifyFailSetConfDescr(); NotifyFailSetConfDescr();
NotifyFail(reason); NotifyFail(reason);
} }
*/
void NotifyFailUnknownDevice(uint16_t VID, uint16_t PID) { void NotifyFailUnknownDevice(uint16_t VID, uint16_t PID) {
Notify(PSTR("\r\nUnknown Device Connected - VID: "), 0x80); Notify(PSTR("\r\nUnknown Device Connected - VID: "), 0x80);
D_PrintHex<uint16_t > (VID, 0x80); D_PrintHex<uint16_t > (VID, 0x80);

View file

@ -43,6 +43,7 @@ void E_Notifyc(char c, int lvl);
void NotifyFailGetDevDescr(uint8_t reason); void NotifyFailGetDevDescr(uint8_t reason);
void NotifyFailSetDevTblEntry(uint8_t reason); void NotifyFailSetDevTblEntry(uint8_t reason);
void NotifyFailGetConfDescr(uint8_t reason); void NotifyFailGetConfDescr(uint8_t reason);
void NotifyFailSetConfDescr(uint8_t reason);
void NotifyFailGetDevDescr(void); void NotifyFailGetDevDescr(void);
void NotifyFailSetDevTblEntry(void); void NotifyFailSetDevTblEntry(void);
void NotifyFailGetConfDescr(void); void NotifyFailGetConfDescr(void);

View file

@ -18,6 +18,13 @@ e-mail : support@circuitsathome.com
#ifndef _USBHOST_H_ #ifndef _USBHOST_H_
#define _USBHOST_H_ #define _USBHOST_H_
// So we can use delay() -- xxxajk
#if defined(ARDUINO) && ARDUINO >=100
#include "Arduino.h"
#else
#include <WProgram.h>
#endif
#include "avrpins.h" #include "avrpins.h"
#include "max3421e.h" #include "max3421e.h"
#include "usb_ch9.h" #include "usb_ch9.h"
@ -52,6 +59,11 @@ typedef SPi< Pb5, Pb3, Pb4, Pb2 > spi;
typedef SPi< Pb7, Pb5, Pb6, Pb4 > spi; typedef SPi< Pb7, Pb5, Pb6, Pb4 > spi;
#endif #endif
typedef enum VBUS_t {
on = 0,
off = GPX_VBDET
};
template< typename SS, typename INTR > class MAX3421e /* : public spi */ { template< typename SS, typename INTR > class MAX3421e /* : public spi */ {
static uint8_t vbusState; static uint8_t vbusState;
@ -65,6 +77,11 @@ public:
uint8_t gpioRd(); uint8_t gpioRd();
uint16_t reset(); uint16_t reset();
int8_t Init(); int8_t Init();
int8_t Init(int mseconds);
void vbusPower(VBUS_t state) {
regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL | state));
}
uint8_t getVbusState(void) { uint8_t getVbusState(void) {
return vbusState; return vbusState;
@ -94,7 +111,7 @@ MAX3421e< SS, INTR >::MAX3421e() {
#endif #endif
/* MAX3421E - full-duplex SPI, level interrupt */ /* MAX3421E - full-duplex SPI, level interrupt */
regWr(rPINCTL, (bmFDUPSPI + bmINTLEVEL)); regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL | GPX_VBDET));
}; };
/* write single byte into MAX3421 register */ /* write single byte into MAX3421 register */
@ -200,17 +217,6 @@ uint16_t MAX3421e< SS, INTR >::reset() {
} }
return( i); return( i);
} }
///* initialize MAX3421E. Set Host mode, pullups, and stuff. Returns 0 if success, -1 if not */
//template< typename SS, typename INTR >
//int8_t MAX3421e< SS, INTR >::Init()
//{
// if( reset() == 0 ) { //OSCOKIRQ hasn't asserted in time
// return ( -1 );
// }
// regWr( rMODE, bmDPPULLDN|bmDMPULLDN|bmHOST ); // set pull-downs, Host
//
// return( 0 );
//}
/* initialize MAX3421E. Set Host mode, pullups, and stuff. Returns 0 if success, -1 if not */ /* initialize MAX3421E. Set Host mode, pullups, and stuff. Returns 0 if success, -1 if not */
template< typename SS, typename INTR > template< typename SS, typename INTR >
@ -218,6 +224,10 @@ int8_t MAX3421e< SS, INTR >::Init() {
if(reset() == 0) { //OSCOKIRQ hasn't asserted in time if(reset() == 0) { //OSCOKIRQ hasn't asserted in time
return( -1); return( -1);
} }
// GPX pin on.
regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL));
regWr(rMODE, bmDPPULLDN | bmDMPULLDN | bmHOST); // set pull-downs, Host regWr(rMODE, bmDPPULLDN | bmDMPULLDN | bmHOST); // set pull-downs, Host
regWr(rHIEN, bmCONDETIE | bmFRAMEIE); //connection detection regWr(rHIEN, bmCONDETIE | bmFRAMEIE); //connection detection
@ -230,6 +240,38 @@ int8_t MAX3421e< SS, INTR >::Init() {
regWr(rHIRQ, bmCONDETIRQ); //clear connection detect interrupt regWr(rHIRQ, bmCONDETIRQ); //clear connection detect interrupt
regWr(rCPUCTL, 0x01); //enable interrupt pin regWr(rCPUCTL, 0x01); //enable interrupt pin
return( 0);
}
/* initialize MAX3421E. Set Host mode, pullups, and stuff. Returns 0 if success, -1 if not */
template< typename SS, typename INTR >
int8_t MAX3421e< SS, INTR >::Init(int mseconds) {
if(reset() == 0) { //OSCOKIRQ hasn't asserted in time
return( -1);
}
// Delay a minimum of 1 second to ensure any capacitors are drained.
// 1 second is required to make sure we do not smoke a Microdrive!
if(mseconds < 1000) mseconds = 1000;
delay(mseconds);
regWr(rMODE, bmDPPULLDN | bmDMPULLDN | bmHOST); // set pull-downs, Host
regWr(rHIEN, bmCONDETIE | bmFRAMEIE); //connection detection
/* check if device is connected */
regWr(rHCTL, bmSAMPLEBUS); // sample USB bus
while(!(regRd(rHCTL) & bmSAMPLEBUS)); //wait for sample operation to finish
busprobe(); //check if anything is connected
regWr(rHIRQ, bmCONDETIRQ); //clear connection detect interrupt
regWr(rCPUCTL, 0x01); //enable interrupt pin
// GPX pin on. This is done here so that busprobe will fail if we have a switch connected.
regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL));
return( 0); return( 0);
} }