mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-01 06:14:07 +08:00
sensors app: Use indexed param names
This commit is contained in:
parent
19cd496157
commit
23e7823b51
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -36,20 +36,27 @@
|
||||
*
|
||||
* Parameters defined by the sensors task.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
* @author Julian Oes <julian@px4.io>
|
||||
* @author Thomas Gubler <thomas@px4.io>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
* ID of the board this parameter set was calibrated on.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_BOARD_ID, 0);
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_GYRO_ID, 0);
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
@ -58,7 +65,7 @@ PARAM_DEFINE_INT32(SENS_GYRO_ID, 0);
|
||||
* @max 10.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
@ -67,7 +74,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
|
||||
* @max 10.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
@ -76,7 +83,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
|
||||
* @max 5.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
@ -85,7 +92,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
@ -94,7 +101,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
@ -103,14 +110,14 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_ID, 0);
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_ID, 0);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
@ -119,7 +126,7 @@ PARAM_DEFINE_INT32(SENS_MAG_ID, 0);
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
@ -128,7 +135,7 @@ PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
@ -137,78 +144,407 @@ PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_YSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_ZSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_ACC_ID, 0);
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_XOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_YOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_ZOFF, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @min -10.0
|
||||
* @max 10.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @min -10.0
|
||||
* @max 10.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @min -5.0
|
||||
* @max 5.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_ID, 0);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC1_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC1_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC1_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC1_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @min -10.0
|
||||
* @max 10.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @min -10.0
|
||||
* @max 10.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @min -5.0
|
||||
* @max 5.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @min -1.5
|
||||
* @max 1.5
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_ID, 0);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC2_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC2_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC2_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC2_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC2_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Differential pressure sensor offset
|
||||
|
||||
@ -619,29 +619,29 @@ Sensors::Sensors() :
|
||||
_parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH");
|
||||
|
||||
/* gyro offsets */
|
||||
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
|
||||
_parameter_handles.gyro_offset[1] = param_find("SENS_GYRO_YOFF");
|
||||
_parameter_handles.gyro_offset[2] = param_find("SENS_GYRO_ZOFF");
|
||||
_parameter_handles.gyro_scale[0] = param_find("SENS_GYRO_XSCALE");
|
||||
_parameter_handles.gyro_scale[1] = param_find("SENS_GYRO_YSCALE");
|
||||
_parameter_handles.gyro_scale[2] = param_find("SENS_GYRO_ZSCALE");
|
||||
_parameter_handles.gyro_offset[0] = param_find("CAL_GYRO0_XOFF");
|
||||
_parameter_handles.gyro_offset[1] = param_find("CAL_GYRO0_YOFF");
|
||||
_parameter_handles.gyro_offset[2] = param_find("CAL_GYRO0_ZOFF");
|
||||
_parameter_handles.gyro_scale[0] = param_find("CAL_GYRO0_XSCALE");
|
||||
_parameter_handles.gyro_scale[1] = param_find("CAL_GYRO0_YSCALE");
|
||||
_parameter_handles.gyro_scale[2] = param_find("CAL_GYRO0_ZSCALE");
|
||||
|
||||
/* accel offsets */
|
||||
_parameter_handles.accel_offset[0] = param_find("SENS_ACC_XOFF");
|
||||
_parameter_handles.accel_offset[1] = param_find("SENS_ACC_YOFF");
|
||||
_parameter_handles.accel_offset[2] = param_find("SENS_ACC_ZOFF");
|
||||
_parameter_handles.accel_scale[0] = param_find("SENS_ACC_XSCALE");
|
||||
_parameter_handles.accel_scale[1] = param_find("SENS_ACC_YSCALE");
|
||||
_parameter_handles.accel_scale[2] = param_find("SENS_ACC_ZSCALE");
|
||||
_parameter_handles.accel_offset[0] = param_find("CAL_ACC0_XOFF");
|
||||
_parameter_handles.accel_offset[1] = param_find("CAL_ACC0_YOFF");
|
||||
_parameter_handles.accel_offset[2] = param_find("CAL_ACC0_ZOFF");
|
||||
_parameter_handles.accel_scale[0] = param_find("CAL_ACC0_XSCALE");
|
||||
_parameter_handles.accel_scale[1] = param_find("CAL_ACC0_YSCALE");
|
||||
_parameter_handles.accel_scale[2] = param_find("CAL_ACC0_ZSCALE");
|
||||
|
||||
/* mag offsets */
|
||||
_parameter_handles.mag_offset[0] = param_find("SENS_MAG_XOFF");
|
||||
_parameter_handles.mag_offset[1] = param_find("SENS_MAG_YOFF");
|
||||
_parameter_handles.mag_offset[2] = param_find("SENS_MAG_ZOFF");
|
||||
_parameter_handles.mag_offset[0] = param_find("CAL_MAG0_XOFF");
|
||||
_parameter_handles.mag_offset[1] = param_find("CAL_MAG0_YOFF");
|
||||
_parameter_handles.mag_offset[2] = param_find("CAL_MAG0_ZOFF");
|
||||
|
||||
_parameter_handles.mag_scale[0] = param_find("SENS_MAG_XSCALE");
|
||||
_parameter_handles.mag_scale[1] = param_find("SENS_MAG_YSCALE");
|
||||
_parameter_handles.mag_scale[2] = param_find("SENS_MAG_ZSCALE");
|
||||
_parameter_handles.mag_scale[0] = param_find("CAL_MAG0_XSCALE");
|
||||
_parameter_handles.mag_scale[1] = param_find("CAL_MAG0_YSCALE");
|
||||
_parameter_handles.mag_scale[2] = param_find("CAL_MAG0_ZSCALE");
|
||||
|
||||
/* Differential pressure offset */
|
||||
_parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF");
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user