Skip to content
This repository has been archived by the owner on Apr 18, 2024. It is now read-only.

Commit

Permalink
more updates + autonomous and associated files
Browse files Browse the repository at this point in the history
  • Loading branch information
jxia committed Feb 6, 2013
1 parent 634eec1 commit 85e0ff6
Show file tree
Hide file tree
Showing 5 changed files with 912 additions and 32 deletions.
13 changes: 5 additions & 8 deletions Lift_Lowerer.c
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@
#pragma config(Sensor, S1, , sensorI2CMuxController)
#pragma config(Motor, mtr_S1_C1_1, leftTread, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C1_2, rightTread, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C2_1, lift, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C2_2, lift2, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C3_1, lift3, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C2_1, lift, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C2_2, lift2, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C3_1, motorH, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C3_2, motorI, tmotorTetrix, openLoop)
#pragma config(Servo, srvo_S1_C4_1, wristHoriz, tServoStandard)
#pragma config(Servo, srvo_S1_C4_2, wristVert1, tServoStandard)
Expand All @@ -19,17 +19,14 @@ task main()
while (true)
{
if(nNxtButtonPressed == 2) { // If grey left arrow on NXT is pressed, lower lift.
motor[lift] = -10;
motor[lift2] = -10;
motor[lift3] = -100;
motor[lift] = -30;
motor[lift2] = -30;
} else if (nNxtButtonPressed == 1) { // If grey right arrow on NXT is pressed, raise lift.
motor[lift] = 100;
motor[lift2] = 100;
motor[lift3] = 50;
} else {
motor[lift] = 0;
motor[lift2] = 0;
motor[lift3] = 0;
}
}
}
61 changes: 37 additions & 24 deletions Teleop_v2-tank.c
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
#pragma config(Hubs, S1, HTMotor, HTMotor, HTMotor, HTServo)
#pragma config(Sensor, S1, , sensorI2CMuxController)
#pragma config(Motor, mtr_S1_C1_1, leftTread, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C1_2, rightTread, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C2_1, lift, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C2_2, lift2, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C3_1, lift3, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C1_1, rightTread, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C1_2, leftTread, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C2_1, lift, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C2_2, lift2, tmotorTetrix, openLoop, reversed)
#pragma config(Motor, mtr_S1_C3_1, motorH, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C3_2, motorI, tmotorTetrix, openLoop)
#pragma config(Servo, srvo_S1_C4_1, horiz, tServoStandard)
#pragma config(Servo, srvo_S1_C4_2, vert1, tServoStandard)
#pragma config(Servo, srvo_S1_C4_3, vert2, tServoStandard)
#pragma config(Servo, srvo_S1_C4_1, horiz, tServoStandard)
#pragma config(Servo, srvo_S1_C4_2, vert1, tServoStandard)
#pragma config(Servo, srvo_S1_C4_3, vert2, tServoStandard)
#pragma config(Servo, srvo_S1_C4_4, servo4, tServoNone)
#pragma config(Servo, srvo_S1_C4_5, servo5, tServoNone)
#pragma config(Servo, srvo_S1_C4_6, servo6, tServoNone)
Expand Down Expand Up @@ -50,13 +50,13 @@ typedef struct {

// Keep track of lift speed
int liftSpeed;
int returnSpeed;

} State;

void getLatestInput(State *state, UserInput *input);
void handleDriveInputs(State *state, UserInput *input);
void handleLiftInputs(State *state, UserInput *input);
void handleSpecialButtons(State *state, UserInput *input);
void handleWristInputs(State *state, UserInput *input);
void verifyCommands(State *state);
void updateAllMotors(State *state);
Expand All @@ -71,8 +71,8 @@ void showDiagnostics(State *state);
void initializeRobot()
{
servo[horiz] = 0;
servo[vert1] = 225;
servo[vert2] = 220;
servo[vert1] = 225;

// Disable joystick driver's diagnostics display to free up nxt screen for our own diagnostics diplay
disableDiagnosticsDisplay();
Expand Down Expand Up @@ -130,10 +130,10 @@ task main()
// Initialize state values
State currentState;
memset(&currentState, 0, sizeof(currentState));
currentState.vert1Pos = 225;
currentState.vert2Pos = 220;
currentState.vert1Pos = 225;

//waitForStart(); // wait for start of tele-op phase
wait1Msec(1000); //waitForStart(); // wait for start of tele-op phase

while (true)
{
Expand All @@ -144,6 +144,7 @@ task main()
// Process user inputs
handleDriveInputs(&currentState, &input);
handleLiftInputs(&currentState, &input);
handleSpecialButtons(&currentState, &input);
handleWristInputs(&currentState, &input);

// Verify validity/possibility of commands
Expand Down Expand Up @@ -204,20 +205,32 @@ void handleDriveInputs(State *state, UserInput *input)
state->rightTreadSpeed = 0;
}


}
}

void handleLiftInputs(State *state, UserInput *input)
{
if (joyButton(input->joy.joy2_Buttons, 6)) {
state->liftSpeed = 100;
state->returnSpeed = 10;
} else if (joyButton(input->joy.joy2_Buttons, 8)) {
state->liftSpeed = -10;
state->returnSpeed = -100;
state->liftSpeed = -30;
} else {
state->liftSpeed = 0;
state->returnSpeed = 0;
}
}

void handleSpecialButtons(State *state, UserInput *input) {
if (joyButton(input->joy.joy1_Buttons, 2)) {
state->liftSpeed = 100;
for (int i = 0; i < 2000; i++) {
getLatestInput(state, input);
if (joyButton(input->joy.joy1_Buttons, 4)) {
break;
}
updateAllMotors(state);
wait1Msec(1);
}
state->liftSpeed = 0;
updateAllMotors(state);
}
}

Expand All @@ -233,11 +246,11 @@ void handleWristInputs(State *state, UserInput *input)
// Controls for synchronized movement of vertical servos
// (keeps the angle of the hand relative to the ground constant)
if (joyButton(input->joy.joy2_Buttons, 4)) {
state->vert1Pos += WRISTSPEED;
state->vert2Pos += WRISTSPEED;
} else if (joyButton(input->joy.joy2_Buttons, 2)) {
state->vert1Pos -= WRISTSPEED;
state->vert2Pos -= WRISTSPEED;
} else if (joyButton(input->joy.joy2_Buttons, 2)) {
state->vert1Pos += WRISTSPEED;
state->vert2Pos += WRISTSPEED;
}

// Controls for individual movement of 2nd vertical servo
Expand All @@ -249,10 +262,12 @@ void handleWristInputs(State *state, UserInput *input)
}
}



void verifyCommands(State *state)
{
// If the projected servo values aren't within the servos' ranges,
// stay at the servos' current positions.bFloatDuringInactiveMotorPWM = true;
// stay at the servos' current positions.

// Servo Ranges
// Horiz Servo: 0 - 255
Expand All @@ -276,7 +291,6 @@ void updateAllMotors(State *state)
motor[rightTread] = state->rightTreadSpeed;
motor[lift] = state->liftSpeed;
motor[lift2] = state->liftSpeed;
motor[lift3] = state->returnSpeed;
servo[horiz] = state->horizPos;
servo[vert1] = state->vert1Pos;
servo[vert2] = state->vert2Pos;
Expand All @@ -290,7 +304,6 @@ void showDiagnostics(State *state)
string sWristVert2Pos = "vert2 = ";
string batteryLevel = "power = ";


//store variable in a string
string string1 = state->horizPos;
string string2 = state->vert1Pos;
Expand Down
Loading

0 comments on commit 85e0ff6

Please sign in to comment.