Lishui EBikes controller

Hello Dear Community!
Happy and creative New Year to all!

I have few Lishui FOC controllers for EScooters which I recycle and reverse-engineered quite well. They work perfectly in my ebikes projects with opensource firmware project (git:here and pedelecforum.de/wiki)

Cause I also have few 9 inch wheels motors with HAL sensors, I decided to make a simple robot for one of my art projects. Thats why I try to flash SimpleFOC library and to have fun. But “fun” didnt happen :))) Somehow it not working at all :)))))
The CPU is “Bluepill” Stm32F103c8t6 but there is no crystal, so I have changed sys.clock configuration in ArduinoIDE for internal oscilator.
Uart commands work well.
No reaction on motor att all. Unfortunately my skills are not so well to have any idea how to debug. Maybe sys.clock also affect PWM timer and so on.?
I tried few basic Samples Examples in the library no success. Nothing is getting hot, mosfets are fine. At battery start power I hear a very little quet “click” in the test motor
few pics:

cpu config:

Thanks for help

Hi @Fluctuator,

Looks like this should work… you will need BLDCDriver6PWM on these pins.

The system clock does affect the PWM timings, how have you configured it?

Are you working on platformIO or ArduinoIDE?

Hello Runger,
I work in ArduinoIDE in linux
this is my code:

// Open loop motor control example
#include <SimpleFOC.h>


// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(15);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15);

// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6,  8);


//target variable
float target_velocity = 1;

// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }

extern "C" void SystemClock_Config(void) {
  /* Your custom clock config */
 RCC_OscInitTypeDef RCC_OscInitStruct;
  RCC_ClkInitTypeDef RCC_ClkInitStruct;
  RCC_PeriphCLKInitTypeDef PeriphClkInit;

    /**Initializes the CPU, AHB and APB busses clocks 
    */
  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
  RCC_OscInitStruct.HSIState = RCC_HSI_ON;
  RCC_OscInitStruct.HSICalibrationValue = 16;
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
  RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2;
  RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16;
  if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

    /**Initializes the CPU, AHB and APB busses clocks 
    */
  RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
                              |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
  RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
  RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;

  if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

  PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
  PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6;
  if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

    /**Configure the Systick interrupt time 
    */
  HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);

    /**Configure the Systick 
    */
  HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);

  /* SysTick_IRQn interrupt configuration */
  HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);

  
}



void setup() {

    pinMode(PB2, OUTPUT);   // Lishui LED
   pinMode(PB5, OUTPUT);  //lishui PowerON-OFF pin
 
   Serial.setRx(PB_7); //Lishui UART
   Serial.setTx(PB_6);

   SimpleFOCDebug::enable(&Serial);


  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 42;
  // limit the maximal dc voltage the driver can set
  // as a protection measure for the low-resistance motors
  // this value is fixed on startup
  driver.voltage_limit = 21;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

  // limiting motor movements
  // limit the voltage to be set to the motor
  // start very low for high resistance motors
  // currnet = resistance*voltage, so try to be well under 1Amp
  motor.voltage_limit = 1;   // [V]
 
  // open loop control config
  motor.controller = MotionControlType::velocity_openloop;

  // init motor hardware
  motor.init();

  // add target command T
  command.add('T', doTarget, "target velocity");
  command.add('L', doLimit, "voltage limit");

  Serial.begin(9600);
  Serial.println("Motor ready!");
  Serial.println("Set target velocity [rad/s]");
  _delay(1000);
}

void loop() {

  // open loop velocity movement
  // using motor.voltage_limit and motor.velocity_limit
  motor.move(target_velocity);

  // user communication
  command.run();
}

can it be also the num of pole pairs wrong? I tried to guess and put 15, is that the critical parametr for atleast test movement?
I didnt find in the examples pole pairs detection with hall sensors. There is only for encoder it seems.
cant open the motor right now to count magnets, it is in a wooden box

For open-loop it does not matter. it will affect only that the actual speed does not match the speed set in software.
For closed-loop operation it is critical to get it right. Once the motor is moving well in open-loop, there is an example sketch you can use to check the pole pairs.

I wonder if 1V is enough to move it? Maybe you can increase it slightly to check this? But be careful that you aren’t putting too many amps, or something could burn/overheat!

increased motor.voltage_limit = 1; to 6, no change.
than increased to 30 no change.
Motor is not moving :(((
What is the right way to send target uart command “T20” or “T 20” with space? No examples can find anywhere, and what number T 20 or T 200? Cant understand. Cant find docs
Thanks for any help

It’s T20 (no space), and then press return.

Looking at your code, you didn’t enable your driver. Try enabling your driver and then check.

Thanks

Hi again, not working at all …
Can problem be in clock and frequency area? So it means SimpleFOC library doesn work on custom made STM32f103 board with no crystal?
again, from EBIKE opensource firmware FOC runs super well on this controller. Starnge
here is my updated code:

// Open loop motor control example
#include <SimpleFOC.h>

BLDCMotor motor = BLDCMotor(15);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15);



extern "C" void SystemClock_Config(void) {
  /* Your custom clock config */
 RCC_OscInitTypeDef RCC_OscInitStruct;
  RCC_ClkInitTypeDef RCC_ClkInitStruct;
  RCC_PeriphCLKInitTypeDef PeriphClkInit;

    /**Initializes the CPU, AHB and APB busses clocks 
    */
  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
  RCC_OscInitStruct.HSIState = RCC_HSI_ON;
  RCC_OscInitStruct.HSICalibrationValue = 16;
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
  RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2;
  RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16;
  if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

    /**Initializes the CPU, AHB and APB busses clocks 
    */
  RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
                              |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
  RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
  RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;

  if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

  PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
  PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6;
  if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

    /**Configure the Systick interrupt time 
    */
  HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);

    /**Configure the Systick 
    */
  HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);

  /* SysTick_IRQn interrupt configuration */
  HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);

  
}



void setup() {

  driver.voltage_power_supply = 42;
  driver.init();
  driver.enable();
  motor.linkDriver(&driver);

  motor.voltage_limit = 3;   // [V]
  motor.velocity_limit = 5;
 
  motor.controller = MotionControlType::velocity_openloop;
  motor.init();

 
  _delay(1000);
}

void loop() {

  motor.move();

}

tried aslo with motor.voltage_limit = 30;

Do you have a link to a logical schema? Sometimes the drivers have an additional pin that enables them.

What is your input voltage, sometimes druvers don’t enable till 8+V

The generic variants for the STM32duino cores (th eones used by SimpleFOC) initialize the STM32F103 with the HSI clock (i.e. internal clock) even if a crystal is present.

You can clearly see it in these two lines

  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
  RCC_OscInitStruct.HSIState = RCC_HSI_ON;

As such, it makes no difference if the board has a crystal or not, the code is the same, and the crystal is never used.