VOLZ Protocol Issue

Hello,

We have encountered an issue with the implementation of the VOLZ protocol for driving a VOLZ Servo motor. The problem we have is with the scaling of the ranges between the PWM Input and the VOLZ protocol ranges. We think that 2 lines of code needs to be switched over in order for the scaling to work properly, and we have provided you an example calculation bellow with the current CODE as downloaded from GitHub Arduplane 4.0.6, and another example with the 2 lines switched over:

EXAMPLE WITH CURRENT CODE

Here we can take “output_min” as the lower limit of the servo channel in PWM and in this example we set it as 1000

Here we can take “output_max” as the upper limit of the servo channel in PWM and in this example we set it as 2000

Here we can take “output_pwm” as the value of in PWM we want the servo to move, in this case we take it 1500, so that the servo move to the middle (50%).

From the VOLZ Protocol the VOLZ_EXTENDED_POSITION_MIN as 128, and the VOLZ_EXTENDED_POSITION_MAX as 3968, which gives the parameter “VOLZ_SCALE_VALUE” as 3840

Following the code as it is, we can calculate the following:

output_pwm – oputput_min => 1500 – 1000 = 500 => value

value = value + VOLZ_EXTENDED_POSITION_MIN => 500 + 128 => 628 à value

value = value * VOLZ_SCALE_VALUE / (output_max – output_min) => 628 * 3840/1000 = 2411.52

Here we can see that the middle of the servo from the VOLZ Protocol is equal to (3840/2) + 128 = 2048, which is substantially different from the number we get using the current implementation of the VOLZ protocol.

The modification we suggest is to switch the “value = value + VOLZ_EXTENDED_POSITION_MIN” with the “value = value * VOLZ_SCALE_VALUE / (output_max – output_min)”, which looks like the following picture:

Following now the new code we can calculate the following

output_pwm – oputput_min => 1500 – 1000 = 500 => value

value = value * VOLZ_SCALE_VALUE / (output_max – output_min) => 500 * 3840/1000 = 1920

value = value + VOLZ_EXTENDED_POSITION_MIN => 1920 + 128 = 2048

This time we can see that both the value calculated by the modified code and the middle of the servo from the VOLZ Protocol match and both are 2048.

With the code modified you can see that regardless of how you change the PWM Ranges, the VOLZ scale will remain proportional to the PWM scale, which we think should be the case.

We also would like to propose further changes to the implementation of the VOLZ Protocol, so that the ranges can be clipped at both minimum and maximum. For example if for some reason you want to move the servo from 20% to 100% rather than 0% to a 100%, it would not be possible at this point as the only values you can change in the Mission Planner are the values for “output_min” and “output_max” in PWM, which will rescale using the VOLZ min and max value and still move from 0% to a 100% the actual servo. We propose that either new parameters are set which decouples “output_min” and “output_max” from the values used to calculate the VOLZ position, for example:

NEW PARAMETER “output_min_VOLZ” set to 1000

NEW PARAMETER “output_max_VOLZ” set to 2000

Old parameter “output_min” set to 1200

Old parameter “output_max” set to 2000

Old parameter “output_pwm” set to 1200 (we want the minimum to be servo at 20%)

Following the modified Code where we change the parameters as follow:

Value = c-> get_output_pwm() - c-> get_output_min_VOLZ()

Value = 1200 – 1000 = 200

value = value * VOLZ_SCALE_VALUE / (output_max_VOLZ – output_min_VOLZ) à 200 * 3840/(2000-1000) = 768

value = value + VOLZ_EXTENDED_POSITION_MIN à 768 + 128 = 896

Here we can see that from the VOLZ limits 20% of the VOLZ servo movement equal to (3840*0.2) +128 = 896. This decoupling of the PWM limits for min and max on 2 separate parameters (output_min_VOLZ, output_max_VOLZ, output_min, output_max) allows to set a given range for the VOLZ Servo movement, and different range for the movement you want to happen, allowing to clip both maximum and minimum movement and also shift the center position of the servo.

@tridge

BEST REGARDS TO ALL CONTRIBUTORS

This is quite hard to follow here, can you open a PR on github for the change.

https://ardupilot.org/dev/docs/submitting-patches-back-to-master.html

yes please
I’d also be tempted to just not use the SERVOn_{MIN,MAX} values and always assume they are 1000 to 2000 in the maths for calculating the value we send. That way adjusting SERVOn_{MIN,MAX} will change the throw of the servo.

Hello,
Thank you for the fast and guided response !
I will do my best with the git hub, and will post here when PR is ready.

Hello,
I’ve created a pull request and you can find below the link:

[https://github.com/ArduPilot/ardupilot/pull/15451](http://AP_Volz_Protocol scaling bugfix #15451)