mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
ArduCopter: make SRV_Channels::cork non-static
for symmetry with the push function
This commit is contained in:
parent
50c574672a
commit
3403a49236
@ -146,9 +146,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
|||||||
read_radio();
|
read_radio();
|
||||||
|
|
||||||
// pass through throttle to motors
|
// pass through throttle to motors
|
||||||
SRV_Channels::cork();
|
auto &srv = AP::srv();
|
||||||
|
srv.cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||||
AP::srv().push();
|
srv.push();
|
||||||
|
|
||||||
// read some compass values
|
// read some compass values
|
||||||
compass.read();
|
compass.read();
|
||||||
|
@ -95,9 +95,10 @@ void Copter::esc_calibration_passthrough()
|
|||||||
hal.scheduler->delay(3);
|
hal.scheduler->delay(3);
|
||||||
|
|
||||||
// pass through to motors
|
// pass through to motors
|
||||||
SRV_Channels::cork();
|
auto &srv = AP::srv();
|
||||||
|
srv.cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||||
AP::srv().push();
|
srv.push();
|
||||||
}
|
}
|
||||||
#endif // FRAME_CONFIG != HELI_FRAME
|
#endif // FRAME_CONFIG != HELI_FRAME
|
||||||
}
|
}
|
||||||
@ -112,25 +113,26 @@ void Copter::esc_calibration_auto()
|
|||||||
esc_calibration_setup();
|
esc_calibration_setup();
|
||||||
|
|
||||||
// raise throttle to maximum
|
// raise throttle to maximum
|
||||||
SRV_Channels::cork();
|
auto &srv = AP::srv();
|
||||||
|
srv.cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||||
AP::srv().push();
|
srv.push();
|
||||||
|
|
||||||
// delay for 5 seconds while outputting pulses
|
// delay for 5 seconds while outputting pulses
|
||||||
uint32_t tstart = millis();
|
uint32_t tstart = millis();
|
||||||
while (millis() - tstart < 5000) {
|
while (millis() - tstart < 5000) {
|
||||||
SRV_Channels::cork();
|
srv.cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||||
AP::srv().push();
|
srv.push();
|
||||||
esc_calibration_notify();
|
esc_calibration_notify();
|
||||||
hal.scheduler->delay(3);
|
hal.scheduler->delay(3);
|
||||||
}
|
}
|
||||||
|
|
||||||
// block until we restart
|
// block until we restart
|
||||||
while(1) {
|
while(1) {
|
||||||
SRV_Channels::cork();
|
srv.cork();
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
||||||
AP::srv().push();
|
srv.push();
|
||||||
esc_calibration_notify();
|
esc_calibration_notify();
|
||||||
hal.scheduler->delay(3);
|
hal.scheduler->delay(3);
|
||||||
}
|
}
|
||||||
|
@ -156,8 +156,10 @@ void Copter::motors_output()
|
|||||||
// output any servo channels
|
// output any servo channels
|
||||||
SRV_Channels::calc_pwm();
|
SRV_Channels::calc_pwm();
|
||||||
|
|
||||||
|
auto &srv = AP::srv();
|
||||||
|
|
||||||
// cork now, so that all channel outputs happen at once
|
// cork now, so that all channel outputs happen at once
|
||||||
SRV_Channels::cork();
|
srv.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();
|
||||||
@ -181,7 +183,7 @@ void Copter::motors_output()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// push all channels
|
// push all channels
|
||||||
AP::srv().push();
|
srv.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