forked from Archive/PX4-Autopilot
moved commander to new param interface
This commit is contained in:
parent
112cd4a95b
commit
b07de1379d
|
@ -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[1] = (max_avg[1] + min_avg[1]) / 2.0f;
|
||||||
mag_offset[2] = (max_avg[2] + min_avg[2]) / 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];
|
if (param_set(param_find("SENSOR_MAG_XOFF"), &(mag_offset[0]))) {
|
||||||
global_data_parameter_storage->pm.param_values[PARAM_SENSOR_MAG_YOFFSET] = mag_offset[1];
|
fprintf(stderr, "[commander] Setting X mag offset failed!\n");
|
||||||
global_data_parameter_storage->pm.param_values[PARAM_SENSOR_MAG_ZOFFSET] = mag_offset[2];
|
}
|
||||||
|
|
||||||
|
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[0]);
|
||||||
free(mag_maxima[1]);
|
free(mag_maxima[1]);
|
||||||
|
|
|
@ -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
|
* get param value, since MAVLink encodes float and int params in the same
|
||||||
* space during transmission, copy param onto float val_buf
|
* 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_msg_param_value_pack_chan(mavlink_system.sysid,
|
||||||
mavlink_system.compid,
|
mavlink_system.compid,
|
||||||
|
@ -143,7 +145,8 @@ int mavlink_pm_send_param(param_t param)
|
||||||
mavlink_type,
|
mavlink_type,
|
||||||
param_count(),
|
param_count(),
|
||||||
param_get_index(param));
|
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";
|
static const char *mavlink_parameter_file = "/eeprom/parameters";
|
||||||
|
|
Loading…
Reference in New Issue