update vars

This commit is contained in:
Cole Deck 2023-09-29 00:13:19 -05:00
parent 339c8ca1a6
commit 55a0b6549f
3 changed files with 20 additions and 22 deletions

View File

@ -26,3 +26,4 @@ lib_deps =
107-systems/107-Arduino-Servo-RP2040@^0.1.0 107-systems/107-Arduino-Servo-RP2040@^0.1.0
debug_tool = cmsis-dap debug_tool = cmsis-dap
build_flags = -O3 build_flags = -O3
; upload_protocol = cmsis-dap

View File

@ -17,7 +17,7 @@ extern long last_p;
// Loop timing // Loop timing
#define LOOP_DELAY_MS_CORE_0 50 // Minimum milliseconds between the start of each loop, accounting for processing time during each loop #define LOOP_DELAY_MS_CORE_0 50 // Minimum milliseconds between the start of each loop, accounting for processing time during each loop
#define LOOP_DELAY_MS_CORE_1 50 // Minimum milliseconds between the start of each loop, accounting for processing time during each loop #define LOOP_DELAY_MS_CORE_1 50 // Minimum milliseconds between the start of each loop, accounting for processing time during each loop
#define LOOP_DELAY_SECONDS ((float)LOOP_DELAY_MS / 1000.0f) // Previous number expressed in seconds #define LOOP_DELAY_SECONDS ((float)LOOP_DELAY_MS_CORE_0 / 1000.0f) // Previous number expressed in seconds
// Math things // Math things
#define DEGREES_PER_RADIAN (180.0 / M_PI) #define DEGREES_PER_RADIAN (180.0 / M_PI)

View File

@ -44,13 +44,10 @@ PCF8574 ioex2(0x21, 20, 21);
// JANK: soldered to pico or headers // JANK: soldered to pico or headers
PioEncoder enc1(18); // Front Left PioEncoder enc1(18); // Front Left
PioEncoder enc2(14); // Front Right PioEncoder enc2(14); // Front Right
PioEncoder enc3(26); // Back Left PioEncoder enc3(27); // Back Left
PioEncoder enc4(0); // Back Right PioEncoder enc4(0); // Back Right
// pins for arm servos
#define ARM_SERVO_PIN_1 2
#define ARM_SERVO_PIN_2 3
#define ARM_SERVO_PIN_3 8
// stepper board slave pins // stepper board slave pins
#define MOTOR_X_ENABLE_PIN 8 #define MOTOR_X_ENABLE_PIN 8
@ -89,18 +86,13 @@ Sabertooth actuators(130, Serial2);
#define TALON_PIN_2 6 #define TALON_PIN_2 6
#define TALON_PIN_3 7 #define TALON_PIN_3 7
#define TALON_PIN_4 9 #define TALON_PIN_4 9
// pins for arm servos
#define ARM_SERVO_PIN_1 2
#define ARM_SERVO_PIN_2 3
#define ARM_SERVO_PIN_3 8
static _107_::Servo talon1, talon2, talon3, talon4, arm1, arm2, arm3; static _107_::Servo talon1, talon2, talon3, talon4, arm1, arm2, arm3;
typedef struct
{
int servoIndex;
uint8_t servoPin;
} ISR_servo_t;
#define NUM_SERVOS 7
MCP3008 adc; MCP3008 adc;
int count = 0; int count = 0;
int mode = 1; int mode = 1;
@ -410,11 +402,11 @@ void set_motor(byte motor, int speed) {
else if (motor == 5) else if (motor == 5)
talon1.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET)); talon1.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET));
else if (motor == 6) else if (motor == 6)
talon1.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET)); talon2.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET));
else if (motor == 7) else if (motor == 7)
talon1.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET)); talon3.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET));
else if (motor == 8) else if (motor == 8)
talon1.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET)); talon4.writeMicroseconds(map(speed, -127, 127, MIN_MICROS - OC_OFFSET, MAX_MICROS - OC_OFFSET));
else if (motor <= 10) { else if (motor <= 10) {
// actuator controls // actuator controls
actuators.motor((motor - 9 + 1), speed); actuators.motor((motor - 9 + 1), speed);
@ -664,10 +656,14 @@ void setup() {
talon2.attach(TALON_PIN_2); talon2.attach(TALON_PIN_2);
talon3.attach(TALON_PIN_3); talon3.attach(TALON_PIN_3);
talon4.attach(TALON_PIN_4); talon4.attach(TALON_PIN_4);
for (int i = 5; i < 9; i++)
set_motor(i, 0);
arm1.attach(ARM_SERVO_PIN_1); arm1.attach(ARM_SERVO_PIN_1);
arm2.attach(ARM_SERVO_PIN_2); arm2.attach(ARM_SERVO_PIN_2);
arm3.attach(ARM_SERVO_PIN_3); arm3.attach(ARM_SERVO_PIN_3);
for (int i = 15; i < 18; i++)
set_motor(i, 0);
Serial.println(" done"); Serial.println(" done");
@ -678,10 +674,11 @@ void setup() {
// Initialize encoders // Initialize encoders
Serial.print("Initializing encoders.."); Serial.print("Initializing encoders..");
set_hex(0x5); set_hex(0x5);
//enc1.begin(); enc1.begin();
//enc2.begin(); enc1.flip();
//enc3.begin(); enc2.begin();
//enc4.begin(); enc3.begin();
enc4.begin();
Serial.println(" done"); Serial.println(" done");
delay(20); delay(20);