From 3641ba1596f0e46f2e40b3101e3e1e4b6e796b39 Mon Sep 17 00:00:00 2001 From: antrob25 Date: Tue, 26 Apr 2022 15:32:53 -0500 Subject: [PATCH] bruh --- powerboardcode/powerboard/powerboard.h | 2 +- powerboardcode/powerboard/powerboard.ino | 16 +++++++--------- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/powerboardcode/powerboard/powerboard.h b/powerboardcode/powerboard/powerboard.h index 92fb1bf..66b96e2 100644 --- a/powerboardcode/powerboard/powerboard.h +++ b/powerboardcode/powerboard/powerboard.h @@ -92,7 +92,7 @@ uint8_t twelveLogicOverCurrent = 0; #define MOTOR6_CTL 30 #define MOTORS_CTL 36 -#define MOTOR_DELAY 750 +#define MOTOR_DELAY 500 //uint8_t currentSense12V[] = {MULTIMEDIA_SENSE, NAV_SENSE, GIMBAL_ACT_SENSE, DRIVE_SENSE, SCISENSOR_ACT_SENSE, NETSWITCH_SENSE, CAM1_SENSE, CAM2_SENSE, BBB_SENSE, AUX_LOG_SENSE}; uint8_t twelveVoltBusses[NUM_12V_PORTS] = {GIMBAL_CTL, DRIVE_CTL, MULTIMEDIA_CTL, NAV_CTL, CAM1_CTL, CAM2_CTL, BBB_CTL, SPARE_CTL}; diff --git a/powerboardcode/powerboard/powerboard.ino b/powerboardcode/powerboard/powerboard.ino index a567816..26bd099 100644 --- a/powerboardcode/powerboard/powerboard.ino +++ b/powerboardcode/powerboard/powerboard.ino @@ -2,11 +2,10 @@ void setup() { Serial.begin(115200); - Telemetry.begin(telemetry, 150000); setPins(); setPinStates(); - Serial.begin(115200); RoveComm.begin(RC_POWERBOARD_FOURTHOCTET, &TCPServer, RC_ROVECOMM_POWERBOARD_MAC); + Telemetry.begin(telemetry, 1500000); } void loop() @@ -88,16 +87,15 @@ void loop() void setPins() { - // sets Spare to OUTPUT - pinMode(PACK_SPARE_CTL, OUTPUT); - pinMode(POE_CTL, OUTPUT); - // sets motor busses to OUTPUT for (int i = 0 ; i < NUM_MOTORS ; i++) { pinMode(motorBusses[i], OUTPUT); + digitalWrite(motorBusses[i], LOW); } + pinMode(PACK_SPARE_CTL, OUTPUT); + pinMode(POE_CTL, OUTPUT); // sets Aux to OUTPUT pinMode(AUX_CTL, OUTPUT); @@ -110,8 +108,6 @@ void setPins() void setPinStates() { - digitalWrite(POE_CTL, HIGH); - digitalWrite(PACK_SPARE_CTL, HIGH); // turns on 12 volt busses for (int i = 0 ; i < NUM_12V_PORTS ; i++) { @@ -127,6 +123,9 @@ void setPinStates() delay(MOTOR_DELAY); digitalWrite(motorBusses[i], HIGH); } + digitalWrite(PACK_SPARE_CTL, HIGH); + digitalWrite(POE_CTL, HIGH); + } float senseCurrent(const uint8_t sensePin) @@ -203,5 +202,4 @@ void telemetry() delay(100); RoveComm.write(RC_POWERBOARD_TWELVEVLOGICBUSCURRENT_DATA_ID, RC_POWERBOARD_TWELVEVLOGICBUSCURRENT_DATA_COUNT, TWELVELOGICBUSCURRENTS); delay(100); - Telemetry.begin(telemetry, 150000); } \ No newline at end of file