Browse Source

Fixed and improved error messages for MAVLink param read / write

sbg
Lorenz Meier 13 years ago
parent
commit
89f36087da
  1. 50
      apps/mavlink/mavlink_parameters.c

50
apps/mavlink/mavlink_parameters.c

@ -147,7 +147,9 @@ int mavlink_pm_send_param(param_t param) @@ -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() @@ -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() @@ -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() @@ -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 @@ -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;
}
}

Loading…
Cancel
Save