APM:Libraries
AP_OpticalFlow_SITL.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_OpticalFlow_SITL.cpp - SITL emulation of optical flow sensor.
18  */
19 
20 #include <AP_HAL/AP_HAL.h>
21 
22 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
23 
24 #include "AP_OpticalFlow_SITL.h"
25 
26 extern const AP_HAL::HAL& hal;
27 
29  OpticalFlow_backend(_frontend)
30 {
32 }
33 
35 {
36 }
37 
39 {
40  if (!_sitl->flow_enable) {
41  return;
42  }
43 
44  // update at the requested rate
45  uint32_t now = AP_HAL::millis();
46  if (now - last_flow_ms < 1000*(1.0f/_sitl->flow_rate)) {
47  return;
48  }
49  last_flow_ms = now;
50 
54 
56 
57  // NED velocity vector in m/s
58  Vector3f velocity(_sitl->state.speedN,
60  _sitl->state.speedD);
61 
62  // a rotation matrix following DCM conventions
63  Matrix3f rotmat;
67 
68 
69  state.device_id = 1;
70  state.surface_quality = 51;
71 
72  // sensor position offset in body frame
73  Vector3f posRelSensorBF = _sitl->optflow_pos_offset;
74 
75  // estimate range to centre of image
76  float range;
77  if (rotmat.c.z > 0.05f && _sitl->height_agl > 0) {
78  Vector3f relPosSensorEF = rotmat * posRelSensorBF;
79  range = (_sitl->height_agl - relPosSensorEF.z) / rotmat.c.z;
80  } else {
81  range = 1e38f;
82  }
83 
84  // Calculate relative velocity in sensor frame assuming no misalignment between sensor and vehicle body axes
85  Vector3f relVelSensor = rotmat.mul_transpose(velocity);
86 
87  // correct relative velocity for rotation rates and sensor offset
88  relVelSensor += gyro % posRelSensorBF;
89 
90  // Divide velocity by range and add body rates to get predicted sensed angular
91  // optical rates relative to X and Y sensor axes assuming no misalignment or scale
92  // factor error. Note - these are instantaneous values. The sensor sums these values across the interval from the last
93  // poll to provide a delta angle across the interface
94  state.flowRate.x = -relVelSensor.y/range + gyro.x;
95  state.flowRate.y = relVelSensor.x/range + gyro.y;
96 
97  // The flow sensors body rates are assumed to be the same as the vehicle body rates (ie no misalignment)
98  // Note - these are instantaneous values. The sensor sums these values across the interval from the last
99  // poll to provide a delta angle across the interface.
100  state.bodyRate = Vector2f(gyro.x, gyro.y);
101 
104  next_optflow_index = 0;
105  }
106 
108 
109  if (_sitl->flow_delay != optflow_delay) {
110  // cope with updates to the delay control
111  if (_sitl->flow_delay > 0 &&
112  (uint8_t)(_sitl->flow_delay) > ARRAY_SIZE(optflow_data)) {
114  }
116  for (uint8_t i=0; i<optflow_delay; i++) {
117  optflow_data[i] = state;
118  }
119  }
120 
121  _applyYaw(state.flowRate);
122 
123  // copy results to front end
124  _update_frontend(state);
125 }
126 
127 #endif // CONFIG_HAL_BOARD
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
Vector2< float > Vector2f
Definition: vector2.h:239
void _applyYaw(Vector2f &v)
double pitchDeg
Definition: SITL.h:20
float height_agl
Definition: SITL.h:80
double speedE
Definition: SITL.h:17
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
double rollRate
Definition: SITL.h:19
double speedD
Definition: SITL.h:17
T y
Definition: vector2.h:37
double yawRate
Definition: SITL.h:19
AP_Int16 flow_rate
Definition: SITL.h:137
double rollDeg
Definition: SITL.h:20
void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
#define f(i)
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
double yawDeg
Definition: SITL.h:20
uint32_t millis()
Definition: system.cpp:157
double speedN
Definition: SITL.h:17
T z
Definition: vector3.h:67
static int state
Definition: Util.cpp:20
OpticalFlow::OpticalFlow_state optflow_data[20]
AP_Int8 flow_delay
Definition: SITL.h:138
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
AP_Vector3f optflow_pos_offset
Definition: SITL.h:181
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
double pitchRate
Definition: SITL.h:19
T x
Definition: vector2.h:37
static constexpr float radians(float deg)
Definition: AP_Math.h:158
AP_Int8 flow_enable
Definition: SITL.h:136
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_OpticalFlow_SITL(OpticalFlow &_frontend)
constructor
struct sitl_fdm state
Definition: SITL.h:71
T x
Definition: vector3.h:67