diff --git a/docs/LinearHallTrace_3rd_motor_120deg.png b/docs/LinearHallTrace_3rd_motor_120deg.png deleted file mode 100644 index 2caab2f..0000000 Binary files a/docs/LinearHallTrace_3rd_motor_120deg.png and /dev/null differ diff --git a/docs/motor.jpg b/docs/motor.jpg deleted file mode 100644 index b632122..0000000 Binary files a/docs/motor.jpg and /dev/null differ diff --git a/docs/traces.png b/docs/traces.png deleted file mode 100644 index 48aa2ba..0000000 Binary files a/docs/traces.png and /dev/null differ diff --git a/src/joystickXY.cppok b/src/joystickXY.cppok new file mode 100644 index 0000000..0a8b6e5 --- /dev/null +++ b/src/joystickXY.cppok @@ -0,0 +1,113 @@ +#include +#include + +MagneticSensorAnalog sensor = MagneticSensorAnalog(A0, 183, 512); + +BLDCMotor motorX = BLDCMotor(4); +BLDCDriver3PWM driverX = BLDCDriver3PWM(3, 5, 6); + +BLDCMotor motorY = BLDCMotor(4); +BLDCDriver3PWM driverY = BLDCDriver3PWM(7, 8, 9); + +float targetX = 0.0; +float targetY = 0.0; + +float target = 6.3; + +void setup() +{ + sensor.init(); + // motorY.linkSensor(&sensor); + + // X MOTR STUFF + driverX.voltage_power_supply = 5.0; + driverX.init(); + motorX.linkDriver(&driverX); + motorX.foc_modulation = FOCModulationType::SpaceVectorPWM; + motorX.controller = MotionControlType::angle_openloop; + motorX.voltage_limit = 0.6; + // motorX.PID_velocity.P = 0.001f; + // motorX.PID_velocity.I = 20; + // motorX.PID_velocity.D = 0; + // motorX.LPF_velocity.Tf = 0.01f; + // motorX.P_angle.P = 20; + motorX.velocity_limit = 10; + + // *************** Y MOTOR STUFF ****************** + driverY.voltage_power_supply = 5.0; + driverY.init(); + motorY.linkDriver(&driverY); + motorY.foc_modulation = FOCModulationType::SinePWM; + motorY.controller = MotionControlType::angle_openloop; + motorY.voltage_limit = 0.6; + // motorY.PID_velocity.P = 0.001f; + // motorY.PID_velocity.I = 0; + // motorY.PID_velocity.D = 0; + // motorY.LPF_velocity.Tf = 0.01f; + // motorY.P_angle.P = 0.1; + motorY.velocity_limit = 10; + + Serial.begin(115200); + _delay(100); + Serial.println("INIT"); + + // initialize motor + motorX.init(); + motorX.initFOC(); + motorY.init(); + motorY.initFOC(); + + Serial.println(F("Motor ready.")); + _delay(1000); + // Serial.println(sensor.getPreciseAngle()); +} + +void serialLoop() +{ + static String received_chars; + while (Serial.available()) + { + char inChar = (char)Serial.read(); + received_chars += inChar; + if (inChar == '\n') + { + target = received_chars.toFloat(); + Serial.print("Target = "); + Serial.print(target); + received_chars = ""; + } + } +} + +float mapfloat(float x, float in_min, float in_max, float out_min, float out_max) +{ + return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min; +} + +void loop() +{ + sensor.update(); + + serialLoop(); + + int senseX = analogRead(A2); + int senseY = analogRead(A3); + + targetX = mapfloat(senseX, 0.0, 1024.0, -0.6, 1.2); + targetY = mapfloat(senseY, 0.0, 1024.0, -0.5, 2.2); + + Serial.print("senseX="); + Serial.print(senseX); + Serial.print("\t mappedX="); + Serial.print(targetX); + Serial.print("\t senseY="); + Serial.print(senseY); + Serial.print("\t mappedY="); + Serial.println(targetY); + + motorX.move(targetX); + motorX.loopFOC(); + + motorY.move(targetY); + motorY.loopFOC(); +} \ No newline at end of file diff --git a/src/main.cppfr b/src/main.cppfr deleted file mode 100644 index 4eec6ca..0000000 --- a/src/main.cppfr +++ /dev/null @@ -1,38 +0,0 @@ -// Test file - -#include - -const int analogInPin = A2; // Analog input pin that the potentiometer is attached to -//const int analogOutPin = 9; // Analog output pin that the LED is attached to - -int sensorValue = 0; // value read from the pot -int maxValue = 200; -int minValue = 200; - -void setup() { - // initialize serial communications at 9600 bps: - Serial.begin(115200); -} - -void loop() { - // read the analog in value: - sensorValue = analogRead(analogInPin); - - if(sensorValue > maxValue) - { - maxValue = sensorValue; - } - else if(sensorValue < minValue) - { - minValue = sensorValue; - } - - Serial.print("sensor = "); - Serial.print(sensorValue); - Serial.print("\t min="); - Serial.print(minValue); - Serial.print("\tmax="); - Serial.println(maxValue); - - delay(2); -} \ No newline at end of file