PX4 Firmware
PX4 Autopilot Software http://px4.io
sensor_params_flow.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * PX4Flow board rotation
36  *
37  * This parameter defines the yaw rotation of the PX4FLOW board relative to the vehicle body frame.
38  * Zero rotation is defined as X on flow board pointing towards front of vehicle.
39  * The recommneded installation default for the PX4FLOW board is with the Y axis forward (270 deg yaw).
40  *
41  * @value 0 No rotation
42  * @value 1 Yaw 45°
43  * @value 2 Yaw 90°
44  * @value 3 Yaw 135°
45  * @value 4 Yaw 180°
46  * @value 5 Yaw 225°
47  * @value 6 Yaw 270°
48  * @value 7 Yaw 315°
49  *
50  * @reboot_required true
51  *
52  * @group Sensors
53  */
54 PARAM_DEFINE_INT32(SENS_FLOW_ROT, 6);
55 
56 /**
57  * Minimum height above ground when reliant on optical flow.
58  *
59  * This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.
60  * The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.
61  *
62  * @unit m
63  * @min 0.0
64  * @max 1.0
65  * @increment 0.1
66  * @decimal 1
67  * @group Sensor Calibration
68  */
69 PARAM_DEFINE_FLOAT(SENS_FLOW_MINHGT, 0.7f);
70 
71 /**
72  * Maximum height above ground when reliant on optical flow.
73  *
74  * This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.
75  * The height setpoint will be limited to be no greater than this value when the navigation system
76  * is completely reliant on optical flow data and the height above ground estimate is valid.
77  * The sensor may be usable above this height, but accuracy will progressively degrade.
78  *
79  * @unit m
80  * @min 1.0
81  * @max 25.0
82  * @increment 0.1
83  * @decimal 1
84  * @group Sensor Calibration
85  */
86 PARAM_DEFINE_FLOAT(SENS_FLOW_MAXHGT, 3.0f);
87 
88 /**
89  * Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor.
90  * Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and
91  * control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground
92  * is less than 50% of this value.
93  *
94  * @unit rad/s
95  * @min 1.0
96  * @decimal 2
97  * @group Sensor Calibration
98  */
99 PARAM_DEFINE_FLOAT(SENS_FLOW_MAXR, 2.5f);
PARAM_DEFINE_INT32(SENS_FLOW_ROT, 6)
PX4Flow board rotation.
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
PARAM_DEFINE_FLOAT(SENS_FLOW_MINHGT, 0.7f)
Minimum height above ground when reliant on optical flow.