Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions ArduSub/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -183,6 +183,10 @@
# define AUTO_DISARMING_DELAY 0
#endif

#ifndef NEUTRAL_THROTTLE
# define NEUTRAL_THROTTLE (0.5f) // Throttle output for "no vertical thrust"
#endif

//////////////////////////////////////////////////////////////////////////////
// Logging control
//
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/mode_acro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ void ModeAcro::run()
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
return;
}
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/mode_althold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ void ModeAlthold::run_pre()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::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(0.5,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->relax_z_controller(motors.get_throttle_hover());
sub.last_pilot_heading = ahrs.yaw_sensor;
Expand Down
6 changes: 3 additions & 3 deletions ArduSub/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ void ModeAuto::auto_wp_run()
// call attitude controller
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.wp_nav.wp_and_spline_init(); // Reset xy target
return;
Expand Down Expand Up @@ -302,7 +302,7 @@ void ModeAuto::auto_loiter_run()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();

sub.wp_nav.wp_and_spline_init(); // Reset xy target
Expand Down Expand Up @@ -475,7 +475,7 @@ void ModeAuto::auto_terrain_recover_run()
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();

sub.loiter_nav.init_target(); // Reset xy target
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/mode_circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ void ModeCircle::run()
// To-Do: add some initialisation of position controllers
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.circle_nav.init();
return;
Expand Down
8 changes: 4 additions & 4 deletions ArduSub/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -457,7 +457,7 @@ void ModeGuided::guided_pos_control_run()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.wp_nav.wp_and_spline_init();
return;
Expand Down Expand Up @@ -522,7 +522,7 @@ void ModeGuided::guided_vel_control_run()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
// initialise velocity controller
position_control->init_z_controller();
Expand Down Expand Up @@ -595,7 +595,7 @@ void ModeGuided::guided_posvel_control_run()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
// initialise velocity controller
position_control->init_z_controller();
Expand Down Expand Up @@ -675,7 +675,7 @@ void ModeGuided::guided_angle_control_run()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out(0.0f,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
// initialise velocity controller
position_control->init_z_controller();
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/mode_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ void ModeManual::run()
// if not armed set throttle to zero and exit immediately
if (!sub.motors.armed()) {
sub.motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
return;
}
Expand Down
4 changes: 2 additions & 2 deletions ArduSub/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ bool ModePoshold::init(bool ignore_checks)
position_control->init_z_controller();

// Stop all thrusters
attitude_control->set_throttle_out(0.5f ,true, g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE ,true, g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->relax_z_controller(0.5f);

Expand All @@ -43,7 +43,7 @@ void ModePoshold::run()
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::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(0.5f ,true, g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE ,true, g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->init_xy_controller_stopping_point();
position_control->relax_z_controller(0.5f);
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/mode_stabilize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ void ModeStabilize::run()
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.last_pilot_heading = ahrs.yaw_sensor;
return;
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/mode_surface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ void ModeSurface::run()
if (!motors.armed()) {
motors.output_min();
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->init_z_controller();
return;
Expand Down
Loading