mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: added throttle suppression for quadplanes
this tries to prevent motor start when on ground. Motors instead go into spin_when_armed state
This commit is contained in:
parent
66c4995c9d
commit
63317e9430
@ -1011,6 +1011,58 @@ void QuadPlane::update(void)
|
||||
tiltrotor_update();
|
||||
}
|
||||
|
||||
/*
|
||||
see if motors should be shutdown. If they should be then change AP_Motors state to
|
||||
AP_Motors::DESIRED_SHUT_DOWN
|
||||
|
||||
This is a safety check to prevent accidental motor runs on the
|
||||
ground, such as if RC fails and QRTL is started
|
||||
*/
|
||||
void QuadPlane::check_throttle_suppression(void)
|
||||
{
|
||||
// if the motors have been running in the last 2 seconds then
|
||||
// allow them to run now
|
||||
if (AP_HAL::millis() - last_motors_active_ms < 2000) {
|
||||
return;
|
||||
}
|
||||
|
||||
// see if motors are already disabled
|
||||
if (motors->get_desired_spool_state() < AP_Motors::DESIRED_THROTTLE_UNLIMITED) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if the users throttle is above zero then allow motors to run
|
||||
if (plane.channel_throttle->get_control_in() != 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if we are in a fixed wing auto throttle mode and we have
|
||||
// unsuppressed the throttle then allow motors to run
|
||||
if (plane.auto_throttle_mode && !plane.throttle_suppressed) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if our vertical velocity is greater than 1m/s then allow motors to run
|
||||
if (fabsf(inertial_nav.get_velocity_z()) > 100) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if we are more than 5m from home altitude then allow motors to run
|
||||
if (plane.relative_ground_altitude(plane.g.rangefinder_landing) > 5) {
|
||||
return;
|
||||
}
|
||||
|
||||
// allow for takeoff
|
||||
if (plane.control_mode == AUTO && plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_VTOL_TAKEOFF) {
|
||||
return;
|
||||
}
|
||||
|
||||
// motors should be in the spin when armed state to warn user they could become active
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors->set_throttle(0);
|
||||
last_motors_active_ms = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
output motors and do any copter needed
|
||||
*/
|
||||
@ -1020,6 +1072,10 @@ void QuadPlane::motors_output(void)
|
||||
// output is direct from run_esc_calibration()
|
||||
return;
|
||||
}
|
||||
|
||||
// see if motors should be shut down
|
||||
check_throttle_suppression();
|
||||
|
||||
motors->output();
|
||||
if (motors->armed()) {
|
||||
plane.DataFlash.Log_Write_Rate(plane.ahrs, *motors, *attitude_control, *pos_control);
|
||||
@ -1029,6 +1085,12 @@ void QuadPlane::motors_output(void)
|
||||
attitude_control->control_monitor_log();
|
||||
}
|
||||
}
|
||||
|
||||
// remember when motors were last active for throttle suppression
|
||||
if (motors->get_throttle() > 0.01f || tilt.motors_active) {
|
||||
last_motors_active_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -187,6 +187,8 @@ private:
|
||||
|
||||
void guided_start(void);
|
||||
void guided_update(void);
|
||||
|
||||
void check_throttle_suppression(void);
|
||||
|
||||
AP_Int16 transition_time_ms;
|
||||
|
||||
@ -262,10 +264,10 @@ private:
|
||||
} transition_state;
|
||||
|
||||
// true when waiting for pilot throttle
|
||||
bool throttle_wait;
|
||||
bool throttle_wait:1;
|
||||
|
||||
// true when quad is assisting a fixed wing mode
|
||||
bool assisted_flight;
|
||||
bool assisted_flight:1;
|
||||
|
||||
struct {
|
||||
// time when motors reached lower limit
|
||||
@ -324,6 +326,9 @@ private:
|
||||
bool motors_active:1;
|
||||
} tilt;
|
||||
|
||||
// time when motors were last active
|
||||
uint32_t last_motors_active_ms;
|
||||
|
||||
void tiltrotor_slew(float tilt);
|
||||
void tiltrotor_update(void);
|
||||
void tilt_compensate(float *thrust, uint8_t num_motors);
|
||||
|
Loading…
Reference in New Issue
Block a user