mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Support checking max rpm in the takeoff check
This commit is contained in:
parent
3de912f2b8
commit
04b16d1a79
@ -1215,6 +1215,15 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("TKOFF_THR_MAX", 6, ParametersG2, takeoff_throttle_max, 0.9),
|
AP_GROUPINFO("TKOFF_THR_MAX", 6, ParametersG2, takeoff_throttle_max, 0.9),
|
||||||
|
|
||||||
|
#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME
|
||||||
|
// @Param: TKOFF_RPM_MAX
|
||||||
|
// @DisplayName: Takeoff Check RPM maximum
|
||||||
|
// @Description: Takeoff is not permitted until motors report no more than this RPM. Set to zero to disable check
|
||||||
|
// @Range: 0 10000
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("TKOFF_RPM_MAX", 7, ParametersG2, takeoff_rpm_max, 0),
|
||||||
|
#endif
|
||||||
|
|
||||||
// ID 62 is reserved for the AP_SUBGROUPEXTENSION
|
// ID 62 is reserved for the AP_SUBGROUPEXTENSION
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -681,6 +681,7 @@ public:
|
|||||||
AP_Float takeoff_throttle_max;
|
AP_Float takeoff_throttle_max;
|
||||||
#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME
|
#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME
|
||||||
AP_Int16 takeoff_rpm_min;
|
AP_Int16 takeoff_rpm_min;
|
||||||
|
AP_Int16 takeoff_rpm_max;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if WEATHERVANE_ENABLED == ENABLED
|
#if WEATHERVANE_ENABLED == ENABLED
|
||||||
|
@ -30,7 +30,7 @@ void Copter::takeoff_check()
|
|||||||
// check ESCs are sending RPM at expected level
|
// check ESCs are sending RPM at expected level
|
||||||
uint32_t motor_mask = motors->get_motor_mask();
|
uint32_t motor_mask = motors->get_motor_mask();
|
||||||
const bool telem_active = AP::esc_telem().is_telemetry_active(motor_mask);
|
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);
|
const bool rpm_adequate = AP::esc_telem().are_motors_running(motor_mask, g2.takeoff_rpm_min, g2.takeoff_rpm_max);
|
||||||
|
|
||||||
// if RPM is at the expected level clear block
|
// if RPM is at the expected level clear block
|
||||||
if (telem_active && rpm_adequate) {
|
if (telem_active && rpm_adequate) {
|
||||||
@ -49,7 +49,7 @@ void Copter::takeoff_check()
|
|||||||
if (!telem_active) {
|
if (!telem_active) {
|
||||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s waiting for ESC RPM", prefix_str);
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s waiting for ESC RPM", prefix_str);
|
||||||
} else if (!rpm_adequate) {
|
} else if (!rpm_adequate) {
|
||||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s ESC RPM too low", prefix_str);
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s ESC RPM out of range", prefix_str);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user