aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-08-23 20:45:28 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-08-23 20:45:28 +0200
commitb07de1379d1636847148e3052c055c9396ef8f4f (patch)
treefd30154431330e14695f9ee5f41fd4f29f7d73ef
parent112cd4a95b0b0c5920b68e8c8db1e83b72e14fa8 (diff)
downloadpx4-firmware-b07de1379d1636847148e3052c055c9396ef8f4f.tar.gz
px4-firmware-b07de1379d1636847148e3052c055c9396ef8f4f.tar.bz2
px4-firmware-b07de1379d1636847148e3052c055c9396ef8f4f.zip
moved commander to new param interface
-rw-r--r--apps/commander/commander.c14
-rw-r--r--apps/mavlink/mavlink_parameters.c7
2 files changed, 16 insertions, 5 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 75946fb24..e89dae983 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 99df42738..dbf5b75d8 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";