mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Copter: use cork/push wrapper
This commit is contained in:
parent
d57f307032
commit
23b20307af
@ -156,9 +156,9 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
read_radio();
|
read_radio();
|
||||||
|
|
||||||
// pass through throttle to motors
|
// 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);
|
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
|
||||||
hal.rcout->push();
|
SRV_Channels::push();
|
||||||
|
|
||||||
// read some compass values
|
// read some compass values
|
||||||
compass.read();
|
compass.read();
|
||||||
|
@ -116,9 +116,9 @@ void Copter::esc_calibration_passthrough()
|
|||||||
delay(3);
|
delay(3);
|
||||||
|
|
||||||
// pass through to motors
|
// pass through to motors
|
||||||
hal.rcout->cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
|
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
|
#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");
|
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
|
||||||
printed_msg = true;
|
printed_msg = true;
|
||||||
}
|
}
|
||||||
hal.rcout->cork();
|
SRV_Channels::cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||||
hal.rcout->push();
|
SRV_Channels::push();
|
||||||
esc_calibration_notify();
|
esc_calibration_notify();
|
||||||
delay(3);
|
delay(3);
|
||||||
}
|
}
|
||||||
|
@ -293,7 +293,7 @@ void Copter::motors_output()
|
|||||||
SRV_Channels::calc_pwm();
|
SRV_Channels::calc_pwm();
|
||||||
|
|
||||||
// cork now, so that all channel outputs happen at once
|
// 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
|
// update output on any aux channels, for manual passthru
|
||||||
SRV_Channels::output_ch_all();
|
SRV_Channels::output_ch_all();
|
||||||
@ -316,7 +316,7 @@ void Copter::motors_output()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// push all channels
|
// push all channels
|
||||||
hal.rcout->push();
|
SRV_Channels::push();
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for pilot stick input to trigger lost vehicle alarm
|
// check for pilot stick input to trigger lost vehicle alarm
|
||||||
|
Loading…
Reference in New Issue
Block a user