remove simple_foc commander and monitor

This commit is contained in:
Ilya Uraev 2025-05-30 17:14:30 +03:00
parent f1d922bd34
commit d1e918371c
4 changed files with 11 additions and 22 deletions

View file

@ -26,6 +26,6 @@ extern MotorControlInputs motor_control_inputs;
void doMotor(char *cmd); void doMotor(char *cmd);
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor, void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
DRV8313Driver *driver, LowsideCurrentSense *current_sense, DRV8313Driver *driver, LowsideCurrentSense *current_sense,
Commander *commander, CommandCallback callback,FLASH_RECORD* pid_data); FLASH_RECORD* pid_data);
void foc_step(BLDCMotor *motor, Commander *commander); void foc_step(BLDCMotor *motor);

View file

@ -1,17 +1,9 @@
#include "config.h" #include "config.h"
void doMotor(char *cmd) {
command.motor(&motor, cmd);
digitalWrite(PC10, !digitalRead(PC10));
delayMicroseconds(2);
}
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor, void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
DRV8313Driver *driver, LowsideCurrentSense *current_sense, DRV8313Driver *driver, LowsideCurrentSense *current_sense,
Commander *commander, CommandCallback callback,FLASH_RECORD* pid_data) { FLASH_RECORD* pid_data) {
encoder->init(&spi); encoder->init(&spi);
/* convert data from flash int value to float*/ /* convert data from flash int value to float*/
@ -38,8 +30,6 @@ void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
motor->linkSensor(encoder); motor->linkSensor(encoder);
motor->linkDriver(driver); motor->linkDriver(driver);
motor->linkCurrentSense(current_sense); motor->linkCurrentSense(current_sense);
motor->useMonitoring(Serial);
motor->monitor_downsample = 5000; // Default monitoring interval
motor->controller = MotionControlType::angle; motor->controller = MotionControlType::angle;
motor->torque_controller = TorqueControlType::voltage; motor->torque_controller = TorqueControlType::voltage;
motor->foc_modulation = FOCModulationType::SpaceVectorPWM; motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
@ -66,7 +56,7 @@ void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
} }
void foc_step(BLDCMotor *motor, Commander *commander) { void foc_step(BLDCMotor *motor) {
if (motor_control_inputs.target_velocity != 0 || if (motor_control_inputs.target_velocity != 0 ||
motor->controller == MotionControlType::velocity) { motor->controller == MotionControlType::velocity) {
if (motor->controller != MotionControlType::velocity) { if (motor->controller != MotionControlType::velocity) {
@ -82,6 +72,4 @@ void foc_step(BLDCMotor *motor, Commander *commander) {
motor->loopFOC(); motor->loopFOC();
motor->move(); motor->move();
motor->monitor();
commander->run();
} }

View file

@ -46,7 +46,7 @@ DRV8313Driver driver(TIM1_CH1, TIM1_CH2, TIM1_CH3, EN_W_GATE_DRIVER,
LowsideCurrentSense current_sense(0.01, 10.0, CURRENT_SENSOR_1, LowsideCurrentSense current_sense(0.01, 10.0, CURRENT_SENSOR_1,
CURRENT_SENSOR_2, CURRENT_SENSOR_3); CURRENT_SENSOR_2, CURRENT_SENSOR_3);
Commander command(Serial); // Commander command(Serial);
MotorControlInputs motor_control_inputs; MotorControlInputs motor_control_inputs;
@ -83,7 +83,7 @@ volatile uint32_t ipsr_value = 0;
// flash_rec = load_params(); // flash_rec = load_params();
// Initialize FOC system // Initialize FOC system
setup_foc(&encoder, &motor, &driver, &current_sense, &command, doMotor,flash_rec); setup_foc(&encoder, &motor, &driver, &current_sense,flash_rec);
CAN2->IER |= CAN_IER_FMPIE0 | // Сообщение в FIFO0 CAN2->IER |= CAN_IER_FMPIE0 | // Сообщение в FIFO0
CAN_IER_FFIE0 | // FIFO0 full CAN_IER_FFIE0 | // FIFO0 full
@ -104,7 +104,7 @@ volatile uint32_t ipsr_value = 0;
void loop() { void loop() {
__enable_irq(); __enable_irq();
foc_step(&motor, &command); foc_step(&motor);
CAN_message_t msg; CAN_message_t msg;
// GPIOC->ODR ^= GPIO_ODR_OD11; // Toggle status LED // GPIOC->ODR ^= GPIO_ODR_OD11; // Toggle status LED
// delay(500); // delay(500);

View file

@ -124,8 +124,9 @@ void firmware_update(){
void setup_angle(float target_angle) { void setup_angle(float target_angle) {
motor.enable(); // Enable motor if disabled motor.enable(); // Enable motor if disabled
motor.controller = MotionControlType::angle; // motor.controller = MotionControlType::angle;
motor.move(target_angle); motor_control_inputs.target_angle = target_angle;
// motor.move(target_angle);
} }
// void setup_pid_angle(uint8_t param_pid, uint32_t data){ // void setup_pid_angle(uint8_t param_pid, uint32_t data){
@ -241,4 +242,4 @@ void listen_can(const CAN_message_t &msg) {
} }
} }
} }
} }