mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
Sub: desired-ground-idle replaces spin-when-armed
This commit is contained in:
parent
2650b1fe93
commit
8ba87171e6
@ -26,7 +26,7 @@ void Sub::acro_run()
|
||||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
return;
|
||||
}
|
||||
|
@ -37,7 +37,7 @@ void Sub::althold_run()
|
||||
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||
|
@ -117,7 +117,7 @@ void Sub::auto_wp_run()
|
||||
// (of course it would be better if people just used take-off)
|
||||
// call attitude controller
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
||||
return;
|
||||
@ -204,7 +204,7 @@ void Sub::auto_spline_run()
|
||||
// (of course it would be better if people just used take-off)
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
|
||||
return;
|
||||
}
|
||||
@ -389,7 +389,7 @@ void Sub::auto_loiter_run()
|
||||
{
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
||||
@ -674,7 +674,7 @@ void Sub::auto_terrain_recover_run()
|
||||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
return;
|
||||
}
|
||||
|
@ -41,7 +41,7 @@ void Sub::circle_run()
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
// To-Do: add some initialisation of position controllers
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
||||
|
@ -291,7 +291,7 @@ void Sub::guided_pos_control_run()
|
||||
{
|
||||
// if motors not enabled set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
||||
@ -342,7 +342,7 @@ void Sub::guided_vel_control_run()
|
||||
if (!motors.armed()) {
|
||||
// initialise velocity controller
|
||||
pos_control.init_vel_controller_xyz();
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
||||
@ -397,7 +397,7 @@ void Sub::guided_posvel_control_run()
|
||||
// set target position and velocity to current position and velocity
|
||||
pos_control.set_pos_target(inertial_nav.get_position());
|
||||
pos_control.set_desired_velocity(Vector3f(0,0,0));
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
||||
@ -467,7 +467,7 @@ void Sub::guided_angle_control_run()
|
||||
{
|
||||
// if motors not enabled set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||
attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt);
|
||||
|
||||
|
@ -19,7 +19,7 @@ void Sub::manual_run()
|
||||
{
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
return;
|
||||
}
|
||||
|
@ -40,7 +40,7 @@ void Sub::poshold_run()
|
||||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
loiter_nav.clear_pilot_desired_acceleration();
|
||||
loiter_nav.init_target();
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
|
@ -20,7 +20,7 @@ void Sub::stabilize_run()
|
||||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
last_pilot_heading = ahrs.yaw_sensor;
|
||||
return;
|
||||
|
@ -27,7 +27,7 @@ void Sub::surface_run()
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed()) {
|
||||
motors.output_min();
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user