mirror of https://github.com/ArduPilot/ardupilot
Plane: adjust for desired spool state and spool state renames
This commit is contained in:
parent
46a6f45e4a
commit
f09822a400
|
@ -772,14 +772,14 @@ void QuadPlane::hold_stabilize(float throttle_in)
|
|||
multicopter_attitude_rate_update(get_desired_yaw_rate_cds());
|
||||
|
||||
if (throttle_in <= 0) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||
attitude_control->set_throttle_out(0, true, 0);
|
||||
if (!is_tailsitter()) {
|
||||
// always stabilize with tailsitters so we can do belly takeoffs
|
||||
attitude_control->relax_attitude_controllers();
|
||||
}
|
||||
} else {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
attitude_control->set_throttle_out(throttle_in, true, 0);
|
||||
}
|
||||
}
|
||||
|
@ -890,7 +890,7 @@ void QuadPlane::check_yaw_reset(void)
|
|||
void QuadPlane::hold_hover(float target_climb_rate)
|
||||
{
|
||||
// motors use full range
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
|
||||
// initialize vertical speeds and acceleration
|
||||
pos_control->set_max_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);
|
||||
|
@ -910,13 +910,13 @@ void QuadPlane::hold_hover(float target_climb_rate)
|
|||
void QuadPlane::control_qacro(void)
|
||||
{
|
||||
if (throttle_wait) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||
attitude_control->set_throttle_out(0, true, 0);
|
||||
attitude_control->relax_attitude_controllers();
|
||||
} else {
|
||||
check_attitude_relax();
|
||||
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
|
||||
// convert the input to the desired body frame rate
|
||||
float target_roll = 0;
|
||||
|
@ -975,7 +975,7 @@ void QuadPlane::control_qacro(void)
|
|||
void QuadPlane::control_hover(void)
|
||||
{
|
||||
if (throttle_wait) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||
attitude_control->set_throttle_out(0, true, 0);
|
||||
attitude_control->relax_attitude_controllers();
|
||||
pos_control->relax_alt_hold_controllers(0);
|
||||
|
@ -1062,7 +1062,7 @@ bool QuadPlane::is_flying_vtol(void) const
|
|||
if (!available()) {
|
||||
return false;
|
||||
}
|
||||
if (motors->get_spool_mode() == AP_Motors::SHUT_DOWN) {
|
||||
if (motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) {
|
||||
// assume that with no motor outputs we're not flying in VTOL mode
|
||||
return false;
|
||||
}
|
||||
|
@ -1104,7 +1104,7 @@ float QuadPlane::landing_descent_rate_cms(float height_above_ground) const
|
|||
void QuadPlane::control_loiter()
|
||||
{
|
||||
if (throttle_wait) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||
attitude_control->set_throttle_out(0, true, 0);
|
||||
attitude_control->relax_attitude_controllers();
|
||||
pos_control->relax_alt_hold_controllers(0);
|
||||
|
@ -1127,7 +1127,7 @@ void QuadPlane::control_loiter()
|
|||
last_loiter_ms = now;
|
||||
|
||||
// motors use full range
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
|
||||
// initialize vertical speed and acceleration
|
||||
pos_control->set_max_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);
|
||||
|
@ -1369,7 +1369,7 @@ void QuadPlane::update_transition(void)
|
|||
plane.control_mode == &plane.mode_training) {
|
||||
// in manual modes quad motors are always off
|
||||
if (!tilt.motors_active && !is_tailsitter()) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||
motors->output();
|
||||
}
|
||||
transition_state = TRANSITION_DONE;
|
||||
|
@ -1462,7 +1462,7 @@ void QuadPlane::update_transition(void)
|
|||
|
||||
switch (transition_state) {
|
||||
case TRANSITION_AIRSPEED_WAIT: {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
// we hold in hover until the required airspeed is reached
|
||||
if (transition_start_ms == 0) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Transition airspeed wait");
|
||||
|
@ -1505,7 +1505,7 @@ void QuadPlane::update_transition(void)
|
|||
}
|
||||
|
||||
case TRANSITION_TIMER: {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
// after airspeed is reached we degrade throttle over the
|
||||
// transition time, but continue to stabilize
|
||||
const uint32_t transition_timer_ms = now - transition_low_airspeed_ms;
|
||||
|
@ -1542,7 +1542,7 @@ void QuadPlane::update_transition(void)
|
|||
}
|
||||
|
||||
case TRANSITION_ANGLE_WAIT_FW: {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
assisted_flight = true;
|
||||
// calculate transition rate in degrees per
|
||||
// millisecond. Assume we want to get to the transition angle
|
||||
|
@ -1565,7 +1565,7 @@ void QuadPlane::update_transition(void)
|
|||
|
||||
case TRANSITION_DONE:
|
||||
if (!tilt.motors_active && !is_tailsitter()) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||
motors->output();
|
||||
}
|
||||
return;
|
||||
|
@ -1590,7 +1590,7 @@ void QuadPlane::update(void)
|
|||
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
if (plane.afs.should_crash_vehicle()) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||
motors->output();
|
||||
return;
|
||||
}
|
||||
|
@ -1688,7 +1688,7 @@ void QuadPlane::update(void)
|
|||
|
||||
/*
|
||||
see if motors should be shutdown. If they should be then change AP_Motors state to
|
||||
AP_Motors::DESIRED_SHUT_DOWN
|
||||
AP_Motors::DesiredSpoolState::SHUT_DOWN
|
||||
|
||||
This is a safety check to prevent accidental motor runs on the
|
||||
ground, such as if RC fails and QRTL is started
|
||||
|
@ -1702,7 +1702,7 @@ void QuadPlane::update_throttle_suppression(void)
|
|||
}
|
||||
|
||||
// see if motors are already disabled
|
||||
if (motors->get_desired_spool_state() < AP_Motors::DESIRED_THROTTLE_UNLIMITED) {
|
||||
if (motors->get_desired_spool_state() < AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1733,7 +1733,7 @@ void QuadPlane::update_throttle_suppression(void)
|
|||
}
|
||||
|
||||
// motors should be in the spin when armed state to warn user they could become active
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
||||
motors->set_throttle(0);
|
||||
last_motors_active_ms = 0;
|
||||
}
|
||||
|
@ -1780,7 +1780,7 @@ void QuadPlane::motors_output(bool run_rate_controller)
|
|||
#else
|
||||
if (!hal.util->get_soft_armed() || SRV_Channels::get_emergency_stop()) {
|
||||
#endif
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||
motors->output();
|
||||
return;
|
||||
}
|
||||
|
@ -1802,7 +1802,7 @@ void QuadPlane::motors_output(bool run_rate_controller)
|
|||
update_throttle_suppression();
|
||||
|
||||
motors->output();
|
||||
if (motors->armed() && motors->get_spool_mode() != AP_Motors::spool_up_down_mode::SHUT_DOWN) {
|
||||
if (motors->armed() && motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN) {
|
||||
plane.logger.Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
||||
Log_Write_QControl_Tuning();
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
|
@ -2209,7 +2209,7 @@ void QuadPlane::setup_target_position(void)
|
|||
{
|
||||
const Location &loc = plane.next_WP_loc;
|
||||
Location origin = inertial_nav.get_origin();
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
|
||||
const Vector2f diff2d = origin.get_distance_NE(loc);
|
||||
poscontrol.target.x = diff2d.x * 100;
|
||||
|
@ -2301,7 +2301,7 @@ void QuadPlane::control_auto(const Location &loc)
|
|||
return;
|
||||
}
|
||||
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
|
||||
uint16_t id = plane.mission.get_current_nav_cmd().id;
|
||||
switch (id) {
|
||||
|
@ -2614,7 +2614,7 @@ int8_t QuadPlane::forward_throttle_pct(void)
|
|||
plane.control_mode == &plane.mode_qstabilize ||
|
||||
plane.control_mode == &plane.mode_qhover ||
|
||||
plane.control_mode == &plane.mode_qautotune ||
|
||||
motors->get_desired_spool_state() < AP_Motors::DESIRED_GROUND_IDLE) {
|
||||
motors->get_desired_spool_state() < AP_Motors::DesiredSpoolState::GROUND_IDLE) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -2758,7 +2758,7 @@ void QuadPlane::guided_update(void)
|
|||
{
|
||||
if (plane.control_mode == &plane.mode_guided && guided_takeoff && plane.current_loc.alt < plane.next_WP_loc.alt) {
|
||||
throttle_wait = false;
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
takeoff_controller();
|
||||
} else {
|
||||
guided_takeoff = false;
|
||||
|
@ -2770,7 +2770,7 @@ void QuadPlane::guided_update(void)
|
|||
void QuadPlane::afs_terminate(void)
|
||||
{
|
||||
if (available()) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
||||
motors->output();
|
||||
}
|
||||
}
|
||||
|
@ -2828,7 +2828,7 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude)
|
|||
plane.prev_WP_loc = plane.current_loc;
|
||||
plane.next_WP_loc = plane.current_loc;
|
||||
plane.next_WP_loc.alt += takeoff_altitude*100;
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||
guided_start();
|
||||
guided_takeoff = true;
|
||||
return true;
|
||||
|
|
|
@ -266,7 +266,7 @@ void Plane::control_failsafe()
|
|||
case Mode::Number::QRTL: // throttle is ignored, but reset anyways
|
||||
case Mode::Number::QACRO:
|
||||
case Mode::Number::QAUTOTUNE:
|
||||
if (quadplane.available() && quadplane.motors->get_desired_spool_state() > AP_Motors::DESIRED_GROUND_IDLE) {
|
||||
if (quadplane.available() && quadplane.motors->get_desired_spool_state() > AP_Motors::DesiredSpoolState::GROUND_IDLE) {
|
||||
// set half throttle to avoid descending at maximum rate, still has a slight descent due to throttle deadzone
|
||||
channel_throttle->set_control_in(channel_throttle->get_range() / 2);
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue