PID for Danfoss proportional valve

So, after a lot of headache (our fault), we got AgOpenGPS working on my friend’s JD 7530 Premium. He found AgOpenGPS in a Google search, and contacted me since I have some experience in electronic engineering. The 7530 is Autosteer ready, and we reused the Danfoss proportional valve already on the tractor. An IBT_2 is controlling the valve, using the fix provided by the coffeetrac repo, as described here.

The problem we have is that pure Proportional is not working accurately. If we turn the Proportional up quite a bit, the steering overshoots in a consistent manner. If we turn the Proportional down, the steering won’t ever reach the line (setpoint). We tried the latest beta 4.2.01, and see that the Integral has been removed from AgOpenGPS. We went back to the latest stable release, and implemented the Integral in the Nano’s code, looking off of a PID library. There was an immediate improvement in the steering.

Now we would like to implement the Derivative yet, probably by reassigning the output gain to the Derivative of the PID control. Hopefully in the next few days we will report back on the success of this test.

What I’m wondering is, why was the PID control never fully implemented? Are we the only ones affected by this problem of using a proportional valve? Lack of time / knowledge / need for PID control? Would PID control be of interest to the AgOpenGPS community?

1 Like

I have this problem also…and am also currently working on implementing full PID control… id be interested to follow your progress…

I’ve been helping Darren with this issue, there’s a couple of reasons that you’re experiencing this issue as I understand it:

  • Directly controlling a proportional valve with open-loop PWM is less than ideal, this is due to the inherent differences in coil resistance due to temperature and other factors. This is normally resolved by using a current sensing feedback loop - in the valve’s manual you’ll probably notice that the flow rate is proportional to coil current rather than voltage.

  • There is no dither on the PWM signal driving the valve - because of this, you will experience significant hysteresis (i.e. the amount of PWM DC% you need to move the valve one way compared to the DC% you need to get it to reverse the other way - there’s a significant amount of “deadband” in the middle). This is because the valve essentially sticks in its “deadband” and requires a good bit of current to get it to move in the other direction. This is usually resolved by superimposing a lower frequency PWM signal over the top of the main PWM frequency to cause the valve to continuously move and stop the stiction, this can also be done by using a constantly low PWM frequency to ensure that the way the coil is inducing current is continuously changing, however it is less accurate.

This is what happens when you have very high PWM frequencies:

This is what happens if you just use one low frequency PWM signal:

(I can only add one image per new post, so you’ll need to click that one :slight_smile: )

Note that the waveform shown rising here is the current induced in the coil due to the PWM signal.

  • The improvement you see from utilising the Integral part of PID is because it is able to see the error over time and compensate for the hysteresis and inaccuracy of valve being driven poorly. This simply masks the real issue underneath.

There are essentially no problems with this when actuating a motor that turns the wheel itself, there’s no deadband, there’s no control issues etc, you can just drive the wheel one way vs the other and direct proportional control will work really well.

Darren and I are working on adding a few parts to resolve this, both from a code and hardware perspective - notably the current sensing feedback loop which would then be able to control the valve with constant-current and also adding PID control. If this still proves to have problems with the deadband, we’ll look into using superimposed dither to resolve that, however I suspect this will nearly be easy enough to mask with low frequency PWM and PID.

We’ll keep a post updated with this - hope this helps explain the problem!

Ruan

1 Like

Some help for us who did not understand :slight_smile:

1 Like

That is a great explanation even for me, who has dabbled with PID for 5+ years now.

What type of a Danfoss valve is the 7530 using? If it has the PVE head (the black box type), that should have a built-in closed loop control like this, so you shouldn’t have any issues with the stuff @ruan is mentioning, if I’m not totally off?

image

I’m currently putting in a PVG16 valve with the PVHC head (two individual coils), does the JD use this then:

image

Here the coils aren’t directly driving the main spool, but operate two pilot hydraulic valves that move the main spool. The hysteresis limits look quite large on the diagram…

image

The Danfoss valve on the 7530 has 4 wires. Error, Ground, U DC, and U S.

It’s a PVE valve, but we never were definite if it’s a A, H, or S model. John Deere applied their own number to the valve, which obfuscates things.

PVEH - PVES
PVES

As far as I can tell, both these valves should perform somewhat the same, using a different operation. I see that in the spec sheet the PVES is listed as a 0% hysteresis.

Later today, we will be working on this again. Hopefully we will have some more info to report. Maybe even success?!

Thanks @ruan and @nut for chiming in here, as I wasn’t thinking along the lines of hysteresis. I’ll keep an eye open today and maybe test the hysteresis and PWM speed.

Update: My friend just told me he gave Danfoss the number on the valve, and they responded and said the valve is a PVES model, which has 0% hysteresis. Sorry for any confusion.

Ok, so we got the proportional valve working like a top. The important parts are:

  1. find the hysteresis on the PWM for valve engagement (no, it doesn’t have 0% hysteresis)
    using analogWrite():
    *128 did not move
    *118, 138 put pressure on the wheels without moving left or right
    *108, 148 moved slowly left and right
    in real life we used minimum PWM of 30 (98, 158)

  2. use less Proportional (after all, a hydraulic valve is way faster than a steering motor)

  3. add Integral

  4. add Derivative

which leads us to changing lines around 530 in Autosteer_USB.ino to:

//Settings Header has been found, 8 bytes are the settings
if (Serial.available() > 7 && isSettingFound)
{
isSettingFound = false; //reset the flag
//change the factors as required for your own PID values
steerSettings.Kp = (float)Serial.read() * 0.2; // read Kp from AgOpenGPS
steerSettings.Ki = (float)Serial.read() * 0.1; // read Ki from AgOpenGPS
steerSettings.Kd = (float)Serial.read() * 0.1; // read Kd from AgOpenGPS
steerSettings.Ko = (float)Serial.read() * 0.1; // read Ko from AgOpenGPS
steerSettings.steeringPositionZero = 1533 + Serial.read(); //read steering zero offset
steerSettings.minPWMValue = Serial.read(); //read the minimum amount of PWM for instant on
steerSettings.maxIntegralValue = Serial.read() * 2; //
steerSettings.steerSensorCounts = Serial.read(); //sent as 10 times the setting displayed in AOG
EEPROM.put(10, steerSettings);
}

and replacing function calcSteeringPID in AutosteerPID.ino with:

void calcSteeringPID(void)
{

//Proportional
pidOutput = steerSettings.Kp * steerAngleError ;
//Integral
outputSum += (steerSettings.Ki * steerAngleError);
if (outputSum < -steerSettings.maxIntegralValue){
outputSum = -steerSettings.maxIntegralValue;
}
else if (outputSum > steerSettings.maxIntegralValue){
outputSum = steerSettings.maxIntegralValue;
}
//Derivative
dInput = steerAngleError - lastSteerAngleError;
pidOutput += outputSum - (steerSettings.Kd * dInput);

pwmDrive = (constrain(pidOutput, -250, 250));

//add min throttle factor so no delay from motor resistance.
if (pwmDrive < 0 ) pwmDrive -= steerSettings.minPWMValue;
else if (pwmDrive > 0 ) pwmDrive += steerSettings.minPWMValue;

if (pwmDrive > 255) pwmDrive = 255;
if (pwmDrive < -255) pwmDrive = -255;

if (aogSettings.MotorDriveDirection) pwmDrive *= -1;

lastSteerAngleError = steerAngleError;

}

Now do note that this only works with the 4.1.12 release, as Integral, Integral max, and Output gain have been removed since. It would be nice of @BrianTee_Admin to put Integral, Integral max and Derivative back in again. Hint, hint :smiley: The Output gain isn’t really useful, as that only multiplies the final result, which is better adjusted individually in Proportional, Integral, and Derivative.

The whole .ino sketch I used can be found here.

Things to do:

  1. Use a better way of resetting the Integral and Derivative when shutting down autosteer and turning it back on. Namely, when turning it back on, the kickback of Derivative or lack of Integral makes autosteer turn sharply (even when close to the AB line) until the values are built up again. Maybe the solution would be to keep on calculating when autosteer is turned off, but not set the valve. At this time, all Integral and Derivative is cleared when the autosteer is turned off.
1 Like

Did you see this post from grabik and also the next posts from him?

PID.ino

PID calculation:

*//Proportional
pValue = steerSettings.Kp * steerAngleError *steerSettings.Ko;

/* //Derivative
dError = steerAngleError - lastLastError;
dValue = Kd * (dError) * Ko;

//save history of errors
lastLastError = lastError;
lastError = steerAngleError;
*/

drive = pValue;// + dValue;
pwmDrive = (constrain(drive, -255, 255));

//add throttle factor so no delay from motor resistance.
if (pwmDrive < 0 ) pwmDrive -= steerSettings.minPWMValue;
else if (pwmDrive > 0 ) pwmDrive += steerSettings.minPWMValue;

if (pwmDrive > 255) pwmDrive = 255;
if (pwmDrive < -255) pwmDrive = -255;
*

8 byte PWM resolution on arduino nano(255) , for driver direction DIR pin, and PWM ,DIR pin LOW left side -255 max write to PWM 255 , right side DIR pin HIGH 255 max write to PWM 255 for max duty cycle.

For Danfoss valve not need DIR pin for change direction.

Sorry for not mentioning… Yes, I also included the

pwmDrive = pwmDrive / 4;
pwmDrive = pwmDrive + 128; // add Center Pos.

as explained in that topic. That got the IBT_2 working with the valve, but does not necessarily get AgOpenGPS working with the valve.

From reading through that topic, it also appears to me that he is not using Integral.

According to the following text from the pid for dummies, it is not important to have derivative.

Derivative Action – predicting the future

OK, so the combination of P and I action seems to cover all the bases and do a pretty good job of controlling our system. That is the reason that PI controllers are the most prevalent. They do the job well enough and keep things simple. Great.

But engineers being engineers are always looking to tweak performance.

They do this in a PID loop by adding the final ingredient: Derivative Action.

So adding derivative action can allow you to have bigger P and I gains and still keep the loop stable, giving you a faster response and better loop performance.

If you think about it, Derivative action improves the controller action because it predicts what is yet to happen by projecting the current rate of change into the future. This means that it is not using the current measured value, but a future measured value.

The units used for derivative action describe how far into the future you want to look. i.e. If derivative action is 20 seconds, the derivative term will project the current rate of change 20 seconds into the future.

The big problem with D control is that if you have noise on your signal (which looks like a bunch of spikes with steep sides) this confuses the hell out of the algorithm. It looks at the slope of the noise-spike and thinks:

“Holy crap! This process is changing quickly, lets pile on the D Action!!!”

And your control output jumps all over the place, messing up your control.

Of course you can try and filter the noise out, but my advice is that, unless PI control is really slow, don’t worry about switching D on.

Maybe a delay on power (so signal can be built up first)
If sharp turn is always to same side, it could be a Danfoss thing when powered on. Could be checked by applying center voltage to signal when turning power on. Edit: center voltage meaning 6v if you have 12v as supply)

Isn’t the Danfoss supposed to have an analog signal in since it has its own PWM generator with LVDT feedback?

That’s my understanding as well. You need DC supply voltage on one pin and then a control voltage on the other. Hysteresis shouldn’t exist as there’s a displacement feedback in the valve controller.

Here’s some discussion & working setups in another thread .ino for PCB+MD13S+Danfoss valve You should see something like 25-75% of U_DC in U_S, check out the pictures towards the back of the thread from @Kaupoi and @Larsvest

We tried putting PWM to the U S pin, and everything worked. A lot of analog input controllers out there accept true analog, and they also accept PWM.
Danfoss PWM connection

I think I have the PID ‘turn on’ figured out. Now to test it yet. :face_with_raised_eyebrow:

The Integral can not be calculating while not steering, since it would build up to the Integral max over time, even if off of the AB line by 1%, for instance.

The ‘last’ value of the Derivative needs to be saved constantly, as this will be used to calculate the Derivative once the steering is on again.

The only value used for PID is the P, the rest have been used for other purposes like low and high max pwm etc.

I understand they “work” with PWM, but have your tried with an analog signal? For example if you sent a 50% duty cycle, half the time the danfoss would think wide open , the other half closed - that would work however with the LVDT feedback I’m not so sure that is the best scenario for its feedback control.

All i’m saying is worth a try.

I’d like to disagree on the theory that the Danfoss thinks it should be wide open half the time and closed half the time with 50% duty cycle. We can get it to steer left by putting 12Vdc to the U DC and U S pins, but putting 12V to the U DC pin and 0 Vdc to the U S pin does nothing. We can get it to steer right by connecting the Nano’s 3V or 5V pin to the U S pin. The 3V steers faster to the right than the 5V. But like I said before, 0V on the signal pin gets ignored.

I recall the signal is 0.25 - 0.75 times U_DC, so with 12 volts 3 volts full the other way and 9 volts the other.

1 Like