Removed some old debug prints from motors.pde
added ability to not increment I term for traversals.
This commit is contained in:
parent
f3964611e1
commit
34a53f6f7d
@ -91,9 +91,10 @@ get_stabilize_yaw(long target_angle)
|
|||||||
static int
|
static int
|
||||||
get_nav_throttle(long z_error)
|
get_nav_throttle(long z_error)
|
||||||
{
|
{
|
||||||
|
bool calc_i = abs(z_error) < ALT_ERROR_MAX;
|
||||||
// limit error to prevent I term run up
|
// limit error to prevent I term run up
|
||||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
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;
|
rate_error = rate_error - climb_rate;
|
||||||
|
|
||||||
// limit the rate
|
// limit the rate
|
||||||
|
@ -20,7 +20,7 @@ static void arm_motors()
|
|||||||
// full right
|
// full right
|
||||||
if (g.rc_4.control_in > 4000) {
|
if (g.rc_4.control_in > 4000) {
|
||||||
if (arming_counter == LEVEL_DELAY){
|
if (arming_counter == LEVEL_DELAY){
|
||||||
Serial.printf("\nAL\n");
|
//Serial.printf("\nAL\n");
|
||||||
// begin auto leveling
|
// begin auto leveling
|
||||||
auto_level_counter = 200;
|
auto_level_counter = 200;
|
||||||
arming_counter = 0;
|
arming_counter = 0;
|
||||||
@ -39,7 +39,7 @@ static void arm_motors()
|
|||||||
// full left
|
// full left
|
||||||
}else if (g.rc_4.control_in < -4000) {
|
}else if (g.rc_4.control_in < -4000) {
|
||||||
if (arming_counter == LEVEL_DELAY){
|
if (arming_counter == LEVEL_DELAY){
|
||||||
Serial.printf("\nLEV\n");
|
//Serial.printf("\nLEV\n");
|
||||||
|
|
||||||
// begin manual leveling
|
// begin manual leveling
|
||||||
imu.init_accel(mavlink_delay);
|
imu.init_accel(mavlink_delay);
|
||||||
@ -65,7 +65,7 @@ static void arm_motors()
|
|||||||
|
|
||||||
static void init_arm_motors()
|
static void init_arm_motors()
|
||||||
{
|
{
|
||||||
Serial.printf("\nARM\n");
|
//Serial.printf("\nARM\n");
|
||||||
#if HIL_MODE != HIL_MODE_DISABLED
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
|
||||||
#endif
|
#endif
|
||||||
@ -106,7 +106,7 @@ static void init_arm_motors()
|
|||||||
|
|
||||||
static void init_disarm_motors()
|
static void init_disarm_motors()
|
||||||
{
|
{
|
||||||
Serial.printf("\nDISARM\n");
|
//Serial.printf("\nDISARM\n");
|
||||||
#if HIL_MODE != HIL_MODE_DISABLED
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
||||||
#endif
|
#endif
|
||||||
|
@ -8,9 +8,10 @@
|
|||||||
#include "APM_PI.h"
|
#include "APM_PI.h"
|
||||||
|
|
||||||
long
|
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) {
|
if (_integrator < -_imax) {
|
||||||
_integrator = -_imax;
|
_integrator = -_imax;
|
||||||
|
@ -77,7 +77,8 @@ public:
|
|||||||
///
|
///
|
||||||
/// @returns The updated control output.
|
/// @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
|
/// Reset the PI integrator
|
||||||
///
|
///
|
||||||
|
Loading…
Reference in New Issue
Block a user