mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
sensors params split by sensor index
This commit is contained in:
parent
273742aa0d
commit
1ccbaf4cd2
89
src/modules/sensors/sensor_params_acc0.c
Normal file
89
src/modules/sensors/sensor_params_acc0.c
Normal file
@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 0 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_EN, 1);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0f);
|
||||
89
src/modules/sensors/sensor_params_acc1.c
Normal file
89
src/modules/sensors/sensor_params_acc1.c
Normal file
@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 1 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_EN, 1);
|
||||
|
||||
/**
|
||||
* 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);
|
||||
89
src/modules/sensors/sensor_params_acc2.c
Normal file
89
src/modules/sensors/sensor_params_acc2.c
Normal file
@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 2 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_EN, 1);
|
||||
|
||||
/**
|
||||
* 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);
|
||||
@ -37,174 +37,3 @@
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC_PRIME, 0);
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 0 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_EN, 1);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Accelerometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_ACC0_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 1 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_EN, 1);
|
||||
|
||||
/**
|
||||
* 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 Accelerometer that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 2 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_EN, 1);
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
@ -37,174 +37,3 @@
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO_PRIME, 0);
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 0 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_EN, 1);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 1 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_EN, 1);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 2 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_EN, 1);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZSCALE, 1.0f);
|
||||
|
||||
89
src/modules/sensors/sensor_params_gyro0.c
Normal file
89
src/modules/sensors/sensor_params_gyro0.c
Normal file
@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 0 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_EN, 1);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO0_ZSCALE, 1.0f);
|
||||
89
src/modules/sensors/sensor_params_gyro1.c
Normal file
89
src/modules/sensors/sensor_params_gyro1.c
Normal file
@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 1 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_EN, 1);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO1_ZSCALE, 1.0f);
|
||||
89
src/modules/sensors/sensor_params_gyro2.c
Normal file
89
src/modules/sensors/sensor_params_gyro2.c
Normal file
@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of the Gyro that the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 2 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_EN, 1);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Gyro X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Gyro Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_GYRO2_ZSCALE, 1.0f);
|
||||
@ -56,408 +56,3 @@ PARAM_DEFINE_INT32(CAL_MAG_PRIME, 0);
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG_SIDES, 63);
|
||||
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 0 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 0 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 1 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 1 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @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 Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 2 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 2 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @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 Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG3_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 3 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG3_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 2 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG3_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @min -500.0
|
||||
* @max 500.0
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_ZSCALE, 1.0f);
|
||||
|
||||
131
src/modules/sensors/sensor_params_mag0.c
Normal file
131
src/modules/sensors/sensor_params_mag0.c
Normal file
@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 0 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 0 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG0_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG0_ZSCALE, 1.0f);
|
||||
131
src/modules/sensors/sensor_params_mag1.c
Normal file
131
src/modules/sensors/sensor_params_mag1.c
Normal file
@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 1 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 1 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG1_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG1_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @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);
|
||||
131
src/modules/sensors/sensor_params_mag2.c
Normal file
131
src/modules/sensors/sensor_params_mag2.c
Normal file
@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 2 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 2 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG2_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG2_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @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);
|
||||
131
src/modules/sensors/sensor_params_mag3.c
Normal file
131
src/modules/sensors/sensor_params_mag3.c
Normal file
@ -0,0 +1,131 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ID of Magnetometer the calibration is for.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG3_ID, 0);
|
||||
|
||||
/**
|
||||
* Mag 3 enabled
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG3_EN, 1);
|
||||
|
||||
/**
|
||||
* Rotation of magnetometer 2 relative to airframe.
|
||||
*
|
||||
* An internal magnetometer will force a value of -1, so a GCS
|
||||
* should only attempt to configure the rotation if the value is
|
||||
* greater than or equal to zero.
|
||||
*
|
||||
* @value -1 Internal mag
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
*
|
||||
* @min -1
|
||||
* @max 30
|
||||
* @reboot_required true
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG3_ROT, -1);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_XOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_YOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis offset
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_ZOFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer X-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_XSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Y-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_YSCALE, 1.0f);
|
||||
|
||||
/**
|
||||
* Magnetometer Z-axis scaling factor
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_MAG3_ZSCALE, 1.0f);
|
||||
Loading…
x
Reference in New Issue
Block a user