Anexo C Programacion
Anexo C Programacion
#include <usbhid.h>
#include <hiduniversal.h>
#include <usbhub.h>
#include <SPI.h>
#include "hidjoystickrptparser.h"
#ifdef dobogusinclude
#include <spi4teensy3.h>
#endif
USB Usb;
USBHub Hub(&Usb);
HIDUniversal Hid(&Usb);
JoystickEvents JoyEvents;
JoystickReportParser Joy(&JoyEvents);
void setup()
Serial.begin(115200);
#if !defined(__MIPSEL__)
while (!Serial);
#endif
Serial.println("Start");
if (Usb.Init() == -1)
delay(200);
if (!Hid.SetReportParser(0, &Joy))
void loop()
Usb.Task();
#include "hidjoystickrptparser.h"
#include <RobojaxBTS7960.h>
//MOTOR IZQUIERDA
#define RPWM 3
#define R_EN 14
#define R_IS 16
#define LPWM 5
#define L_EN 15
#define L_IS 17
//MOTOR DERECHA
#define RPWM_D 2
#define R_EN_D 18
#define R_IS_D 20
#define LPWM_D 4
#define L_EN_D 19
#define L_IS_D 21
#define CW 1
#define CCW 0
#define debug 0
#define LED 52
int Valor=0,ValX=0;
byte Valor2=0,Valor3=0;
JoystickReportParser::JoystickReportParser(JoystickEvents *evt) :
joyEvents(evt),
oldHat(0xDE),
oldButtons(0) {
oldPad[i] = 0xD;
// Checking if there are changes in report since the method was last called
if (buf[i] != oldPad[i]) {
match = false;
break;
joyEvents->OnHatSwitch(hat);
oldHat = hat;
buttons <<= 4;
if (changes) {
joyEvents->OnButtonDn(i + 1);
else
joyEvents->OnButtonUp(i + 1);
}
}
oldButtons = buttons;
motorI.begin();
motorD.begin();
Serial.print("X1: ");
Serial.println(evt->X);
Serial.print("Y1: ");
Serial.println(evt->Y);
Valor=map(evt->Y,0,255,255,-255);
ValX=map(evt->X,0,255,255,-255);
if(Valor<0)
Valor2=map(Valor,1,-255,0,255);
if(Valor<-20)
motorI.rotate(30,CCW);
motorD.rotate(30,CCW);
if(Valor>0)
Valor2=map(Valor,1,255,0,255); // ADELANTE
if(Valor>20)
motorI.rotate(30,CW); // motorI.rotate(Valor2,CW)
motorD.rotate(30,CW); // motorD.rotate(Valor2,CW);
if(evt->X<40)
// Valor3=map(ValX,1,-255,0,255); //IZQUIERDA
motorI.rotate(30,CCW);
motorD.rotate(30,CW);
// Serial.println(Valor3);
if(evt->X>140)
// Valor3=map(ValX,1,255,0,255); //DERECHA
motorI.rotate(30,CW);
motorD.rotate(30,CCW);
// Serial.println(Valor3);
if(((evt->X<140)&&(evt->X>118))&&((evt->Y<140)&&(evt->Y>118)))
motorI.stop();
motorD.stop();
}
void JoystickEvents::OnHatSwitch(uint8_t hat)
Serial.println("");
Serial.print("Up: ");
Serial.println(but_id, DEC);
Serial.print("Dn: ");
Serial.println(but_id, DEC);
digitalWrite(LED, LOW);
#if !defined(__HIDJOYSTICKRPTPARSER_H__)
#define __HIDJOYSTICKRPTPARSER_H__
#include <usbhid.h>
struct GamePadEventData
class JoystickEvents
public:
};
#define RPT_GEMEPAD_LEN 5
JoystickEvents *joyEvents;
uint8_t oldPad[RPT_GEMEPAD_LEN];
uint8_t oldHat;
uint16_t oldButtons;
public:
JoystickReportParser(JoystickEvents *evt);
virtual void Parse(USBHID *hid, bool is_rpt_id, uint8_t len, uint8_t *buf);
};
#endif // __HIDJOYSTICKRPTPARSER_H__