Skip to content

Commit

Permalink
Copter: make sure takeoff check checks the right ESC channels
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and tridge committed Nov 15, 2023
1 parent b44b804 commit 452ec19
Showing 1 changed file with 6 additions and 0 deletions.
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

0 comments on commit 452ec19

Please sign in to comment.