Adjust serial monitor speed and refine motor control logic

- Changed `monitor_speed` in `platformio.ini` from `115200` to `19200` for compatibility.
- Initialized `MotorControlInputs` struct members with default values.
- Uncommented digital write operations in `doMotor` for proper execution.
- Disabled debug output and monitoring configurations for cleaner operation.
- Adjusted motor tuning parameters by commenting out specific settings.
- Changed `Serial.begin(115200)` to `Serial.begin(19200)` in `setup()` to match the new monitor speed.
- Commented out `_delay(1000)` and `current_angle` variable to remove unnecessary delays and unused code.
This commit is contained in:
Ilya Uraev 2025-02-04 13:40:15 +03:00
parent 47a87711d9
commit d5f772cb6d
2 changed files with 16 additions and 14 deletions

View file

@ -16,7 +16,7 @@ board = genericSTM32F446RE
framework = arduino framework = arduino
upload_protocol = stlink upload_protocol = stlink
debug_tool = stlink debug_tool = stlink
monitor_speed = 115200 monitor_speed = 19200
monitor_parity = N monitor_parity = N
build_flags = build_flags =
-DSTM32F446xx -DSTM32F446xx

View file

@ -31,17 +31,17 @@ LowsideCurrentSense current_sense(0.01, 10.0, CURRENT_SENSOR_1,
Commander command(Serial); Commander command(Serial);
struct MotorControlInputs { struct MotorControlInputs {
float target_angle; float target_angle = 0.0;
float target_velocity; float target_velocity = 0.0;
bool motor_enabled; bool motor_enabled = false;
}; };
MotorControlInputs motor_control_inputs; MotorControlInputs motor_control_inputs;
void doMotor(char *cmd) { void doMotor(char *cmd) {
command.motor(&motor, cmd); command.motor(&motor, cmd);
// digitalWrite(PC10, !digitalRead(PC10)); digitalWrite(PC10, !digitalRead(PC10));
// delayMicroseconds(2); delayMicroseconds(2);
} }
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor, void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
@ -57,14 +57,14 @@ void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
current_sense->linkDriver(driver); current_sense->linkDriver(driver);
current_sense->init(); current_sense->init();
motor->linkCurrentSense(current_sense); motor->linkCurrentSense(current_sense);
SimpleFOCDebug::enable(nullptr); // SimpleFOCDebug::enable(nullptr);
commander->add('M', callback, "motor"); commander->add('M', callback, "motor");
motor->useMonitoring(Serial); motor->useMonitoring(Serial);
motor->monitor_start_char = 'M'; // motor->monitor_start_char = 'M';
motor->monitor_end_char = 'M'; // motor->monitor_end_char = 'M';
// motor->monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // motor->monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE;
motor->monitor_downsample = 10; // default 10 motor->monitor_downsample = 10; // default 10
commander->verbose = VerboseMode::user_friendly; // commander->verbose = VerboseMode::user_friendly;
motor->controller = MotionControlType::angle; motor->controller = MotionControlType::angle;
motor->torque_controller = TorqueControlType::voltage; motor->torque_controller = TorqueControlType::voltage;
motor->foc_modulation = FOCModulationType::SinePWM; motor->foc_modulation = FOCModulationType::SinePWM;
@ -75,11 +75,13 @@ void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
motor->LPF_velocity.Tf = 0.005; motor->LPF_velocity.Tf = 0.005;
motor->LPF_angle.Tf = 0.005; motor->LPF_angle.Tf = 0.005;
motor->P_angle.P = 15; motor->P_angle.P = 15;
// motor->P_angle.I = 15;
// motor->P_angle.3 = 15;
motor->velocity_limit = 40; motor->velocity_limit = 40;
motor->voltage_limit = 40; motor->voltage_limit = 40;
motor->current_limit = 0.5; motor->current_limit = 0.5;
motor->sensor_direction = Direction::CCW; motor->sensor_direction = Direction::CCW;
current_sense->skip_align = true; current_sense->skip_align = false;
motor->init(); motor->init();
motor->initFOC(); motor->initFOC();
} }
@ -166,7 +168,7 @@ void foc_step(BLDCMotor *motor, Commander *commander) {
void setup() { void setup() {
Serial.setRx(HARDWARE_SERIAL_RX_PIN); Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN); Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200); Serial.begin(19200);
// setup led pin // setup led pin
pinMode(PC11, OUTPUT); pinMode(PC11, OUTPUT);
pinMode(PC10, OUTPUT); pinMode(PC10, OUTPUT);
@ -180,10 +182,10 @@ void setup() {
SendTimer->attachInterrupt(send_data); SendTimer->attachInterrupt(send_data);
SendTimer->resume(); SendTimer->resume();
setup_foc(&encoder, &motor, &driver, &current_sense, &command, doMotor); setup_foc(&encoder, &motor, &driver, &current_sense, &command, doMotor);
_delay(1000); // _delay(1000);
} }
float current_angle = 0.0; // float current_angle = 0.0;
void loop() { void loop() {
foc_step(&motor, &command); foc_step(&motor, &command);
// current_angle = encoder.getAngle(); // current_angle = encoder.getAngle();