diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index c8568532bf..4c77f95c47 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -156,9 +156,9 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) read_radio(); // pass through throttle to motors - hal.rcout->cork(); + SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f); - hal.rcout->push(); + SRV_Channels::push(); // read some compass values compass.read(); diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index f416fb5b07..b3c670395a 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -116,9 +116,9 @@ void Copter::esc_calibration_passthrough() delay(3); // pass through to motors - hal.rcout->cork(); + SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f); - hal.rcout->push(); + SRV_Channels::push(); } #endif // FRAME_CONFIG != HELI_FRAME } @@ -163,9 +163,9 @@ void Copter::esc_calibration_auto() gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch"); printed_msg = true; } - hal.rcout->cork(); + SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(1.0f); - hal.rcout->push(); + SRV_Channels::push(); esc_calibration_notify(); delay(3); } diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 6cb789a4d9..79d9f27817 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -293,7 +293,7 @@ void Copter::motors_output() SRV_Channels::calc_pwm(); // cork now, so that all channel outputs happen at once - hal.rcout->cork(); + SRV_Channels::cork(); // update output on any aux channels, for manual passthru SRV_Channels::output_ch_all(); @@ -316,7 +316,7 @@ void Copter::motors_output() } // push all channels - hal.rcout->push(); + SRV_Channels::push(); } // check for pilot stick input to trigger lost vehicle alarm