Closed jonathanshu87 closed 4 months ago
Plan to take potentiometer output from analog pin after applying exponential moving algorithm and map the values to motor rotation.
Using arduino map() function to convert these ranges
To decrease latency:
#include <SoftwareSerial.h>
#define STEP_INCREMENT 1.0 // Initial radian increment for searching limits
#define FINE_TUNE_INCREMENT 0.1 // Smaller increment for fine-tuning edge detection
SoftwareSerial serialMotor0(8, 9); // RX, TX
float minLimitM0 = -10.0;
float maxLimitM0 = 10.0;
SoftwareSerial serialMotor1(10, 11); // RX, TX
float minLimitM1 = -10.0;
float maxLimitM1 = 10.0;
void setup() {
Serial.begin(115200);
serialMotor0.begin(115200);
//serialMotor1.begin(9600);
//calibrationMotor();
//delay(10000);
}
void loop() {
playerControl(0);
controlSerialData();
}
int prev= 0;
int scaledValue = 0;
int potValue = 0;
void playerControl(int id){
potValue = analogRead(A0);
//int scaledValue = map(potValue, 0, 1023, 0, 100);
//scaledValue = map(analogRead(A0), 0, 1023, 0, 100);
//moveMotor(0, potValue, -1);
if ((prev - potValue > 2) || (potValue - prev > 2)){
moveMotor(id, potValue, -1);
prev = potValue;
}
}
void controlSerialData(){
if (Serial.available() > 0) {
// Read the input from the Serial Monitor
String input = Serial.readStringUntil('\n');
// Send the input to the other Arduino
serialMotor0.println(input);
}
// Check if there is any message from the other Arduino
if (serialMotor0.available() > 0) {
// Read the message
String messageReceived = serialMotor0.readStringUntil('\n');
// Print the received message to the Serial Monitor
Serial.print("Received: ");
Serial.println(messageReceived);
}
}
/*
* id : which motor we want to control, 0 or 1
* position : position between 0 and 1023 that we want the motor to goes to
* speed : speed in rad/s that we want to move
*/
void moveMotor(int id, float position, float speed){
if (position < 0 || position >1023 ){
return;
}
String speedString = (speed == -1) ? "" : " " + String(speed, 2);
if(id == 0){
float range = maxLimitM0 - minLimitM0;
float targetPosition = minLimitM0 + (position / 1023.0) * range;
serialMotor0.println("M" + String(targetPosition, 2) + speedString);
}
if (id == 1){
float range = maxLimitM1 - minLimitM1;
float targetPosition = minLimitM1 + (position / 100.0) * range;
serialMotor1.println("M" + String(targetPosition, 2) + speedString);
}
}
void calibrationMotor(){
// Move to minimum limit
findEdge(0, serialMotor0);
findEdge(1, serialMotor1);
}
void findEdge(int id, SoftwareSerial serialMotor) {
float position = 0.0;
float increment = STEP_INCREMENT;
while (!checkEdgeReached(id)) {
position -= increment;
serialMotor.println("M" + String(position, 2) + " 10");
delay(200); // Allow motor to move
//increment = FINE_TUNE_INCREMENT;
}
if (id == 0){
minLimitM0 = position;
}
else {
minLimitM1 = position;
}
increment = STEP_INCREMENT;
delay(500);
while (!checkEdgeReached(id)) {
position += increment;
serialMotor.println("M" + String(position, 2) + " 10");
delay(200); // Allow motor to move
increment = FINE_TUNE_INCREMENT;
}
if (id == 0){
maxLimitM0 = position;
}
else {
maxLimitM1 = position;
}
}
String searchString = "paddle_position :";
bool checkEdgeReached(int id) {
while (true) {
if (Serial.available() > 0) {
String inputString = Serial.readStringUntil('\n');
searchString = String(id, 1) + searchString;
int index = inputString.indexOf(searchString);
if (index != -1) {
float value = inputString.substring(index + searchString.length()).toFloat();
return (value >= 99.9 || value <= 0.1);
}
}
}
return false;
}
#include <Arduino.h>
#include <SimpleFOC.h>
BLDCMotor motor = BLDCMotor(7, 0.025); // br3536 kv1200
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
Commander commander = Commander(Serial);
void onMotion(char* cmd) { commander.motion(&motor, cmd); }
String searchString = "Initial position :";
void setup() {
Wire.setClock(400000);
sensor.init();
motor.linkSensor(&sensor);
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
currentSense.linkDriver(&driver);
currentSense.init();
currentSense.skip_align = true;
motor.linkCurrentSense(¤tSense);
motor.controller = MotionControlType::angle;
//motor.voltage_limit = 12;
motor.current_limit = 35;
motor.velocity_limit = 1000;
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20;
motor.PID_velocity.D = 0.001;
motor.PID_velocity.output_ramp = 1000;
motor.LPF_velocity.Tf = 0.01;
Serial.begin(115200);
motor.useMonitoring(Serial);
//motor.zero_electric_angle = 1.07;
//motor.sensor_direction = Direction::CCW;
motor.init();
motor.initFOC();
commander.add('M', onMotion, "motion control");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target angle using serial terminal:"));
_delay(1000);
}
void loop() {
motor.loopFOC();
motor.move();
commander.run();
}
Send a command to the motor driver giving the position wanted (and eventually the speed we want)