#include"PS2X_lib.h"#include#include#include#include#if ARDUINO > 22#include"Arduino.h"#else#include"WProgram.h"#include"pins_arduino.h"#endifstatic byte enter_config[]={0x01,0x43,0x00,0x01,0x00};static byte set_mode[]={0x01,0x44,0x00,0x01,0x03,0x00,0x00,0x00,0x00};static byte set_bytes_large[]={0x01,0x4F,0x00,0xFF,0xFF,0x03,0x00,0x00,0x00};static byte exit_config[]={0x01,0x43,0x00,0x00,0x5A,0x5A,0x5A,0x5A,0x5A};static byte enable_rumble[]={0x01,0x4D,0x00,0x00,0x01};static byte type_read[]={0x01,0x45,0x00,0x5A,0x5A,0x5A,0x5A,0x5A,0x5A};/****************************************************************************************/
boolean PS2X::NewButtonState(){return((last_buttons ^ buttons)>0);}/****************************************************************************************/
boolean PS2X::NewButtonState(unsignedint button){return(((last_buttons ^ buttons)& button)>0);}/****************************************************************************************/
boolean PS2X::ButtonPressed(unsignedint button){return(NewButtonState(button)&Button(button));}/****************************************************************************************/
boolean PS2X::ButtonReleased(unsignedint button){return((NewButtonState(button))&((~last_buttons & button)>0));}/****************************************************************************************/
boolean PS2X::Button(uint16_t button){return((~buttons & button)>0);}/****************************************************************************************/unsignedint PS2X::ButtonDataByte(){return(~buttons);}/****************************************************************************************/
byte PS2X::Analog(byte button){return PS2data[button];}/****************************************************************************************/unsignedchar PS2X::_gamepad_shiftinout (char byte){unsignedchar tmp =0;for(unsignedchar i=0;i<8;i++){if(CHK(byte,i))CMD_SET();elseCMD_CLR();CLK_CLR();delayMicroseconds(CTRL_CLK);//if(DAT_CHK()) SET(tmp,i);if(DAT_CHK())bitSet(tmp,i);CLK_SET();#if CTRL_CLK_HIGHdelayMicroseconds(CTRL_CLK_HIGH);#endif}CMD_SET();delayMicroseconds(CTRL_BYTE_DELAY);return tmp;}/****************************************************************************************/void PS2X::read_gamepad(){read_gamepad(false,0x00);}/****************************************************************************************/
boolean PS2X::read_gamepad(boolean motor1, byte motor2){double temp =millis()- last_read;if(temp >1500)//waited to longreconfig_gamepad();if(temp < read_delay)//waited too shortdelay(read_delay - temp);if(motor2 !=0x00)motor2 =map(motor2,0,255,0x40,0xFF);//noting below 40 will make it spinchar dword[9]={0x01,0x42,0,motor1,motor2,0,0,0,0};byte dword2[12]={0,0,0,0,0,0,0,0,0,0,0,0};// Try a few times to get valid data...for(byte RetryCnt =0; RetryCnt <5; RetryCnt++){CMD_SET();CLK_SET();ATT_CLR();// low enable joystickdelayMicroseconds(CTRL_BYTE_DELAY);//Send the command to send button and joystick data;for(int i =0; i<9; i++){PS2data[i]=_gamepad_shiftinout(dword[i]);}if(PS2data[1]==0x79){//if controller is in full data return mode, get the rest of datafor(int i =0; i<12; i++){PS2data[i+9]=_gamepad_shiftinout(dword2[i]);}}ATT_SET();// HI disable joystick// Check to see if we received valid data or not. // We should be in analog mode for our data to be valid (analog == 0x7_)if((PS2data[1]&0xf0)==0x70)break;// If we got to here, we are not in analog mode, try to recover...reconfig_gamepad();// try to get back into Analog mode.delay(read_delay);}// If we get here and still not in analog mode (=0x7_), try increasing the read_delay...if((PS2data[1]&0xf0)!=0x70){if(read_delay <10)read_delay++;// see if this helps out...}#ifdef PS2X_COM_DEBUGSerial.println("OUT:IN");for(int i=0; i<9; i++){Serial.print(dword[i], HEX);Serial.print(":");Serial.print(PS2data[i], HEX);Serial.print(" ");}for(int i =0; i<12; i++){Serial.print(dword2[i], HEX);Serial.print(":");Serial.print(PS2data[i+9], HEX);Serial.print(" ");}Serial.println("");#endiflast_buttons = buttons;//store the previous buttons states#if defined(__AVR__)buttons =*(uint16_t*)(PS2data+3);//store as one value for multiple functions#elsebuttons =(uint16_t)(PS2data[4]<<8)+ PS2data[3];//store as one value for multiple functions#endiflast_read =millis();return((PS2data[1]&0xf0)==0x70);// 1 = OK = analog mode - 0 = NOK}/****************************************************************************************/
byte PS2X::config_gamepad(uint8_t clk, uint8_t cmd, uint8_t att, uint8_t dat){returnconfig_gamepad(clk, cmd, att, dat, false, false);}/****************************************************************************************/
byte PS2X::config_gamepad(uint8_t clk, uint8_t cmd, uint8_t att, uint8_t dat, bool pressures, bool rumble){byte temp[sizeof(type_read)];#ifdef __AVR___clk_mask =digitalPinToBitMask(clk);_clk_oreg =portOutputRegister(digitalPinToPort(clk));_cmd_mask =digitalPinToBitMask(cmd);_cmd_oreg =portOutputRegister(digitalPinToPort(cmd));_att_mask =digitalPinToBitMask(att);_att_oreg =portOutputRegister(digitalPinToPort(att));_dat_mask =digitalPinToBitMask(dat);_dat_ireg =portInputRegister(digitalPinToPort(dat));#elseuint32_t lport;// Port number for this pin_clk_mask =digitalPinToBitMask(clk);lport =digitalPinToPort(clk);_clk_lport_set =portOutputRegister(lport)+2;_clk_lport_clr =portOutputRegister(lport)+1;_cmd_mask =digitalPinToBitMask(cmd);lport =digitalPinToPort(cmd);_cmd_lport_set =portOutputRegister(lport)+2;_cmd_lport_clr =portOutputRegister(lport)+1;_att_mask =digitalPinToBitMask(att);lport =digitalPinToPort(att);_att_lport_set =portOutputRegister(lport)+2;_att_lport_clr =portOutputRegister(lport)+1;_dat_mask =digitalPinToBitMask(dat);_dat_lport =portInputRegister(digitalPinToPort(dat));#endifpinMode(clk, OUTPUT);//configure portspinMode(att, OUTPUT);pinMode(cmd, OUTPUT);pinMode(dat, INPUT);#if defined(__AVR__)digitalWrite(dat, HIGH);//enable pull-up#endifCMD_SET();// SET(*_cmd_oreg,_cmd_mask);CLK_SET();//new error checking. First, read gamepad a few times to see if it's talkingread_gamepad();read_gamepad();//see if it talked - see if mode came back. //If still anything but 41, 73 or 79, then it's not talkingif(PS2data[1]!=0x41&& PS2data[1]!=0x73&& PS2data[1]!=0x79){#ifdef PS2X_DEBUGSerial.println("Controller mode not matched or no controller found");Serial.print("Expected 0x41, 0x73 or 0x79, but got ");Serial.println(PS2data[1], HEX);#endifreturn1;//return error code 1}//try setting mode, increasing delays if need be.read_delay =1;for(int y =0; y <=10; y++){sendCommandString(enter_config,sizeof(enter_config));//start config run//read typedelayMicroseconds(CTRL_BYTE_DELAY);CMD_SET();CLK_SET();ATT_CLR();// low enable joystickdelayMicroseconds(CTRL_BYTE_DELAY);for(int i =0; i<9; i++){temp[i]=_gamepad_shiftinout(type_read[i]);}ATT_SET();// HI disable joystickcontroller_type = temp[3];sendCommandString(set_mode,sizeof(set_mode));if(rumble){sendCommandString(enable_rumble,sizeof(enable_rumble)); en_Rumble = true;}if(pressures){sendCommandString(set_bytes_large,sizeof(set_bytes_large)); en_Pressures = true;}sendCommandString(exit_config,sizeof(exit_config));read_gamepad();if(pressures){if(PS2data[1]==0x79)break;if(PS2data[1]==0x73)return3;}if(PS2data[1]==0x73)break;if(y ==10){#ifdef PS2X_DEBUGSerial.println("Controller not accepting commands");Serial.print("mode stil set at");Serial.println(PS2data[1], HEX);#endifreturn2;//exit function with error}read_delay +=1;//add 1ms to read_delay}return0;//no error if here}/****************************************************************************************/void PS2X::sendCommandString(byte string[], byte len){#ifdef PS2X_COM_DEBUGbyte temp[len];ATT_CLR();// low enable joystickdelayMicroseconds(CTRL_BYTE_DELAY);for(int y=0; y < len; y++)temp[y]=_gamepad_shiftinout(string[y]);ATT_SET();//high disable joystickdelay(read_delay);//wait a fewSerial.println("OUT:IN Configure");for(int i=0; i<len; i++){Serial.print(string[i], HEX);Serial.print(":");Serial.print(temp[i], HEX);Serial.print(" ");}Serial.println("");#elseATT_CLR();// low enable joystickfor(int y=0; y < len; y++)_gamepad_shiftinout(string[y]);ATT_SET();//high disable joystickdelay(read_delay);//wait a few#endif}/****************************************************************************************/
byte PS2X::readType(){/*byte temp[sizeof(type_read)];sendCommandString(enter_config, sizeof(enter_config));delayMicroseconds(CTRL_BYTE_DELAY);CMD_SET();CLK_SET();ATT_CLR(); // low enable joystickdelayMicroseconds(CTRL_BYTE_DELAY);for (int i = 0; i<9; i++) {temp[i] = _gamepad_shiftinout(type_read[i]);}sendCommandString(exit_config, sizeof(exit_config));if(temp[3] == 0x03)return 1;else if(temp[3] == 0x01)return 2;return 0;
*/if(controller_type ==0x03)return1;elseif(controller_type ==0x01)return2;elseif(controller_type ==0x0C)return3;//2.4G Wireless Dual Shock PS2 Game Controllerreturn0;}/****************************************************************************************/void PS2X::enableRumble(){sendCommandString(enter_config,sizeof(enter_config));sendCommandString(enable_rumble,sizeof(enable_rumble));sendCommandString(exit_config,sizeof(exit_config));en_Rumble = true;}/****************************************************************************************/
bool PS2X::enablePressures(){sendCommandString(enter_config,sizeof(enter_config));sendCommandString(set_bytes_large,sizeof(set_bytes_large));sendCommandString(exit_config,sizeof(exit_config));read_gamepad();read_gamepad();if(PS2data[1]!=0x79)return false;en_Pressures = true;return true;}/****************************************************************************************/void PS2X::reconfig_gamepad(){sendCommandString(enter_config,sizeof(enter_config));sendCommandString(set_mode,sizeof(set_mode));if(en_Rumble)sendCommandString(enable_rumble,sizeof(enable_rumble));if(en_Pressures)sendCommandString(set_bytes_large,sizeof(set_bytes_large));sendCommandString(exit_config,sizeof(exit_config));}/****************************************************************************************/#ifdef __AVR__inlinevoid PS2X::CLK_SET(void){register uint8_t old_sreg = SREG;cli();*_clk_oreg |= _clk_mask;SREG = old_sreg;}inlinevoid PS2X::CLK_CLR(void){register uint8_t old_sreg = SREG;cli();*_clk_oreg &=~_clk_mask;SREG = old_sreg;}inlinevoid PS2X::CMD_SET(void){register uint8_t old_sreg = SREG;cli();*_cmd_oreg |= _cmd_mask;// SET(*_cmd_oreg,_cmd_mask);SREG = old_sreg;}inlinevoid PS2X::CMD_CLR(void){register uint8_t old_sreg = SREG;cli();*_cmd_oreg &=~_cmd_mask;// SET(*_cmd_oreg,_cmd_mask);SREG = old_sreg;}inlinevoid PS2X::ATT_SET(void){register uint8_t old_sreg = SREG;cli();*_att_oreg |= _att_mask ;SREG = old_sreg;}inlinevoid PS2X::ATT_CLR(void){register uint8_t old_sreg = SREG;cli();*_att_oreg &=~_att_mask;SREG = old_sreg;}inline bool PS2X::DAT_CHK(void){return(*_dat_ireg & _dat_mask)? true : false;}#else// On pic32, use the set/clr registers to make them atomic...inlinevoid PS2X::CLK_SET(void){*_clk_lport_set |= _clk_mask;}inlinevoid PS2X::CLK_CLR(void){*_clk_lport_clr |= _clk_mask;}inlinevoid PS2X::CMD_SET(void){*_cmd_lport_set |= _cmd_mask;}inlinevoid PS2X::CMD_CLR(void){*_cmd_lport_clr |= _cmd_mask;}inlinevoid PS2X::ATT_SET(void){*_att_lport_set |= _att_mask;}inlinevoid PS2X::ATT_CLR(void){*_att_lport_clr |= _att_mask;}inline bool PS2X::DAT_CHK(void){return(*_dat_lport & _dat_mask)? true : false;}#endif
arduino文件
#include"PS2X_lib.h"//for v1.6#include#include/******************************************************************* set pins connected to PS2 controller:* - 1e column: original * - 2e colmun: Stef?* replace pin numbers by the ones you use******************************************************************/#define PS2_DAT 6 #define PS2_CMD 5 #define PS2_SEL 4 #define PS2_CLK 3 /******************************************************************* select modes of PS2 controller:* - pressures = analog reading of push-butttons * - rumble = motor rumbling* uncomment 1 of the lines for each mode selection******************************************************************/#define pressures true #define rumble truePS2X ps2x;// create PS2 Controller Class//right now, the library does NOT support hot pluggable controllers, meaning //you must always either restart your Arduino after you connect the controller, //or call config_gamepad(pins) again after connecting the controller.int error =0;
byte type =0;
byte vibrate =0;int lx =0;int ly=0;int L_Speed =0;int R_Speed =0;Servo myservo1,myservo2,myservo3,myservo4;// create servo object to control a servoconstint SERVOS =4;//舵机数4个constint ACC =10;// the accurancy of the potentiometer value before idle starts countingint value[SERVOS], idle[SERVOS], currentAngle[SERVOS], MIN[SERVOS], MAX[SERVOS], INITANGLE[SERVOS], previousAngle[SERVOS],ANA[SERVOS];int Left_motor=8;//左电机(IN3) 输出0 前进 输出1 后退int Left_motor_pwm=9;//左电机PWM调速int Right_motor_pwm=10;// 右电机PWM调速int Right_motor=11;// 右电机后退(IN1) 输出0 前进 输出1 后退voidsetup(){Serial.begin(57600);myservo1.attach(2);//手爪电机myservo2.attach(7);//上臂电机myservo3.attach(12);//下臂电机myservo4.attach(13);//底座电机 //-----电机IO口定-pinMode(8, OUTPUT);pinMode(9, OUTPUT);pinMode(10, OUTPUT);pinMode(11, OUTPUT);stop();//手爪 ServoMIN[0]=10;MAX[0]=50;INITANGLE[0]=30;//上臂电机MIN[1]=10;// This should bring the lever to just below 90deg to groundMAX[1]=140;INITANGLE[1]=90;// This should bring the lever parallel with the ground//下臂电机MIN[2]=40;MAX[2]=170;INITANGLE[2]=90;//底座电机MIN[3]=0;MAX[3]=170;INITANGLE[3]=90;//初始化电机myservo1.write(INITANGLE[0]); myservo2.write(INITANGLE[1]); myservo3.write(INITANGLE[2]);myservo4.write(INITANGLE[3]); currentAngle[0]=INITANGLE[0];currentAngle[1]=INITANGLE[1];currentAngle[2]=INITANGLE[2];currentAngle[3]=INITANGLE[3];delay(2000);//added delay to give wireless ps2 module some time to startup, before configuring itSerial.print("Search Controller..");//CHANGES for v1.6 HERE!!! **************PAY ATTENTION*************do{//setup pins and settings: GamePad(clock, command, attention, data, Pressures?, Rumble?) check for errorerror = ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT, pressures, rumble);if(error ==0){Serial.println("\nConfigured successful ");break;}else{Serial.print(".");delay(100);}}while(1); type = ps2x.readType();switch(type){case0:Serial.println("Unknown Controller type found ");break;case1:Serial.println("DualShock Controller found ");break;case2:Serial.println("GuitarHero Controller found ");break;case3:Serial.println("Wireless Sony DualShock Controller found ");break;}//震动一,说明连接ps2x.read_gamepad(true,200);//开启震动delay(500);ps2x.read_gamepad(false,200);//开启震动delay(300);ps2x.read_gamepad(true,200);//开启震动delay(500);}voidloop(){/* You must Read Gamepad to get new values and set vibration valuesps2x.read_gamepad(small motor on/off, larger motor strenght from 0-255)if you don't enable the rumble, use ps2x.read_gamepad(); with no valuesYou should call this at least once a second*/ ps2x.read_gamepad(false, vibrate);//开启震动if(ps2x.Button(PSB_START)){//开始按键Serial.println("Start is being held");ps2x.read_gamepad(true,200);}if(ps2x.Button(PSB_SELECT))Serial.println("Select is being held");if(ps2x.Button(PSB_PAD_UP))//方向按键向上按下{ Serial.print("Up held this hard: ");Serial.println(ps2x.Analog(PSAB_PAD_UP), DEC);forward();}elseif(ps2x.ButtonReleased(PSB_PAD_UP)){//方向按键向上释放stop();}if(ps2x.Button(PSB_PAD_DOWN))//方向按键向下按下{ Serial.print("DOWN held this hard: ");Serial.println(ps2x.Analog(PSAB_PAD_DOWN), DEC);back();}elseif(ps2x.ButtonReleased(PSB_PAD_DOWN))//方向按键向下释放{stop();}if(ps2x.Button(PSB_R1)){//侧面开关右R1R_Speed =0;}if(ps2x.Button(PSB_L1)){//侧面开关左L1L_Speed =0;}if(ps2x.Button(PSB_PAD_LEFT))//方向按键左侧按下 {left();}elseif(ps2x.ButtonReleased(PSB_PAD_LEFT))//方向按键左侧释放{stop();}if(ps2x.Button(PSB_PAD_RIGHT))//方向按键右侧按下{ Serial.println(ps2x.Analog(PSB_PAD_RIGHT));right();}elseif(ps2x.ButtonReleased(PSB_PAD_RIGHT))//方向按键右侧释放{// Serial.println("*****PSB_PAD_RIGHT***** ");stop();} vibrate = ps2x.Analog(PSAB_CROSS);//this will set the large motor vibrate speed based on how hard you press the blue (X) button{}if(ps2x.NewButtonState()){//will be TRUE if any button changes state (on to off, or off to on)if(ps2x.Button(PSB_L3))//左侧L3Serial.println("L3 pressed");if(ps2x.Button(PSB_R3))//右侧L3Serial.println("R3 pressed");if(ps2x.Button(PSB_L2))//左侧L2Serial.println("L2 pressed");if(ps2x.Button(PSB_R2))//右侧R2Serial.println("R2 pressed");if(ps2x.Button(PSB_TRIANGLE))Serial.println("Triangle pressed");//三角形按键按下 }if(ps2x.ButtonPressed(PSB_CIRCLE)){//will be TRUE if button was JUST pressedSerial.println("Circle just pressed");openGripper();}if(ps2x.NewButtonState(PSB_CROSS)){// ×键新键改变Serial.println("X just changed");ps2x.read_gamepad(true, vibrate);//获取震动值}if(ps2x.ButtonPressed(PSB_SQUARE)){//will be TRUE if button was JUST releasedSerial.println("Square just released");closeGripper();}if(ps2x.Button(PSB_L1)|| ps2x.Button(PSB_R1)){//print stick values if either is TRUESerial.print("Stick Values:");Serial.print(ps2x.Analog(PSS_LY), DEC);//Left stick, Y axis. Other options: LX, RY, RX Serial.print(",");Serial.print(ps2x.Analog(PSS_LX), DEC); Serial.print(",");Serial.print(ps2x.Analog(PSS_RY), DEC); Serial.print(",");Serial.println(ps2x.Analog(PSS_RX), DEC);} value[0]= ps2x.Analog(PSS_LX);value[1]= ps2x.Analog(PSS_RY);value[2]= ps2x.Analog(PSS_LY);value[3]= ps2x.Analog(PSS_RX);for(int i =0; i < SERVOS; i++){if(value[i]>130){if(currentAngle[i]< MAX[i]) currentAngle[i]+=1;// Serial.print("value"); // Serial.print(i); // Serial.print(":"); // Serial.println(value[i]);switch(i){case0: myservo1.write(currentAngle[i]);break;case1: myservo2.write(currentAngle[i]);break;case2: myservo3.write(currentAngle[i]);break;case3: myservo4.write(currentAngle[i]);break;}}elseif(value[i]<120){if(currentAngle[i]> MIN[i]) currentAngle[i]-=1;// Serial.print("value"); // Serial.print(i); // Serial.print(":"); // Serial.println(value[i]);switch(i){case0: myservo1.write(currentAngle[i]);break;case1: myservo2.write(currentAngle[i]);break;case2: myservo3.write(currentAngle[i]);break;case3: myservo4.write(currentAngle[i]);break;}}}delay(10);}//Grab somethingvoidopenGripper(){myservo1.write(MIN[0]);delay(300);}//Let go of somethingvoidcloseGripper(){myservo1.write(MAX[0]);delay(300);}voidforward(){digitalWrite(8, LOW);digitalWrite(9, HIGH);digitalWrite(11, LOW);digitalWrite(10, HIGH);}voidright(){digitalWrite(8, LOW);digitalWrite(9, HIGH);digitalWrite(11, LOW);digitalWrite(10, LOW);}voidback(){digitalWrite(8, HIGH);digitalWrite(9, HIGH);digitalWrite(11, HIGH);digitalWrite(10, HIGH);}voidleft(){digitalWrite(8, LOW);digitalWrite(9, LOW);digitalWrite(11, LOW);digitalWrite(10, HIGH);}voidstop(){digitalWrite(8, LOW);digitalWrite(9, LOW);digitalWrite(11, LOW);digitalWrite(10, LOW);}