mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
Plane: quadplane sets motors desired spool state
This commit is contained in:
parent
0abea7af68
commit
39f795d9fd
@ -495,8 +495,10 @@ void QuadPlane::hold_stabilize(float throttle_in)
|
|||||||
smoothing_gain);
|
smoothing_gain);
|
||||||
|
|
||||||
if (throttle_in <= 0) {
|
if (throttle_in <= 0) {
|
||||||
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||||
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
||||||
} else {
|
} else {
|
||||||
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
attitude_control->set_throttle_out(throttle_in, true, 0);
|
attitude_control->set_throttle_out(throttle_in, true, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -528,6 +530,9 @@ void QuadPlane::init_hover(void)
|
|||||||
*/
|
*/
|
||||||
void QuadPlane::hold_hover(float target_climb_rate)
|
void QuadPlane::hold_hover(float target_climb_rate)
|
||||||
{
|
{
|
||||||
|
// motors use full range
|
||||||
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
|
|
||||||
// initialize vertical speeds and acceleration
|
// initialize vertical speeds and acceleration
|
||||||
pos_control->set_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);
|
pos_control->set_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);
|
||||||
pos_control->set_accel_z(pilot_accel_z);
|
pos_control->set_accel_z(pilot_accel_z);
|
||||||
@ -550,6 +555,7 @@ void QuadPlane::hold_hover(float target_climb_rate)
|
|||||||
void QuadPlane::control_hover(void)
|
void QuadPlane::control_hover(void)
|
||||||
{
|
{
|
||||||
if (throttle_wait) {
|
if (throttle_wait) {
|
||||||
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||||
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
||||||
pos_control->relax_alt_hold_controllers(0);
|
pos_control->relax_alt_hold_controllers(0);
|
||||||
} else {
|
} else {
|
||||||
@ -616,6 +622,7 @@ bool QuadPlane::should_relax(void)
|
|||||||
void QuadPlane::control_loiter()
|
void QuadPlane::control_loiter()
|
||||||
{
|
{
|
||||||
if (throttle_wait) {
|
if (throttle_wait) {
|
||||||
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||||
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
attitude_control->set_throttle_out_unstabilized(0, true, 0);
|
||||||
pos_control->relax_alt_hold_controllers(0);
|
pos_control->relax_alt_hold_controllers(0);
|
||||||
wp_nav->init_loiter_target();
|
wp_nav->init_loiter_target();
|
||||||
@ -631,7 +638,10 @@ void QuadPlane::control_loiter()
|
|||||||
wp_nav->init_loiter_target();
|
wp_nav->init_loiter_target();
|
||||||
}
|
}
|
||||||
last_loiter_ms = millis();
|
last_loiter_ms = millis();
|
||||||
|
|
||||||
|
// motors use full range
|
||||||
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||||
|
|
||||||
// initialize vertical speed and acceleration
|
// initialize vertical speed and acceleration
|
||||||
pos_control->set_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);
|
pos_control->set_speed_z(-pilot_velocity_z_max, pilot_velocity_z_max);
|
||||||
pos_control->set_accel_z(pilot_accel_z);
|
pos_control->set_accel_z(pilot_accel_z);
|
||||||
@ -791,7 +801,8 @@ void QuadPlane::update_transition(void)
|
|||||||
plane.control_mode == ACRO ||
|
plane.control_mode == ACRO ||
|
||||||
plane.control_mode == TRAINING) {
|
plane.control_mode == TRAINING) {
|
||||||
// in manual modes quad motors are always off
|
// in manual modes quad motors are always off
|
||||||
motors->output_min();
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||||
|
motors->output();
|
||||||
transition_state = TRANSITION_DONE;
|
transition_state = TRANSITION_DONE;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -861,7 +872,7 @@ void QuadPlane::update_transition(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
case TRANSITION_DONE:
|
case TRANSITION_DONE:
|
||||||
motors->output_min();
|
motors->output();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -1216,7 +1227,6 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
|
|||||||
if (!setup()) {
|
if (!setup()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
motors->slow_start(true);
|
|
||||||
pid_rate_roll.reset_I();
|
pid_rate_roll.reset_I();
|
||||||
pid_rate_pitch.reset_I();
|
pid_rate_pitch.reset_I();
|
||||||
pid_rate_yaw.reset_I();
|
pid_rate_yaw.reset_I();
|
||||||
|
Loading…
Reference in New Issue
Block a user