mirror of
https://github.com/okalachev/flix.git
synced 2026-01-13 14:36:45 +00:00
More cleanups
This commit is contained in:
@@ -1,46 +1,25 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// https://habr.com/ru/company/first/blog/664922/
|
||||
// esc: https://aliexpress.com/item/4000280617058.html (KINGDUO Micro Mini 4A 1S Brushed Esc 3.6-6V)
|
||||
// motor: https://aliexpress.com/item/32731613504.html (8520 3.7V)
|
||||
// Motors output
|
||||
// Motor: 8520 3.7V
|
||||
// ESC: KINGDUO Micro Mini 4A 1S Brushed Esc 3.6-6V
|
||||
|
||||
#define MOTOR_0_PIN 12
|
||||
#define MOTOR_1_PIN 13
|
||||
#define MOTOR_2_PIN 14
|
||||
#define MOTOR_3_PIN 15
|
||||
|
||||
// #define PWM_FREQUENCY 200
|
||||
// #define PWM_FREQUENCY 50 // TODO: way low frequency considering the IMU is 1kHz
|
||||
#define PWM_FREQUENCY 200 // WARNING: original 50
|
||||
|
||||
#define PWM_FREQUENCY 200
|
||||
#define PWM_RESOLUTION 8
|
||||
|
||||
// #define PWM_MIN 1575
|
||||
// #define PWM_MAX 2300
|
||||
#define PWM_NEUTRAL 1500
|
||||
// #define PWM_REVERSE_MAX 700
|
||||
// #define PWM_REVERSE_MIN 1425
|
||||
|
||||
// static const uint16_t pwmMin[] = {1600-50, 1600-50, 1600-50, 1600-50};
|
||||
// static const uint16_t pwmMax[] = {2100, 2300, 2000, 2000}; // NOTE: ORIGINAL
|
||||
|
||||
static const uint16_t pwmMin[] = {1600, 1600, 1600, 1600}; // NOTE: success
|
||||
// static const uint16_t pwmMax[] = {2000, 2000, 2000, 2000}; // NOTE: success
|
||||
static const uint16_t pwmMin[] = {1600, 1600, 1600, 1600};
|
||||
static const uint16_t pwmMax[] = {2300, 2300, 2300, 2300};
|
||||
// from esc description
|
||||
// static const uint16_t pwmMin[] = {1600, 1600, 1600, 1600};
|
||||
// static const uint16_t pwmMax[] = {2300, 2300, 2300, 2300};
|
||||
|
||||
// static const uint16_t pwmReverseMin[] = {1420+50, 1440+50, 1440+50, 1440+50};
|
||||
|
||||
// static const uint16_t pwmReverseMin[] = {1420, 1440, 1440, 1440};
|
||||
// static const uint16_t pwmReverseMax[] = {700, 1100, 1100, 1100}; // NOTE: ???
|
||||
static const uint16_t pwmReverseMin[] = {1390, 1440, 1440, 1440};
|
||||
static const uint16_t pwmReverseMax[] = {1100, 1100, 1100, 1100};
|
||||
|
||||
bool useBreak; // TODO: redesign
|
||||
|
||||
void setupMotors() {
|
||||
Serial.println("Setup Motors");
|
||||
|
||||
@@ -56,12 +35,6 @@ void setupMotors() {
|
||||
ledcAttachPin(MOTOR_2_PIN, 2);
|
||||
ledcAttachPin(MOTOR_3_PIN, 3);
|
||||
|
||||
// send initial break to initialize ESCs
|
||||
// Serial.println("Calibrating ESCs");
|
||||
// useBreak = true;
|
||||
// sendMotors();
|
||||
// delay(2000);
|
||||
// useBreak = false;
|
||||
sendMotors();
|
||||
Serial.println("Motors initialized");
|
||||
}
|
||||
@@ -69,7 +42,7 @@ void setupMotors() {
|
||||
static uint16_t getPWM(float val, int n)
|
||||
{
|
||||
if (val == 0) {
|
||||
return PWM_NEUTRAL; // useBreak ? PWM_NEUTRAL : 0;
|
||||
return PWM_NEUTRAL;
|
||||
} else if (val > 0) {
|
||||
return mapff(val, 0, 1, pwmMin[n], pwmMax[n]);
|
||||
} else {
|
||||
|
||||
Reference in New Issue
Block a user