|
|
|
@ -258,6 +258,8 @@ static void reset_optflow_I(void)
@@ -258,6 +258,8 @@ static void reset_optflow_I(void)
|
|
|
|
|
{ |
|
|
|
|
g.pi_optflow_roll.reset_I(); |
|
|
|
|
g.pi_optflow_pitch.reset_I(); |
|
|
|
|
of_roll = 0; |
|
|
|
|
of_pitch = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void reset_wind_I(void) |
|
|
|
@ -462,34 +464,35 @@ static void init_z_damper()
@@ -462,34 +464,35 @@ static void init_z_damper()
|
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// calculate modified roll/pitch depending upon optical flow values |
|
|
|
|
// calculate modified roll/pitch depending upon optical flow calculated position |
|
|
|
|
static int32_t |
|
|
|
|
get_of_roll(int32_t control_roll) |
|
|
|
|
{ |
|
|
|
|
#ifdef OPTFLOW_ENABLED |
|
|
|
|
//static int32_t of_roll = 0; // we use global variable to make logging easier |
|
|
|
|
static float tot_x_cm = 0; // total distance from target |
|
|
|
|
static unsigned long last_of_roll_update = 0; |
|
|
|
|
static float prev_value = 0; |
|
|
|
|
float x_cm; |
|
|
|
|
int32_t new_roll = 0; |
|
|
|
|
|
|
|
|
|
// check if new optflow data available |
|
|
|
|
if( optflow.last_update != last_of_roll_update) { |
|
|
|
|
last_of_roll_update = optflow.last_update; |
|
|
|
|
|
|
|
|
|
// filter movement |
|
|
|
|
x_cm = (optflow.x_cm + prev_value) / 2.0 * 50.0; |
|
|
|
|
// add new distance moved |
|
|
|
|
tot_x_cm += optflow.x_cm; |
|
|
|
|
|
|
|
|
|
// only stop roll if caller isn't modifying roll |
|
|
|
|
if( control_roll == 0 && current_loc.alt < 1500) { |
|
|
|
|
of_roll = g.pi_optflow_roll.get_pi(-x_cm, 1.0); // we could use the last update time to calculate the time change |
|
|
|
|
new_roll = g.pi_optflow_roll.get_pid(-tot_x_cm, 1.0, 1.0); // we could use the last update time to calculate the time change |
|
|
|
|
}else{ |
|
|
|
|
g.pi_optflow_roll.reset_I(); |
|
|
|
|
prev_value = 0; |
|
|
|
|
tot_x_cm = 0; |
|
|
|
|
} |
|
|
|
|
// limit amount of change and maximum angle |
|
|
|
|
of_roll = constrain(new_roll, (of_roll-20), (of_roll+20)); |
|
|
|
|
} |
|
|
|
|
// limit maximum angle |
|
|
|
|
of_roll = constrain(of_roll, -1000, 1000); |
|
|
|
|
|
|
|
|
|
// limit max angle |
|
|
|
|
of_roll = constrain(of_roll, -1000, 1000); |
|
|
|
|
return control_roll+of_roll; |
|
|
|
|
#else |
|
|
|
|
return control_roll; |
|
|
|
@ -500,27 +503,30 @@ static int32_t
@@ -500,27 +503,30 @@ static int32_t
|
|
|
|
|
get_of_pitch(int32_t control_pitch) |
|
|
|
|
{ |
|
|
|
|
#ifdef OPTFLOW_ENABLED |
|
|
|
|
//static int32_t of_pitch = 0; // we use global variable to make logging easier |
|
|
|
|
static float tot_y_cm = 0; // total distance from target |
|
|
|
|
static unsigned long last_of_pitch_update = 0; |
|
|
|
|
static float prev_value = 0; |
|
|
|
|
float y_cm; |
|
|
|
|
int32_t new_pitch = 0; |
|
|
|
|
|
|
|
|
|
// check if new optflow data available |
|
|
|
|
if( optflow.last_update != last_of_pitch_update ) { |
|
|
|
|
last_of_pitch_update = optflow.last_update; |
|
|
|
|
|
|
|
|
|
// filter movement |
|
|
|
|
y_cm = (optflow.y_cm + prev_value) / 2.0 * 50.0; |
|
|
|
|
// add new distance moved |
|
|
|
|
tot_y_cm += optflow.y_cm; |
|
|
|
|
|
|
|
|
|
// only stop roll if caller isn't modifying roll |
|
|
|
|
// only stop roll if caller isn't modifying pitch |
|
|
|
|
if( control_pitch == 0 && current_loc.alt < 1500 ) { |
|
|
|
|
of_pitch = g.pi_optflow_pitch.get_pi(y_cm, 1.0); // we could use the last update time to calculate the time change |
|
|
|
|
new_pitch = g.pi_optflow_pitch.get_pid(tot_y_cm, 1.0, 1.0); // we could use the last update time to calculate the time change |
|
|
|
|
}else{ |
|
|
|
|
tot_y_cm = 0; |
|
|
|
|
g.pi_optflow_pitch.reset_I(); |
|
|
|
|
prev_value = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// limit amount of change |
|
|
|
|
of_pitch = constrain(new_pitch, (of_pitch-20), (of_pitch+20)); |
|
|
|
|
} |
|
|
|
|
// limit maximum angle |
|
|
|
|
|
|
|
|
|
// limit max angle |
|
|
|
|
of_pitch = constrain(of_pitch, -1000, 1000); |
|
|
|
|
return control_pitch+of_pitch; |
|
|
|
|
#else |
|
|
|
|