aboutsummaryrefslogtreecommitdiff
path: root/apps/systemlib
diff options
context:
space:
mode:
Diffstat (limited to 'apps/systemlib')
-rw-r--r--apps/systemlib/geo/geo.c9
-rw-r--r--apps/systemlib/pid/pid.c2
2 files changed, 7 insertions, 4 deletions
diff --git a/apps/systemlib/geo/geo.c b/apps/systemlib/geo/geo.c
index 42d8d9c15..ce46d01cc 100644
--- a/apps/systemlib/geo/geo.c
+++ b/apps/systemlib/geo/geo.c
@@ -79,9 +79,12 @@ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, doub
/* conscious mix of double and float trig function to maximize speed and efficiency */
float theta = atan2f(sin(d_lon) * cos(lat_next_rad) , cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon));
- // XXX wrapping check is incomplete
- if (theta < 0.0f) {
- theta = theta + 2.0f * M_PI_F;
+ if (theta < M_PI_F) {
+ theta += 2.0f * M_PI_F;
+ }
+
+ if (theta > M_PI_F) {
+ theta -= 2.0f * M_PI_F;
}
return theta;
diff --git a/apps/systemlib/pid/pid.c b/apps/systemlib/pid/pid.c
index 61dd5757f..cff5e6bbe 100644
--- a/apps/systemlib/pid/pid.c
+++ b/apps/systemlib/pid/pid.c
@@ -179,7 +179,7 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
pid->error_previous = error;
}
- float output = (error * pid->kp) + (i * pid->ki) + (d * pid->kd);
+ float output = (pid->error_previous * pid->kp) + (i * pid->ki) + (d * pid->kd);
if (isfinite(output)) {
pid->last_output = output;