Strange behavior, MP6540H and MA730

Hello, I am using the MA730 encoder (I checked that it reads ok with the MPS SPI demo, also read the angle with the simpleFOC library and it seems to read the correct angle, no noises or oscillations)
I also use the MP6540H driver from MPS, it is very simple and looks like the L6234. 6 inputs (PWM and ENA) and that’s basically it.
I use the angle_control example. The motor moves smoothly at the beginning of the program, indicating a good encoder and setup.
this is log from the start of it:

MOT: Monitor enabled!
MOT: Init
MOT: Enable driver.
MOT: Align sensor.
MOT: sensor_direction==CW
MOT: PP check: fail - estimated pp:10.5160
MOT: Zero elec. angle: 3.10
MOT: No current sense.
MOT: Ready.
Motor ready.
Set the target angle using serial terminal:
Target: 90.000

the thing is, this motor has 2 poles. but the PP check always fails and gives 10.5-11 pole pairs reading. If I set it to 11 in the code, the motor PP check reports as “good” but the motor can’t maintain position and I can revolve it with my hand if I exert some force.
With the “1” setting, the motor shaft seems to maintain the position with no noises or vibrations.

However, when I try to move it to a certain angle, it only moves if the previous one’s offset is larger enough. For example, I move it to “6” and then to “0” - it moves 90 degrees and stops. but lower values than 6 will not work - the motor will not move. setting any value other than “6” moves the motor to the same position as “6” did. Very strange. it doesn’t matter what value I put in, “0” moves it to place A, other value higher then “6” moves it to position “B”, same place every time.

I measured the phase currents, they are low. The motor and the the driver are not getting hot.
The control loop keeps the shaft’s position all the time.
I tried to play with the PID gains but all I got are oscillations.

What can be the problem?

Can you take a picture of your motor, ideally where some of the magnets and stator windings can be seen. Having 2 poles (single pole pair) is quite unusual on this forum - it would be good to see what we are dealing with!

angle control is the most complex. Have you tried torque/voltage and then velocity/voltage control. The first does not require any pid tuning. I’d like to see if you are able to vary speed before moving on to angle control.

Hi Owen, thanks for your answer.
This is the motor:

https://www.portescap.com/en/products/brushless-dc-motors/22ecp45-ultra-ec-slotless-brushless-dc-motor

With voltage mode (torque mode): anything above M0.6 and the motor start vibrating in very small angles, resulting in audible noise.

Velocity mode:
upon starting of the program, oscillations, setting P lower quieted the oscillations but the motor does not move when given speed commands. the current increases, but no movement.

Hmm - I think this is the first slotless motor I’ve seen on this forum. I wonder if SimpleFOC needs to do anything special for this type of motor?

You mention MP6540H which is the 3PWM version but you say it as 6 inputs. Are you sure you don’t have the MP6540HA which is 6PWM.

What do you intend to use this motor for? Presumably super fast speeds? I think ~9000rpm is the highest I’ve heard someone spin a motor with SimpleFOC. Are you hoping to do nearer the 47,000 rpm limit of this motor? That is a lot of Maths for your MCU! Some versions of this motor have hall sensors. I take it yours does not - hence the MA730 magnetic sensor.

It is MP6540H with 3 pwm inputs and 3 enables, so I set it as 3 PWM.
I don’t need it for super fast speeds, 10000RPM max.
The STM32L476 should handle that, it is 80MHz.
Regarding torque mode, Whatever I set the torque to be, I get the proportional amepre reading in the motor phase, so for example if I set the torque to be 0.4, I see 0.37 Ampere, the motor exerts noticeable force. 0.8 gives me 0.7 ampere, etc. so I guess it works. Velocity and position doesn’t work.

I guess you’ll need to manually set the enables pins as i think simpleFOC doesn’t support per-phase enable pins (yet).

Sounds like you are doing inline current sensing. Is that correct? Have you tried it without? E.g torque/voltage mode.

But at the start of the program the shaft turns smoothly to calibrate the sensor. If there was a problem with the enables the shaft wouldn’t move right?
And I get this log when starting:
MOT: Monitor enabled!
MOT: Init
MOT: Enable driver.
MOT: Align sensor.
MOT: sensor_direction==CW
MOT: PP check: fail - estimated pp:10.5160
MOT: Zero elec. angle: 3.10
MOT: No current sense.
MOT: Ready.
Motor ready.

So I don’t think there is problem with the enables.
Also, the shaft keeps the position. If I move the shaft with my hand It goes back to the initial position.
The current I measure is with an ampere meter, measuring the current thru a clamp.

Good point.
During calibration, it is being instructed to move one electrical rotation clockwise then anticlockwise and then asking the sensor how far it has moved.
It then divides 3
2pi radians/sensor moved to give estimated pole pair of 10.5.
I would expect that you should visually see your motor moving ~34degrees clockwise/anticlockwise.

Perhaps you can post your code.

Hi,
Actually at the beginning it spins almost a full rotation and then goes back. I think 340 degrees…
Here is a youtube video with the start-up movement:

https://youtu.be/jz972_u0NuM

Here is the code:

#include <SimpleFOC.h>
MagneticSensorSPI sensor = MagneticSensorSPI(MA730_SPI, D3);
BLDCMotor motor = BLDCMotor(1,1.5);
BLDCDriver3PWM driver = BLDCDriver3PWM(D6, D9, D10, D2, D4, D5);

float target_angle = 0;
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }

void setup() {

sensor.init();
motor.linkSensor(&sensor);

driver.voltage_power_supply = 19;
driver.init();
motor.linkDriver(&driver);

motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

motor.controller = MotionControlType::angle;
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20;
motor.PID_velocity.D = 0;

motor.voltage_limit = 19;

motor.LPF_velocity.Tf = 0.01;

motor.P_angle.P = 20;

motor.velocity_limit = 20;
Serial.begin(115200);

motor.useMonitoring(Serial);

motor.init();
motor.initFOC();

command.add(‘M’,onMotor,“my motor”);
Serial.println(F(“Motor ready.”));
Serial.println(F(“Set the target angle using serial terminal:”));
_delay(1000);
}

void loop() {

motor.loopFOC();

motor.move();

command.run();
}

I think there are two issues.
#1 calibration
I think your single pole is confusing sensorAlign function. Moving 340 degrees is similar to moving -20 degrees (you end up pointing at same place)
To fix this we should be calling sensor.getAngle() many times during calibration - or at least for low pole motors.

Can you add the following

If (i%50==0) {
sensor->getAngle();
}

to this line:


By calling that in the calibration loop the sensor getAngle function will get called 10 times and it’ll know that it has moved 340 degrees not -20 degrees.

#2 other problem
Haven’t worked this out yet but i strongly recommend starting with a simpler control mode to start

motor.controller = MotionControlType::torque;
// Or
motor.controller = MotionControlType::angle_openloop;

Be careful to send small values to move() in torque mode as you don’t want to overheat things.
Once these simple modes work, move to

motor.controller = MotionControlType::velocity;

Tuning velocity pid and Tf. Once that is done it should be straight forward to go back to angle.

putting this line in the file you mentioned did the trick!!! thank you, you saved me!!!
Now the motor moves to the desired position, it vibrates a little bit but I guess now it is a matter of PID tuning!
Thanks again! :grinning: :grinning: :grinning:

1 Like

how is the MA730 working out now? I did try to get them to work but at higher speeds it was unreliable.