diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 75946fb240..e89dae9839 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -406,9 +406,17 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) mag_offset[1] = (max_avg[1] + min_avg[1]) / 2.0f; mag_offset[2] = (max_avg[2] + min_avg[2]) / 2.0f; - global_data_parameter_storage->pm.param_values[PARAM_SENSOR_MAG_XOFFSET] = mag_offset[0]; - global_data_parameter_storage->pm.param_values[PARAM_SENSOR_MAG_YOFFSET] = mag_offset[1]; - global_data_parameter_storage->pm.param_values[PARAM_SENSOR_MAG_ZOFFSET] = mag_offset[2]; + if (param_set(param_find("SENSOR_MAG_XOFF"), &(mag_offset[0]))) { + fprintf(stderr, "[commander] Setting X mag offset failed!\n"); + } + + if (param_set(param_find("SENSOR_MAG_YOFF"), &(mag_offset[1]))) { + fprintf(stderr, "[commander] Setting Y mag offset failed!\n"); + } + + if (param_set(param_find("SENSOR_MAG_ZOFF"), &(mag_offset[2]))) { + fprintf(stderr, "[commander] Setting Z mag offset failed!\n"); + } free(mag_maxima[0]); free(mag_maxima[1]); diff --git a/apps/mavlink/mavlink_parameters.c b/apps/mavlink/mavlink_parameters.c index 99df42738c..dbf5b75d88 100644 --- a/apps/mavlink/mavlink_parameters.c +++ b/apps/mavlink/mavlink_parameters.c @@ -132,7 +132,9 @@ int mavlink_pm_send_param(param_t param) * get param value, since MAVLink encodes float and int params in the same * space during transmission, copy param onto float val_buf */ - if (param_get(param, &val_buf) != OK) return; + + int ret; + if ((ret = param_get(param, &val_buf)) != OK) return ret; mavlink_msg_param_value_pack_chan(mavlink_system.sysid, mavlink_system.compid, @@ -143,7 +145,8 @@ int mavlink_pm_send_param(param_t param) mavlink_type, param_count(), param_get_index(param)); - return mavlink_missionlib_send_message(&tx_msg); + ret = mavlink_missionlib_send_message(&tx_msg); + return ret; } static const char *mavlink_parameter_file = "/eeprom/parameters";