aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/rc_calibration.cpp
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-02-12 17:10:20 +0100
committerJulian Oes <julian@oes.ch>2014-02-12 17:10:20 +0100
commit3462054f73dda9303fcb1b2b5ba0a6f0882ddbd9 (patch)
tree511c63dcc6aae5222c6685e3f1648b2d8f5b2c6b /src/modules/commander/rc_calibration.cpp
parent76ae004e5c6c1dcc05f1eb784f6dc14cff2a3671 (diff)
parent03cfb79b29a81443665208396ba8fc0ab67a021a (diff)
downloadpx4-firmware-3462054f73dda9303fcb1b2b5ba0a6f0882ddbd9.tar.gz
px4-firmware-3462054f73dda9303fcb1b2b5ba0a6f0882ddbd9.tar.bz2
px4-firmware-3462054f73dda9303fcb1b2b5ba0a6f0882ddbd9.zip
Merge remote-tracking branch 'px4/beta' into beta_mavlink
Conflicts: src/modules/mavlink/mavlink.c src/modules/mavlink/mavlink_receiver.h src/modules/mavlink/orb_listener.c
Diffstat (limited to 'src/modules/commander/rc_calibration.cpp')
-rw-r--r--src/modules/commander/rc_calibration.cpp11
1 files changed, 5 insertions, 6 deletions
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
index 90ede499a..41f3ca0aa 100644
--- a/src/modules/commander/rc_calibration.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -53,17 +53,16 @@
#endif
static const int ERROR = -1;
-int do_rc_calibration(int mavlink_fd)
+int do_trim_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "trim calibration starting");
-
int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
+ usleep(200000);
struct manual_control_setpoint_s sp;
bool changed;
orb_check(sub_man, &changed);
if (!changed) {
- mavlink_log_critical(mavlink_fd, "no manual control, aborting");
+ mavlink_log_critical(mavlink_fd, "no inputs, aborting");
return ERROR;
}
@@ -82,12 +81,12 @@ int do_rc_calibration(int mavlink_fd)
int save_ret = param_save_default();
if (save_ret != 0) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
+ mavlink_log_critical(mavlink_fd, "TRIM: SAVE FAIL");
close(sub_man);
return ERROR;
}
- mavlink_log_info(mavlink_fd, "trim calibration done");
+ mavlink_log_info(mavlink_fd, "trim cal done");
close(sub_man);
return OK;
}