mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-08 02:17:07 +08:00
Fix usage of PWM defines in mavlink app
This commit is contained in:
@@ -1801,7 +1801,7 @@ protected:
|
||||
|
||||
float out[8];
|
||||
|
||||
const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2;
|
||||
const float pwm_center = (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2;
|
||||
|
||||
unsigned system_type = _mavlink->get_system_type();
|
||||
|
||||
@@ -1839,14 +1839,14 @@ protected:
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < 8; i++) {
|
||||
if (act.output[i] > PWM_LOWEST_MIN / 2) {
|
||||
if (act.output[i] > PWM_DEFAULT_MIN / 2) {
|
||||
if (i < n) {
|
||||
/* scale PWM out 900..2100 us to 0..1 for rotors */
|
||||
out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
|
||||
out[i] = (act.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
|
||||
|
||||
} else {
|
||||
/* scale PWM out 900..2100 us to -1..1 for other channels */
|
||||
out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
|
||||
out[i] = (act.output[i] - pwm_center) / ((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2);
|
||||
}
|
||||
|
||||
} else {
|
||||
@@ -1859,14 +1859,14 @@ protected:
|
||||
/* fixed wing: scale throttle to 0..1 and other channels to -1..1 */
|
||||
|
||||
for (unsigned i = 0; i < 8; i++) {
|
||||
if (act.output[i] > PWM_LOWEST_MIN / 2) {
|
||||
if (act.output[i] > PWM_DEFAULT_MIN / 2) {
|
||||
if (i != 3) {
|
||||
/* scale PWM out 900..2100 us to -1..1 for normal channels */
|
||||
out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
|
||||
out[i] = (act.output[i] - pwm_center) / ((PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2);
|
||||
|
||||
} else {
|
||||
/* scale PWM out 900..2100 us to 0..1 for throttle */
|
||||
out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
|
||||
out[i] = (act.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN);
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
Reference in New Issue
Block a user