aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-08-21 08:33:35 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-08-21 08:33:35 +0200
commit89f36087dac5100d1eb64ef1bf246ae2541bd9f7 (patch)
tree65b93ee0b3c46bb40af5bfb0b35927c0efac704b
parent14e60e9b4d04b4ac91a39a2158387c3c57474c83 (diff)
downloadpx4-firmware-89f36087dac5100d1eb64ef1bf246ae2541bd9f7.tar.gz
px4-firmware-89f36087dac5100d1eb64ef1bf246ae2541bd9f7.tar.bz2
px4-firmware-89f36087dac5100d1eb64ef1bf246ae2541bd9f7.zip
Fixed and improved error messages for MAVLink param read / write
-rw-r--r--apps/mavlink/mavlink_parameters.c50
1 files changed, 31 insertions, 19 deletions
diff --git a/apps/mavlink/mavlink_parameters.c b/apps/mavlink/mavlink_parameters.c
index bc13f0540..99df42738 100644
--- a/apps/mavlink/mavlink_parameters.c
+++ b/apps/mavlink/mavlink_parameters.c
@@ -147,7 +147,9 @@ int mavlink_pm_send_param(param_t param)
}
static const char *mavlink_parameter_file = "/eeprom/parameters";
-
+/**
+ * @return 0 on success, -1 if device open failed, -2 if writing parameters failed
+ */
static int
mavlink_pm_save_eeprom()
{
@@ -156,7 +158,7 @@ mavlink_pm_save_eeprom()
int fd = open(mavlink_parameter_file, O_WRONLY | O_CREAT | O_EXCL);
if (fd < 0) {
- warn(1, "opening '%s' failed", mavlink_parameter_file);
+ warn("opening '%s' failed", mavlink_parameter_file);
return -1;
}
@@ -165,20 +167,23 @@ mavlink_pm_save_eeprom()
if (result < 0) {
unlink(mavlink_parameter_file);
- warn(1, "error exporting to '%s'", mavlink_parameter_file);
- return -1;
+ warn("error exporting to '%s'", mavlink_parameter_file);
+ return -2;
}
return 0;
}
+/**
+ * @return 0 on success, -1 if device open failed, -2 if writing parameters failed
+ */
static int
mavlink_pm_load_eeprom()
{
int fd = open(mavlink_parameter_file, O_RDONLY);
if (fd < 0) {
- warn(1, "open '%s' failed", mavlink_parameter_file);
+ warn("open '%s' failed", mavlink_parameter_file);
return -1;
}
@@ -186,8 +191,8 @@ mavlink_pm_load_eeprom()
close(fd);
if (result < 0) {
- warn(1, "error importing from '%s'", mavlink_parameter_file);
- return -1;
+ warn("error importing from '%s'", mavlink_parameter_file);
+ return -2;
}
return 0;
@@ -269,35 +274,42 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess
if (((int)(cmd_mavlink.param1)) == 0) {
- if (OK == mavlink_pm_load_eeprom()) {
+ /* read all parameters from EEPROM to RAM */
+ int read_ret = mavlink_pm_load_eeprom();
+ if (read_ret == OK) {
//printf("[mavlink pm] Loaded EEPROM params in RAM\n");
- mavlink_missionlib_send_gcs_string("[mavlink pm] CMD Loaded EEPROM params in RAM");
+ mavlink_missionlib_send_gcs_string("[mavlink pm] OK loaded EEPROM params");
result = MAV_RESULT_ACCEPTED;
} else {
- //fprintf(stderr, "[mavlink pm] ERROR loading EEPROM params in RAM\n");
- mavlink_missionlib_send_gcs_string("[mavlink pm] ERROR loading EEPROM params in RAM");
+ if (read_ret < -1) {
+ mavlink_missionlib_send_gcs_string("[mavlink pm] ERR loading params from EEPROM");
+ } else {
+ mavlink_missionlib_send_gcs_string("[mavlink pm] ERR loading params, no EEPROM found");
+ }
result = MAV_RESULT_FAILED;
}
- /* Write all parameters from RAM to EEPROM */
-
} else if (((int)(cmd_mavlink.param1)) == 1) {
- if (OK == mavlink_pm_save_eeprom()) {
- //printf("[mavlink pm] RAM params written to EEPROM\n");
- mavlink_missionlib_send_gcs_string("[mavlink pm] RAM params written to EEPROM");
+ /* write all parameters from RAM to EEPROM */
+ int write_ret = mavlink_pm_save_eeprom();
+ if (write_ret == OK) {
+ mavlink_missionlib_send_gcs_string("[mavlink pm] OK params written to EEPROM");
result = MAV_RESULT_ACCEPTED;
} else {
- //fprintf(stderr, "[mavlink pm] ERROR writing RAM params to EEPROM\n");
- mavlink_missionlib_send_gcs_string("[mavlink pm] ERROR writing RAM params to EEPROM");
+ if (write_ret < -1) {
+ mavlink_missionlib_send_gcs_string("[mavlink pm] ERR writing params to EEPROM");
+ } else {
+ mavlink_missionlib_send_gcs_string("[mavlink pm] ERR writing params, no EEPROM found");
+ }
result = MAV_RESULT_FAILED;
}
} else {
//fprintf(stderr, "[mavlink pm] refusing unsupported storage request\n");
- mavlink_missionlib_send_gcs_string("[mavlink pm] refusing unsupported storage request");
+ mavlink_missionlib_send_gcs_string("[mavlink pm] refusing unsupported STOR request");
result = MAV_RESULT_UNSUPPORTED;
}
}