aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-05 13:15:35 -0800
committerLorenz Meier <lm@inf.ethz.ch>2012-11-05 13:15:35 -0800
commit7d76a8a57b41c82db0712dd0544e67d1ce97d89c (patch)
treed4dd439ef04d0ea9b8b89355b39acdb13c7fdbaa
parent976545861a1c7336203a1677120633f14d215a40 (diff)
parent59725ccd3a80fd32ed8ef08025daeb4372adb1f1 (diff)
downloadpx4-firmware-7d76a8a57b41c82db0712dd0544e67d1ce97d89c.tar.gz
px4-firmware-7d76a8a57b41c82db0712dd0544e67d1ce97d89c.tar.bz2
px4-firmware-7d76a8a57b41c82db0712dd0544e67d1ce97d89c.zip
Merge pull request #45 from thomasgubler/master_origin
re-adding pid limitation & mavlink waypoint handling fix
-rw-r--r--apps/mavlink/waypoints.c7
-rw-r--r--apps/systemlib/pid/pid.c4
2 files changed, 5 insertions, 6 deletions
diff --git a/apps/mavlink/waypoints.c b/apps/mavlink/waypoints.c
index 3d9e5750a..16759237e 100644
--- a/apps/mavlink/waypoints.c
+++ b/apps/mavlink/waypoints.c
@@ -360,7 +360,7 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
float dist = -1.0f;
if (coordinate_frame == (int)MAV_FRAME_GLOBAL) {
- dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, global_pos->lat, global_pos->lon, global_pos->alt);
+ dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, (float)global_pos->lat * 1e-7f, (float)global_pos->lon * 1e-7f, global_pos->alt);
} else if (coordinate_frame == (int)MAV_FRAME_GLOBAL_RELATIVE_ALT) {
dist = mavlink_wpm_distance_to_point_global_wgs84(wpm->current_active_wp_id, global_pos->lat, global_pos->lon, global_pos->relative_alt);
@@ -376,14 +376,13 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
if (dist >= 0.f && dist <= orbit /*&& wpm->yaw_reached*/) { //TODO implement yaw
wpm->pos_reached = true;
- if (counter % 10 == 0)
+ if (counter % 100 == 0)
printf("Setpoint reached: %0.4f, orbit: %.4f\n", dist, orbit);
}
-
// else
// {
// if(counter % 100 == 0)
-// printf("Setpoint not reached yet: %0.4f, orbit: %.4f\n",dist,orbit);
+// printf("Setpoint not reached yet: %0.4f, orbit: %.4f, coordinate frame: %d\n",dist, orbit, coordinate_frame);
// }
}
diff --git a/apps/systemlib/pid/pid.c b/apps/systemlib/pid/pid.c
index dd8b6adc6..0358caa25 100644
--- a/apps/systemlib/pid/pid.c
+++ b/apps/systemlib/pid/pid.c
@@ -172,9 +172,9 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
// Calculate the output. Limit output magnitude to pid->limit
float output = (pid->error_previous * pid->kp) + (i * pid->ki) + (d * pid->kd);
- //if (output > pid->limit) output = pid->limit;
+ if (output > pid->limit) output = pid->limit;
- //if (output < -pid->limit) output = -pid->limit;
+ if (output < -pid->limit) output = -pid->limit;
if (isfinite(output)) {
pid->last_output = output;