with pid foward right left foward
Dependencies: wheelchaircontrolRosCom
Fork of wheelchaircontrolrealtime by
main.cpp
- Committer:
- jvfausto
- Date:
- 2018-11-02
- Revision:
- 9:1081ebfe3db0
- Parent:
- 8:db780b392bae
- Child:
- 10:beaa2ddfef32
File content as of revision 9:1081ebfe3db0:
#include "wheelchair.h" QEI wheel(D0, D1, NC, 1200); //Initializes right encoder DigitalIn pt3(D1, PullUp); //Pull up resistors to read analog signals into digital signals DigitalIn pt4(D0, PullUp); QEI wheelS (D3, D6, NC, 1200); //Initializes Left encoder DigitalIn pt1(D3, PullUp); //Pull up resistors to read analog signals into digital signals DigitalIn pt2(D6, PullUp); AnalogIn x(A0); //Initializes analog axis for the joystick AnalogIn y(A1); DigitalOut up(D2); //Turn up speed mode for joystick DigitalOut down(D8); //Turn down speed mode for joystick DigitalOut on(D12); //Turn Wheelchair On DigitalOut off(D11); //Turn Wheelchair Off bool manual = false; //Turns chair joystic to automatic and viceverza Serial pc(USBTX, USBRX, 57600); //Serial Monitor Timer t; //Initialize time object t EventQueue queue; //Class to organize threads ros::NodeHandle nh; nav_msgs::Odometry odom; ros::Publisher chatter("odom", &odom); /*void setOdomNode(){ nh.initNode(); nh.advertise(chatter); }*/ Wheelchair smart(xDir,yDir, &pc, &t, &wheel, &wheelS); //Initialize wheelchair object Thread compass; //Thread for compass Thread velosity; //Thread for velosity Thread ros_com; //Thread for velosity int main(void) { nh.initNode(); nh.advertise(chatter); queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); //Sets up sampling frequency of the compass_thread queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::velosity_thread); //Sets up sampling frequency of the velosity_thread queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::rosCom_thread); //Sets up sampling frequency of the velosity_thread t.reset(); compass.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the compass thread velosity.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the velosity thread ros_com.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the velosity thread while(1) { if( pc.readable()) { char c = pc.getc(); //Read the instruction sent if( c == 'w') { smart.forward(); //Move foward } else if( c == 'a') { smart.left(); //Turn left } else if( c == 'd') { smart.right(); //Turn right } else if( c == 's') { smart.backward(); //Turn rackwards } else if( c == 't') { smart.pid_twistA(); /* char buffer[256]; //Buffer for Angle to turn pc.printf ("Enter a long number: "); int angle = 0; //if you can not send a string char d = pc.getc(); //Reads wether to turn right or left if(d == 'r') { angle = 90; } if(d == 'l') { angle = -90; } //if you can send a string /* fgets (buffer, 256, stdin); //Reads string and puts it in a buffer angle = atoi(buffer); //Converst string into integer */ /* if(angle == 0) { pc.printf("invalid input try again\r\n"); } else { smart.pid_turn(angle); //Sends instruction to turn desired angle }*/ } else if(c == 'v'){ smart.showOdom(); } else if(c == 'o') { //Turns on chair pc.printf("turning on\r\n"); on = 1; wait(1); on = 0; } else if(c == 'f') { //Turns off chair pc.printf("turning off\r\n"); off = 1; wait(1); off = 0; } else if(c == 'k'){ //Sends command to go to the kitchen smart.pid_twistV(); } else if( c == 'm' || manual) { //Turns wheelchair to joystick pc.printf("turning on joystick\r\n"); manual = true; t.reset(); while(manual) { smart.move(x,y); //Reads from joystick and moves if( pc.readable()) { char d = pc.getc(); if( d == 'm') { //Turns wheelchair from joystick into auto pc.printf("turning off joystick\r\n"); manual = false; } } } } else { pc.printf("none \r\n"); smart.stop(); //If nothing else is happening stop the chair } } else { smart.stop(); //If nothing else is happening stop the chair } wait(process); } }