mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Volz_Protocol scaling bugfix
->Fixed incorrect scaling betwen PWM values and Volz protocol values ->In the scaling formula are hardcoded PWM values min=1000 and max=2000. The idea behind this is to be able to change Volz range, when you use SERVOn_MIN and SERVOn_MAX parameters.
This commit is contained in:
parent
f62a27ca8a
commit
19f3fda31b
@ -73,15 +73,15 @@ void AP_Volz_Protocol::update()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check if current channel PWM is within range
|
// check if current channel PWM is within range
|
||||||
if (c->get_output_pwm() < c->get_output_min()) {
|
if (c->get_output_pwm() < VOLZ_PWM_POSITION_MIN) {
|
||||||
value = 0;
|
value = 0;
|
||||||
} else {
|
} else {
|
||||||
value = c->get_output_pwm() - c->get_output_min();
|
value = c->get_output_pwm() - VOLZ_PWM_POSITION_MIN;
|
||||||
}
|
}
|
||||||
|
|
||||||
// scale the PWM value to Volz value
|
// scale the PWM value to Volz value
|
||||||
|
value = value * VOLZ_SCALE_VALUE / (VOLZ_PWM_POSITION_MAX - VOLZ_PWM_POSITION_MIN);
|
||||||
value = value + VOLZ_EXTENDED_POSITION_MIN;
|
value = value + VOLZ_EXTENDED_POSITION_MIN;
|
||||||
value = value * VOLZ_SCALE_VALUE / (c->get_output_max() - c->get_output_min());
|
|
||||||
|
|
||||||
// make sure value stays in range
|
// make sure value stays in range
|
||||||
if (value > VOLZ_EXTENDED_POSITION_MAX) {
|
if (value > VOLZ_EXTENDED_POSITION_MAX) {
|
||||||
|
@ -48,6 +48,9 @@
|
|||||||
#define VOLZ_EXTENDED_POSITION_CENTER 0x0800 // Extended Position Data Format defines 0 as 0x0800 - decimal 2048
|
#define VOLZ_EXTENDED_POSITION_CENTER 0x0800 // Extended Position Data Format defines 0 as 0x0800 - decimal 2048
|
||||||
#define VOLZ_EXTENDED_POSITION_MAX 0x0F80 // Extended Position Data Format defines +100 as 0x0F80 decimal 3968 -> full range decimal 3840
|
#define VOLZ_EXTENDED_POSITION_MAX 0x0F80 // Extended Position Data Format defines +100 as 0x0F80 decimal 3968 -> full range decimal 3840
|
||||||
|
|
||||||
|
#define VOLZ_PWM_POSITION_MIN 1000
|
||||||
|
#define VOLZ_PWM_POSITION_MAX 2000
|
||||||
|
|
||||||
class AP_Volz_Protocol {
|
class AP_Volz_Protocol {
|
||||||
public:
|
public:
|
||||||
AP_Volz_Protocol();
|
AP_Volz_Protocol();
|
||||||
|
Loading…
Reference in New Issue
Block a user