Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Correct ESC mask for takeoff check #25512

Merged
merged 1 commit into from
Nov 15, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions ArduCopter/takeoff_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ void Copter::takeoff_check()

// check ESCs are sending RPM at expected level
uint32_t motor_mask = motors->get_motor_mask();
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
// In 4.4 and earlier ESC telemetry is always indexed from 1 for servo channels 9+
motor_mask >>= 8;
}
#endif
const bool telem_active = AP::esc_telem().is_telemetry_active(motor_mask);
const bool rpm_adequate = AP::esc_telem().are_motors_running(motor_mask, g2.takeoff_rpm_min);

Expand Down