speed counter
This commit is contained in:
@@ -8,7 +8,15 @@
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[env:wemos_d1_mini32]
|
||||
[env:esp32-c3]
|
||||
platform = espressif32
|
||||
board = wemos_d1_mini32
|
||||
board = lolin_c3_mini
|
||||
framework = arduino
|
||||
monitor_speed = 115200
|
||||
lib_deps =
|
||||
#gyverlibs/AccelMotor@^1.3
|
||||
#simplefoc/SimpleDCMotor@^1.0.1
|
||||
lib_ldf_mode = deep+
|
||||
build_flags =
|
||||
-DCORE_DEBUG_LEVEL=3
|
||||
-DNDEF_DEBUG=1
|
||||
|
||||
@@ -11,11 +11,16 @@
|
||||
#define ENC_COUNT_REV (500 * 11) //12rmp motor
|
||||
|
||||
// Encoder output to Arduino Interrupt pin. Tracks the pulse count.
|
||||
#define ENC_IN_RIGHT_A 2
|
||||
#define ENC_IN_RIGHT_A 10
|
||||
|
||||
// Other encoder output to Arduino to keep track of wheel direction
|
||||
// Tracks the direction of rotation.
|
||||
#define ENC_IN_RIGHT_B 4
|
||||
#define ENC_IN_RIGHT_B 9
|
||||
|
||||
#define MOTOR_IN1 6
|
||||
#define MOTOR_IN2 7
|
||||
|
||||
#define SPEED 92
|
||||
|
||||
// True = Forward; False = Reverse
|
||||
bool Direction_right = true;
|
||||
@@ -25,6 +30,7 @@ volatile long right_wheel_pulse_count = 0;
|
||||
|
||||
// One-second interval for measurements
|
||||
int interval = 1000;
|
||||
int swapdelay = 500;
|
||||
|
||||
// Counters for milliseconds during interval
|
||||
long previousMillis = 0;
|
||||
@@ -39,21 +45,82 @@ float ang_velocity_right_deg = 0;
|
||||
|
||||
const float rpm_to_radians = 0.10471975512;
|
||||
const float rad_to_deg = 57.29578;
|
||||
bool dir = false;
|
||||
|
||||
void right_wheel_pulse();
|
||||
|
||||
void run_stop()
|
||||
{
|
||||
digitalWrite(MOTOR_IN1, LOW);
|
||||
digitalWrite(MOTOR_IN2, LOW);
|
||||
log_i("stop");
|
||||
|
||||
}
|
||||
|
||||
void run_to()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void run_left()
|
||||
{
|
||||
run_stop();
|
||||
delay(swapdelay);
|
||||
digitalWrite(MOTOR_IN1, LOW);
|
||||
analogWrite(MOTOR_IN2, SPEED);
|
||||
log_i("left");
|
||||
|
||||
dir = true;
|
||||
}
|
||||
|
||||
void run_right()
|
||||
{
|
||||
run_stop();
|
||||
delay(swapdelay);
|
||||
digitalWrite(MOTOR_IN2, LOW);
|
||||
analogWrite(MOTOR_IN1, SPEED);
|
||||
log_i("right");
|
||||
|
||||
dir = false;
|
||||
}
|
||||
|
||||
bool run_to_pos()
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
void swap_dir()
|
||||
{
|
||||
if(dir)
|
||||
{
|
||||
run_right();
|
||||
}
|
||||
else{
|
||||
run_left();
|
||||
}
|
||||
log_i("swap");
|
||||
}
|
||||
|
||||
void setup() {
|
||||
|
||||
// Open the serial port at 9600 bps
|
||||
serial.begin(9600);
|
||||
Serial.begin(115200);
|
||||
|
||||
// Set pin states of the encoder
|
||||
pinMode(ENC_IN_RIGHT_A , INPUT_PULLUP);
|
||||
pinMode(ENC_IN_RIGHT_B , INPUT);
|
||||
pinMode(MOTOR_IN1, OUTPUT);
|
||||
pinMode(MOTOR_IN2, OUTPUT);
|
||||
|
||||
|
||||
// Every time the pin goes high, this is a pulse
|
||||
attachInterrupt(digitalPinToInterrupt(ENC_IN_RIGHT_A), right_wheel_pulse, RISING);
|
||||
|
||||
|
||||
run_left();
|
||||
}
|
||||
|
||||
long swaptime = 0;
|
||||
|
||||
void loop() {
|
||||
|
||||
// Record the time
|
||||
@@ -69,7 +136,7 @@ void loop() {
|
||||
ang_velocity_right = rpm_right * rpm_to_radians;
|
||||
ang_velocity_right_deg = ang_velocity_right * rad_to_deg;
|
||||
|
||||
Serial.print(" Pulses: ");
|
||||
Serial.print(" Pulses/s: ");
|
||||
Serial.println(right_wheel_pulse_count);
|
||||
Serial.print(" Speed: ");
|
||||
Serial.print(rpm_right);
|
||||
@@ -83,8 +150,19 @@ void loop() {
|
||||
Serial.println();
|
||||
|
||||
right_wheel_pulse_count = 0;
|
||||
|
||||
}
|
||||
|
||||
if(millis() - swaptime > 5000)
|
||||
{
|
||||
swaptime = millis();
|
||||
swap_dir();
|
||||
|
||||
}
|
||||
|
||||
// if(rpm_right < 1 && dir)
|
||||
// {
|
||||
// run_stop();
|
||||
// }
|
||||
}
|
||||
|
||||
// Increment the number of pulses by 1
|
||||
@@ -106,4 +184,5 @@ void right_wheel_pulse() {
|
||||
else {
|
||||
right_wheel_pulse_count--;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user