mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Copter: fixed off-by-one in rcmapper
oops ...
This commit is contained in:
parent
6bac13f9e2
commit
340c451caf
@ -122,12 +122,12 @@ static void read_radio()
|
|||||||
ap_system.new_radio_frame = true;
|
ap_system.new_radio_frame = true;
|
||||||
uint16_t periods[8];
|
uint16_t periods[8];
|
||||||
hal.rcin->read(periods,8);
|
hal.rcin->read(periods,8);
|
||||||
g.rc_1.set_pwm(periods[rcmap.roll()]);
|
g.rc_1.set_pwm(periods[rcmap.roll()-1]);
|
||||||
g.rc_2.set_pwm(periods[rcmap.pitch()]);
|
g.rc_2.set_pwm(periods[rcmap.pitch()-1]);
|
||||||
|
|
||||||
set_throttle_and_failsafe(periods[rcmap.throttle()]);
|
set_throttle_and_failsafe(periods[rcmap.throttle()-1]);
|
||||||
|
|
||||||
g.rc_4.set_pwm(periods[rcmap.yaw()]);
|
g.rc_4.set_pwm(periods[rcmap.yaw()-1]);
|
||||||
g.rc_5.set_pwm(periods[4]);
|
g.rc_5.set_pwm(periods[4]);
|
||||||
g.rc_6.set_pwm(periods[5]);
|
g.rc_6.set_pwm(periods[5]);
|
||||||
g.rc_7.set_pwm(periods[6]);
|
g.rc_7.set_pwm(periods[6]);
|
||||||
|
Loading…
Reference in New Issue
Block a user