basic joystick controls

This commit is contained in:
Skylar Grant 2023-10-05 11:20:13 -04:00
parent 9a51e87bc5
commit 9fe96bc99b
3 changed files with 145 additions and 41 deletions

32
.vscode/etc_snippets.code-snippets vendored Normal file
View File

@ -0,0 +1,32 @@
{
// Place your etc244 workspace snippets here. Each snippet is defined under a snippet name and has a scope, prefix, body and
// description. Add comma separated ids of the languages where the snippet is applicable in the scope field. If scope
// is left empty or omitted, the snippet gets applied to all languages. The prefix is what is
// used to trigger the snippet and the body will be expanded and inserted. Possible variables are:
// $1, $2 for tab stops, $0 for the final cursor position, and ${1:label}, ${2:another} for placeholders.
// Placeholders with the same ids are connected.
// Example:
// "Print to console": {
// "scope": "javascript,typescript",
// "prefix": "log",
// "body": [
// "console.log('$1');",
// "$2"
// ],
// "description": "Log output to console"
// }
"Function Descriptor": {
"scope": "c",
"prefix": "//",
"body": [
"/* $1",
" *",
" * Arguments:",
" * $2",
" *",
" * Notes:",
" * $3",
"*/$0"
]
}
}

150
Labs.c
View File

@ -1,23 +1,20 @@
#pragma config(Sensor, in3, armPos, sensorPotentiometer) #pragma config(Sensor, in1, armPos, sensorPotentiometer)
#pragma config(Sensor, in4, lightRight, sensorReflection) #pragma config(Sensor, in2, lightR, sensorReflection)
#pragma config(Sensor, in5, lightLeft, sensorReflection) #pragma config(Sensor, in3, lightL, sensorReflection)
#pragma config(Sensor, in6, lineLeft, sensorLineFollower) #pragma config(Sensor, dgtl3, buttonStart, sensorDigitalIn)
#pragma config(Sensor, in7, lineCenter, sensorLineFollower) #pragma config(Sensor, dgtl4, armLimit, sensorDigitalIn)
#pragma config(Sensor, in8, lineRight, sensorLineFollower) #pragma config(Sensor, dgtl5, buttonL, sensorDigitalIn)
#pragma config(Sensor, dgtl1, leftRotary1, sensorQuadEncoder) #pragma config(Sensor, dgtl6, rotaryR1, sensorQuadEncoder)
#pragma config(Sensor, dgtl3, rightRotary1, sensorQuadEncoder)
#pragma config(Sensor, dgtl5, frontBumper, sensorDigitalIn)
#pragma config(Sensor, dgtl6, rearBumper, sensorDigitalIn)
#pragma config(Sensor, dgtl7, startBumper, sensorDigitalIn)
#pragma config(Sensor, dgtl8, sonarIn, sensorSONAR_inch) #pragma config(Sensor, dgtl8, sonarIn, sensorSONAR_inch)
#pragma config(Sensor, dgtl10, armLimit, sensorDigitalIn) #pragma config(Sensor, dgtl10, rotaryL1, sensorQuadEncoder)
#pragma config(Motor, port1, rightMotor, tmotorVex393_HBridge, openLoop, reversed, driveRight, encoderPort, dgtl3) #pragma config(Sensor, dgtl12, buttonR, sensorDigitalIn)
#pragma config(Motor, port3, clawMotor, tmotorVex393HighSpeed_MC29, openLoop) #pragma config(Motor, port1, leftMotor, tmotorVex393_HBridge, openLoop, reversed, driveLeft)
#pragma config(Motor, port4, armMotor, tmotorVex393_MC29, openLoop) #pragma config(Motor, port2, clawMotor, tmotorVex393_MC29, openLoop)
#pragma config(Motor, port10, leftMotor, tmotorVex393_HBridge, openLoop, reversed, driveLeft, encoderPort, dgtl1) #pragma config(Motor, port3, armMotor, tmotorVex393_MC29, openLoop)
//^^!!Code automatically generated by 'ROBOTC' configuration wizard!!^^// #pragma config(Motor, port10, rightMotor, tmotorVex393_HBridge, openLoop, reversed, driveRight)
//*!!Code automatically generated by 'ROBOTC' configuration wizard !!*//
//=====================================================================// //==================================================================================//
/* Progressive Development Code /* Progressive Development Code
* for ETC 244 VeX Robotics Lab * for ETC 244 VeX Robotics Lab
@ -25,13 +22,13 @@
* Fall 2023-2024 * Fall 2023-2024
* *
* Developed by Skylar Grant * Developed by Skylar Grant
* *
* Notes: This bot and its configuration are non-standard. My sensors are * Notes: This bot and its configuration are non-standard. My sensors are
* located in different locations than usual, and are plugged into * located in different locations than usual, and are plugged into
* different ports than usual. * different ports than usual.
*/ */
//=====================================================================// //==================================================================================//
/* Quick function to set the speed of the drive motors /* Quick function to set the speed of the drive motors
* *
@ -48,7 +45,35 @@ void setMotors(int leftSpeed, int rightSpeed) {
motor[rightMotor] = rightSpeed; motor[rightMotor] = rightSpeed;
} }
//=====================================================================// /* Quickly set the arm motor speed
*
* Arguments:
* - speed: signed integer, -127 to 127
* - Speed to drive the arm motor
*
* Notes:
* This is a very superfluous function but I hate typing motor[motorName] = 127 constantly
*/
void setArm(int speed) {
// Set the arm motor speed
motor[armMotor] = speed;
}
/* Quickly set the claw motor speed
*
* Arguments:
* - speed: signed integer, -127 to 127
* - Speed to drive the claw motor
*
* Notes:
* This is a very superfluous function but I hate typing motor[motorName] = 127 constantly
*/
void setClaw(int speed) {
// Set the claw motor speed
motor[clawMotor] = speed;
}
//==================================================================================//
/* Quick function to stop both drive motors /* Quick function to stop both drive motors
* *
@ -61,7 +86,7 @@ void stop() {
motor[rightMotor] = 0; motor[rightMotor] = 0;
} }
//=====================================================================// //==================================================================================//
/* Function to drive the bot forward for some time /* Function to drive the bot forward for some time
* *
@ -80,7 +105,7 @@ void driveForward(int speed, int timeMs) {
stop(); stop();
} }
//=====================================================================// //==================================================================================//
/* Function to drive the bot backwards for some time /* Function to drive the bot backwards for some time
* *
@ -101,7 +126,7 @@ void driveBackward(int speed, int timeMs) {
stop(); stop();
} }
//=====================================================================// //==================================================================================//
// TODO: Just combine this into one drive function with L/R/B and a reverse boolean // TODO: Just combine this into one drive function with L/R/B and a reverse boolean
/* Function to drive only one side's drive motors for a given time /* Function to drive only one side's drive motors for a given time
@ -127,7 +152,7 @@ void driveOneSide(char *side, int speed, int timeMs) {
stop(); stop();
} }
//=====================================================================// //==================================================================================//
// TODO: Flesh out this function // TODO: Flesh out this function
//void drive(char *side, int speed, int timeMs, int reverse) //void drive(char *side, int speed, int timeMs, int reverse)
@ -173,7 +198,7 @@ void turn(char *direction, int speed, int timeMs, bool reverse) {
stop(); stop();
} }
//=====================================================================// //==================================================================================//
/* Move the bot's arm up or down /* Move the bot's arm up or down
* *
@ -218,7 +243,7 @@ void armUp100(int speed) {
motor[armMotor] = 0; motor[armMotor] = 0;
} }
//=====================================================================// //==================================================================================//
/* Moves the robot's arm down until the limit switch is pressed /* Moves the robot's arm down until the limit switch is pressed
* *
@ -243,7 +268,7 @@ void armDown100(int speed) {
motor[armMotor] = 0; motor[armMotor] = 0;
} }
//=====================================================================// //==================================================================================//
/* Close the claw /* Close the claw
* *
@ -260,7 +285,7 @@ void clawGrab() {
motor[clawMotor] = 0; motor[clawMotor] = 0;
} }
//=====================================================================// //==================================================================================//
/* Open the claw /* Open the claw
* *
@ -277,7 +302,7 @@ void clawRelease() {
motor[clawMotor] = 0; motor[clawMotor] = 0;
} }
//=====================================================================// //==================================================================================//
/* Run the autonomous code, called when the start button is pressed. /* Run the autonomous code, called when the start button is pressed.
* *
@ -312,28 +337,75 @@ void runAutonomous() {
armUp100(32); armUp100(32);
clawRelease(); clawRelease();
clawGrab(); clawGrab();
armDown100(16); armDown100(32);
} }
//=====================================================================// //==================================================================================//
/* Wait for the start button to be pressed, then run autonomous code. /* Wait for the start button to be pressed, then run autonomous code.
* *
* Arguments: None * Arguments: None
*/ */
void waitForStart() { void waitForStart() {
while (SensorValue[startBumper]==1) {
wait1Msec(500);
}
// Once we've detected a button press, run the autonomous function block.
runAutonomous();
// TODO: Experimental, hoping this will call this function again when done instead of exiting // TODO: Experimental, hoping this will call this function again when done instead of exiting
waitForStart(); waitForStart();
} }
//=====================================================================// //==================================================================================//
// This function gets called automatically once the bot is booted. // This function gets called automatically once the bot is booted.
task main() { task main() {
waitForStart(); while (SensorValue[buttonStart]==1) {
// Driver Mode, Controller Inputs
int leftSpeed = (vexRT[Ch2] + vexRT[Ch1]) / 2; // (y + x) / 2
int rightSpeed = (vexRT[Ch2] - vexRT[Ch1])/2; // (y - x) / 2
float leftAdjSpeed = leftSpeed / 10;
float rightAdjSpeed = rightSpeed / 10;
leftAdjSpeed = floor(leftAdjSpeed) * 10;
rightAdjSpeed = floor(rightAdjSpeed) * 10;
if (fabs(leftAdjSpeed) > 30) {
motor[leftMotor] = leftAdjSpeed;
} else {
motor[leftMotor] = 0;
}
if (fabs(rightAdjSpeed) > 30) {
motor[rightMotor] = rightAdjSpeed;
} else {
motor[rightMotor] = 0;
}
// Raise, lower or do not move arm
if(vexRT[Btn7U] == 1) //If button 5U is pressed...
{
motor[armMotor] = 32; //...raise the arm.
}
else if(vexRT[Btn7D] == 1) //Else, if button 5D is pressed...
{
motor[armMotor] = -32; //...lower the arm.
}
else //Else (neither button is pressed)...
{
motor[armMotor] = 0; //...stop the arm.
}
// Open, close or do not more claw
if(vexRT[Btn7L] == 1) //If Button 6U is pressed...
{
motor[clawMotor] = 64; //...close the gripper.
}
else if(vexRT[Btn7R] == 1) //Else, if button 6D is pressed...
{
motor[clawMotor] = -32; //...open the gripper.
}
else //Else (neither button is pressed)...
{
motor[clawMotor] = 0; //...stop the gripper.
}
}
// Once we've detected a button press, run the autonomous function block.
runAutonomous();
} }

View File

@ -42,8 +42,8 @@ DIGITAL
05 - LEFT REAR BUTTON* 05 - LEFT REAR BUTTON*
06 - RIGHT ROTARY ENCODER 1 06 - RIGHT ROTARY ENCODER 1
07 - RIGHT ROTARY ENCODER 2 07 - RIGHT ROTARY ENCODER 2
08 - SONAR OUT 08 - SONAR IN
09 - SONAR IN 09 - SONAR OUT
10 - LEFT ROTARY ENCODER 1 10 - LEFT ROTARY ENCODER 1
11 - LEFT ROTARY ENCODER 2 11 - LEFT ROTARY ENCODER 2
12 - RIGHT REAR BUTTON* 12 - RIGHT REAR BUTTON*