mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: replace set_throttle_out_unstabilized
This commit is contained in:
parent
c4e3c4142e
commit
d8d3522cba
@ -27,7 +27,8 @@ void Sub::acro_run()
|
|||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -39,7 +39,8 @@ void Sub::althold_run()
|
|||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
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)
|
// 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);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||||
last_pilot_heading = ahrs.yaw_sensor;
|
last_pilot_heading = ahrs.yaw_sensor;
|
||||||
return;
|
return;
|
||||||
|
@ -118,8 +118,8 @@ void Sub::auto_wp_run()
|
|||||||
// call attitude controller
|
// call attitude controller
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -203,9 +203,9 @@ void Sub::auto_spline_run()
|
|||||||
// To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
|
// To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
|
||||||
// (of course it would be better if people just used take-off)
|
// (of course it would be better if people just used take-off)
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// 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_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -391,7 +391,8 @@ void Sub::auto_loiter_run()
|
|||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -675,7 +676,8 @@ void Sub::auto_terrain_recover_run()
|
|||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -43,8 +43,8 @@ void Sub::circle_run()
|
|||||||
// To-Do: add some initialisation of position controllers
|
// To-Do: add some initialisation of position controllers
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
pos_control.set_alt_target_to_current_alt();
|
pos_control.set_alt_target_to_current_alt();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -293,8 +293,8 @@ void Sub::guided_pos_control_run()
|
|||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -344,8 +344,8 @@ void Sub::guided_vel_control_run()
|
|||||||
pos_control.init_vel_controller_xyz();
|
pos_control.init_vel_controller_xyz();
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -399,8 +399,8 @@ void Sub::guided_posvel_control_run()
|
|||||||
pos_control.set_desired_velocity(Vector3f(0,0,0));
|
pos_control.set_desired_velocity(Vector3f(0,0,0));
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -469,8 +469,8 @@ void Sub::guided_angle_control_run()
|
|||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control.set_throttle_out_unstabilized(0.0f,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0.0f,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -20,7 +20,8 @@ void Sub::manual_run()
|
|||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -43,7 +43,8 @@ void Sub::poshold_run()
|
|||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
loiter_nav.clear_pilot_desired_acceleration();
|
loiter_nav.clear_pilot_desired_acceleration();
|
||||||
loiter_nav.init_target();
|
loiter_nav.init_target();
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -21,7 +21,8 @@ void Sub::stabilize_run()
|
|||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
last_pilot_heading = ahrs.yaw_sensor;
|
last_pilot_heading = ahrs.yaw_sensor;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -28,7 +28,8 @@ void Sub::surface_run()
|
|||||||
if (!motors.armed()) {
|
if (!motors.armed()) {
|
||||||
motors.output_min();
|
motors.output_min();
|
||||||
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
motors.set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
|
||||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control.set_throttle_out(0,true,g.throttle_filt);
|
||||||
|
attitude_control.relax_attitude_controllers();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user