Removed some old debug prints from motors.pde

added ability to not increment I term for traversals.
This commit is contained in:
Jason Short 2011-11-07 14:32:39 -08:00
parent f3964611e1
commit 34a53f6f7d
4 changed files with 11 additions and 8 deletions

View File

@ -91,9 +91,10 @@ get_stabilize_yaw(long target_angle)
static int
get_nav_throttle(long z_error)
{
bool calc_i = abs(z_error) < ALT_ERROR_MAX;
// limit error to prevent I term run up
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
int rate_error = g.pi_alt_hold.get_pi(z_error, .1); //_p = .85
int rate_error = g.pi_alt_hold.get_pi(z_error, .1, calc_i); //_p = .85
rate_error = rate_error - climb_rate;
// limit the rate

View File

@ -20,7 +20,7 @@ static void arm_motors()
// full right
if (g.rc_4.control_in > 4000) {
if (arming_counter == LEVEL_DELAY){
Serial.printf("\nAL\n");
//Serial.printf("\nAL\n");
// begin auto leveling
auto_level_counter = 200;
arming_counter = 0;
@ -39,7 +39,7 @@ static void arm_motors()
// full left
}else if (g.rc_4.control_in < -4000) {
if (arming_counter == LEVEL_DELAY){
Serial.printf("\nLEV\n");
//Serial.printf("\nLEV\n");
// begin manual leveling
imu.init_accel(mavlink_delay);
@ -65,7 +65,7 @@ static void arm_motors()
static void init_arm_motors()
{
Serial.printf("\nARM\n");
//Serial.printf("\nARM\n");
#if HIL_MODE != HIL_MODE_DISABLED
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
#endif
@ -106,7 +106,7 @@ static void init_arm_motors()
static void init_disarm_motors()
{
Serial.printf("\nDISARM\n");
//Serial.printf("\nDISARM\n");
#if HIL_MODE != HIL_MODE_DISABLED
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
#endif

View File

@ -8,9 +8,10 @@
#include "APM_PI.h"
long
APM_PI::get_pi(int32_t error, float dt)
APM_PI::get_pi(int32_t error, float dt, bool calc_i)
{
_integrator += ((float)error * _ki) * dt;
if(true)
_integrator += ((float)error * _ki) * dt;
if (_integrator < -_imax) {
_integrator = -_imax;

View File

@ -77,7 +77,8 @@ public:
///
/// @returns The updated control output.
///
long get_pi(int32_t error, float dt);
//long get_pi(int32_t error, float dt);
long get_pi(int32_t error, float dt, bool calc_i=true);
/// Reset the PI integrator
///