Closed laurensvalk closed 9 years ago
You could also check this by performing the same experiment with the standard LEGO firmware.
Hi David. Thanks for your immediate response.
I updated the previous post with a kernel version and will report it from now on.
Thanks for the pointer to that source file. I'll have a look.
In response to your points:
3.. ) I agree: The same implementation for all values between -100 and 100, including 0, would be what I expect. (Except for the actual duty value and polarity of course.)
4..) This comes from the motor driver datasheet linked to from the ev3dev web page, so it appears the choice is between brake and standby during the off part of the duty cycle. I'll have a look at the current implementation in the source code now.
5..) I agree that coasting during the off period would be the best behaviour. (There may still be a [perhaps uncommon] reason for the existing implementation though: For example, you get to brake from 100% duty to 50% at no energy cost. However, the same can be accomplished by full braking until you achieve the desired speed, so perhaps it doesn't need to be an explicit option.)
Well, sure enough, we are braking instead of coasting while running: code. I'll have to have a look at the pin assignments to see what is the "right" way to fix this.
Can you explain/confirm what the lines you point to currently do?
case DC_MOTOR_INTERNAL_COMMAND_RUN_FORWARD: //line 255
gpio_direction_output(data->gpio[GPIO_PIN1].gpio, 1);
gpio_direction_input(data->gpio[GPIO_PIN2].gpio); // Does this set the pin to input (high Z) or does this somehow make it a toggling PWM output?
Based on your response, I read that GPIO_PIN1 is set to output and set High, while GPIO_PIN2 becomes the toggling PWM pin, thus making the output toggle between HL (forward) and HH (brake) by the truth table.
I'm a bit confused by the 'direction_input ' notation, which makes it seem like GPIO_PIN2 is set to input/High Z.
Edit: Fixed markup in this comment.
gpio_direction_input(data->gpio[GPIO_PIN2].gpio);
does indeed set the GPIO to high Z, which in turn allows the PWM to control the input of the motor driver chip instead of the GPIO. The PWM is connected to both GPIOs via a 4.7k resistor.
Thanks for the info. Then I should be able to compile the changes for now and report the result, probably tomorrow.
I'll let you decide what is the "right" way to fix it, but I'm happy to provide input if you need an opinion.
I think you may be in for a "surprise".
First, our current driver is the same as the LEGO firmware (code), so it would be interesting to repeat the tests you described using the LEGO firmware to see what happens.
The changes you need to make are https://github.com/dlech/lego-linux-drivers/commit/670ebf51aa043c3b4738c31fb9e0b4919760e05c and https://github.com/dlech/ev3dev-kernel/commit/a3054e2858406abf2e752d8a71999063b41600bb.
This gets the coasting working as expected during the off portion of the duty cycle. However, the surprise is that the motor would not run at 50% duty cycle or less, whereas normally, this was around 20% before making the change.
So, the question is, is this actually the "right" way to do it? I think we should do an experiment comparing the current consumption of the two different configurations using speed regulation to run the motor at a constant speed.
Is the frequency of the PWM module configurable? The effect of setting the bridges to brake is different depending on the current through the inductor. I recall reading something about this topic for a related project last year. I'll try to retrace that.
In any case, I believe the present behavior is also not what's expected. I don't think setting the motor to 1-5% duty cycle should brake the motor.
Right, the search keywords are slow and fast decay mode. Here is an application note explaining what they are (but not what to use them for).
Here is a discussion about the topic, concerning braking.
The following is an interesting quote from that thread:
There is also a missconception that slow decay means brake which raises an eyebrow: "How can my motor move faster when I am braking it all the time?" Slow decay is not brake. Slow decay uses the same FET topology than brake, but they are two different scenarios. On slow decay, both same side FETs are ON and the current decays slowly. The key work here is "current decays". Once current reaches zero, then Brake occurs and this is when you see the BACK EMF taking over and pushing a current opposing to the initial current.
Why is this important? Well, because for slow decay mode to work properly, your PWM frequency has to be fast enough to make the current regulation continuous. If you let the current reach zero, then you will be hitting brake, in which case speed regulation is impossible. I am just mentioning this as an observation as I am positive your PWM frequency is high enough for this not to happen, but it is a good thing to keep an eye open for.
And hence the question about the PWM frequency. I have some reading to do :)
Is the frequency of the PWM module configurable?
Technically, we can set the PWM to any frequency, but right now, it is hard coded at 10kHz here. See https://github.com/ev3dev/ev3dev/issues/121#issuecomment-102648747 for an example of how to take control of the hardware directly without having to recompile the kernel. In that example, he is setting the period to 20ms and the duty cycle to 1 ms because he is controlling hobby type servo motors. There should also be an attribute to invert the duty cycle of the pwm.
I was reading the motor driver chip datasheet and came across this:
The modes during which large current flows are as follows : • Motor surge current when the DC motor starts up or when it shifts rotation directions (forward ↔ reverse). • Passthrough current generated within the IC when shifting rotation directions (forward ↔ reverse) or when shifting from forward/reverse rotation to braking, or vice versa.
So, it sounds like by switching to brake mode during the off cycle causes a high current condition, which is not necessary and even undesirable.
Yes, but that's exactly how the regulated brake mode works - you give up on efficiency wrt current but you get much better regulation of speed for step changes with and without a load on the motor. We can consider another regulation mode that lets the motor float on the off cycle, but be aware that if you have a high inertia load it will take longer to hit the regulation point.
Here's a longer explanation by the guy that @laurensvalk quoted: http://ebldc.com/?p=86
So, obviously, we are presently using a slow decay in our driver implementation. It seems to me though that to be consistent, we should be braking rather than floating/coasting at 0% duty cycle.
I assume that the other motor controllers, such as the BrickPi and NxtMMX use slow decay as well. Therefore, I don't think we should change the current implementation (other than braking at 0% duty cycle).
But, as @rhempel suggested, the question is open: Should we add a fast decay mode that is selectable via the tacho-motor and dc-motor drivers? What are the applications that would benefit from this? Also, what are the consequences?
It doesn't look like the motor controller has any smarts for synchronous fast decay (where the opposite transistors in the H-bridge are turned on until the current is 0). So that means we get asynchronous fast decay where the free-wheeling diodes get to take all of the load, which will certainly make the motor driver chips run hotter. Also, I understand that in this mode there will be more current ripple, and hence more torque ripple, it sounds like this really might not be as desirable as it sounded at first.
Yes, but that's exactly how the regulated brake mode works - you give up on efficiency wrt current but you get much better regulation of speed for step changes with and without a load on the motor. We can consider another regulation mode that lets the motor float on the off cycle, but be aware that if you have a high inertia load it will take longer to hit the regulation point.
What is the advantage of this mode for motors with encoders? With encoder feedback, the regulation point can also be reached quickly by reversing the applied voltage.
What I'm basically looking for is some PWM configuration that approximates a voltage source between -vMax and +vMax. This would mean behavior much like attaching it to a voltage source and just turning the dial, which will not brake the motor unless you reverse the voltage.
I'll have to see if this configuration is possible with the existing motor driver ICs.
I thought the NXT had both options (In RobotC, setting bFloatDuringInactiveMotorPWM to true or false), but I'd have to check with an experiment to be sure.
What you are describing is speed regulation in float mode - I thought that was a combination we could generate based on the stop
attribute.
What you are describing is speed regulation in float mode - I thought that was a combination we could generate based on the stop attribute.
Yes, that's what I'd like to do, except I'd regulate the speed myself by varying the duty cycle based on the encoders. But as the test in the first post shows, this does not currently seem to be implemented this way, because the motor brakes even if the stop setting is set to coast.
I thought this was a nice illustration of the decay modes (from a different driver): Source
If I understand correctly, slow decay mode does not imply braking, as long as the current does not go to zero (in the graph, indeed it doesn't). So in that case, we should indeed use slow decay in order to reduce current and torque ripple. Instead, maybe we can try to find out why this still causes the motor to brake in our case.
Besides, it seems that the change discussed at first (toggling between on and standby) is neither fast decay nor slow decay, right? In fast decay, both pins would be toggling in order to toggle between forward and reverse.
The motor can start braking when the current drops below zero, which can happen if the PWM frequency is too low. 10 kHz seems fine for this application, but it would be interesting to test if this frequency is actually seen on the output.
Unfortunately, I don't have a shunt resistor that I can use to measure current with my oscilloscope. I guess I better get one. :grin:
Well, I went back to the drawing board (discarding assumptions and properly writing down the dynamic equations of a DC motor. Would anyone like to see these?), and it turns out my assumptions about the initial experiment were not correct.
I start a motor at maximum voltage (duty = 100), wait 2 seconds, and then set the duty cycle to 0. As expected, since the motor is in coast mode, the motor gently comes to standstill.
This expectation was wrong. (Instead, the result came from the hard coded coast for 0 duty cycle, which @dlech has proposed to remove, and I agree.)
Now I do the same test, but now I set the duty cycle to 3 instead of 0. However, the motor comes to standstill immediately: it brakes. Upon standstill and moving the motor manually, you can feel that brake mode is on.
This is actually the expected behavior, corresponding more closely to the ideal voltage source. When you set a voltage source to 0V, this corresponds to a short circuit, resulting in brake. (As opposed to an open connection, resulting in free float.)
To summarize, if the purpose is to closely simulate a DC motor with a regulated voltage source, the original implementation with slow decay ('brake') is correct, as long as the exception for 0% is removed. That is, 'brake' at 0% duty is expected. This was the only bug.
Now, one source of confusion (for me anyway) when I was searching for the solution was the terminology 'brake' for slow decay. When you decrease duty from 80% to 30%, the motor does indeed brake, but this is NOT due to the decay mode. In fact, the motor also brakes when using an ideal voltage source and going from 8V to 3V. The motor brakes because the back EMF temporarily exceeds the input voltage.
Would anyone like to see these?
I have them in one of my old text books somewhere. I will probably understand them better now. :+1:
I'm glad to see that we have come to the same conclusion. So, I will apply this patch, which should get the desired behaviour. And we will hold off on implementing a "fast decay" mode.
Fix has been released in kernel v3.16.7-ckt11-5-ev3dev-ev3.
Update/Note: Some of the experiments and result descriptions were later found to be inaccurate, as discussed in the final posts. I'll leave the original discussion here for reference, but be careful not to interpret the intermediate discussion as fact when you study the bahavior of the motors.
When a tacho motor (I use the NXT tacho motor) is in run-direct mode, I understand that setting duty_cycle_sp sets the duty cycle for the motor. However, I'm seeing some unexpected behavior here.
I do the following tests just after plugging a motor, so with the default settings: speed regulation is off. Tests done with
3.16.7-ckt10-4-ev3dev-ev3 #1 PREEMPT Wed May 13 15:21:31 CEST 2015
(My custom compilation of the May 1 2015 release code of both kernel and lego drivers)Suppose I do the following test. I start a motor at maximum voltage (duty = 100), wait 2 seconds, and then set the duty cycle to 0.
As expected, since the motor is in coast mode, the motor gently comes to standstill.
Now I do the same test, but now I set the duty cycle to 3 instead of 0.
Since I apply slightly more voltage (3/100*max_voltage) to the motor than 0, I expect to see not much difference. If anything, the motor should slow down even more gently since I'm still pushing it forward by a tiny amount.
However, the motor comes to standstill immediately: it brakes. Upon standstill and moving the motor manually, you can feel that brake mode is on.
The duty cycle 3 is just an example here, but it makes the effect easy to see. Another way to see it, is to go from 100% to 30% duty. Since a fair amount of voltage is still applied, the motor should slow down fairly slowly (friction being the only cause), but you can see it slow down instantly, indicating brake behavior.
Maybe the motor is braking during the low part of the duty cycle. I believe the motor bridges can be configured in several ways, resulting in either brake or coast during the low cycle.
Coasting during the off cycle would be much more efficient, and better for speed regulation and other controllers. It then becomes much like controlling a variable voltage source, or rotating the dial on a physical voltage source.
It seems the coast behavior itself is already implemented, but only for the case that duty is set to 0.
Or.... I'm seeing a bug and speed regulation is actually still active, making the motor brake until the desired speed is reached. However, to be sure I set Kp, Ki, Kd to 0, and the same phenomenon still occurs.
I hope someone will have the answers. If this behavior is by design, perhaps I can make this a feature request, with an option to choose brake or coast when the duty is in the low part of the cycle :)