mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: fixup RC_Channel data member accesses to function calls
This commit is contained in:
parent
12cf65baed
commit
49d3410896
|
@ -143,7 +143,7 @@ void Copter::heli_update_rotor_speed_targets()
|
||||||
// get rotor control method
|
// get rotor control method
|
||||||
uint8_t rsc_control_mode = motors.get_rsc_mode();
|
uint8_t rsc_control_mode = motors.get_rsc_mode();
|
||||||
|
|
||||||
float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)g.rc_8.control_in/1000.0f);
|
float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)g.rc_8.get_control_in()/1000.0f);
|
||||||
|
|
||||||
switch (rsc_control_mode) {
|
switch (rsc_control_mode) {
|
||||||
case ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH:
|
case ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH:
|
||||||
|
|
Loading…
Reference in New Issue