|
|
|
@ -111,8 +111,8 @@ void Sub::auto_wp_start(const Location_Class& dest_loc)
@@ -111,8 +111,8 @@ void Sub::auto_wp_start(const Location_Class& dest_loc)
|
|
|
|
|
// called by auto_run at 100hz or more
|
|
|
|
|
void Sub::auto_wp_run() |
|
|
|
|
{ |
|
|
|
|
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed() || !motors.get_interlock()) { |
|
|
|
|
// if not auto armed set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed()) { |
|
|
|
|
// 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)
|
|
|
|
|
// call attitude controller
|
|
|
|
@ -198,8 +198,8 @@ void Sub::auto_spline_start(const Location_Class& destination, bool stopped_at_s
@@ -198,8 +198,8 @@ void Sub::auto_spline_start(const Location_Class& destination, bool stopped_at_s
|
|
|
|
|
// called by auto_run at 100hz or more
|
|
|
|
|
void Sub::auto_spline_run() |
|
|
|
|
{ |
|
|
|
|
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) { |
|
|
|
|
// if not auto armed set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed() || !ap.auto_armed) { |
|
|
|
|
// 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)
|
|
|
|
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
|
|
|
@ -376,8 +376,8 @@ bool Sub::auto_loiter_start()
@@ -376,8 +376,8 @@ bool Sub::auto_loiter_start()
|
|
|
|
|
// called by auto_run at 100hz or more
|
|
|
|
|
void Sub::auto_loiter_run() |
|
|
|
|
{ |
|
|
|
|
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed() || !motors.get_interlock()) { |
|
|
|
|
// if not auto armed set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed()) { |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
|
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); |
|
|
|
@ -661,7 +661,7 @@ void Sub::auto_terrain_recover_run()
@@ -661,7 +661,7 @@ void Sub::auto_terrain_recover_run()
|
|
|
|
|
static uint32_t rangefinder_recovery_ms = 0; |
|
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
|
|
|
|
if (!motors.armed() || !motors.get_interlock()) { |
|
|
|
|
if (!motors.armed()) { |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); |
|
|
|
|
return; |
|
|
|
|