APM:Libraries
sitl_rangefinder.cpp
Go to the documentation of this file.
1 /*
2  SITL handling
3 
4  This simulates a rangefinder
5 
6  */
7 
8 #include <AP_HAL/AP_HAL.h>
9 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
10 
11 #include "AP_HAL_SITL.h"
12 #include "AP_HAL_SITL_Namespace.h"
13 #include "HAL_SITL_Class.h"
14 #include "SITL_State.h"
15 #include <SITL/SITL.h>
16 #include <AP_Math/AP_Math.h>
17 
18 extern const AP_HAL::HAL& hal;
19 
20 using namespace HALSITL;
21 
22 /*
23  setup the rangefinder with new input
24  */
25 void SITL_State::_update_rangefinder(float range_value)
26 {
27  float altitude = range_value;
28  if (is_equal(range_value, -1.0f)) { // Use SITL altitude as reading by default
29  altitude = _sitl->height_agl;
30  }
31 
32  // sensor position offset in body frame
33  const Vector3f relPosSensorBF = _sitl->rngfnd_pos_offset;
34 
35  // adjust altitude for position of the sensor on the vehicle if position offset is non-zero
36  if (!relPosSensorBF.is_zero()) {
37  // get a rotation matrix following DCM conventions (body to earth)
38  Matrix3f rotmat;
40  // rotate the offset into earth frame
41  const Vector3f relPosSensorEF = rotmat * relPosSensorBF;
42  // correct the altitude at the sensor
43  altitude -= relPosSensorEF.z;
44  }
45 
46  float voltage = 5.0f; // Start the reading at max value = 5V
47  // If the attidude is non reversed for SITL OR we are using rangefinder from external simulator,
48  // We adjust the reading with noise, glitch and scaler as the reading is on analog port.
49  if ((fabs(_sitl->state.rollDeg) < 90.0 && fabs(_sitl->state.pitchDeg) < 90.0) || !is_equal(range_value, -1.0f)) {
50  if (is_equal(range_value, -1.0f)) { // disable for external reading that already handle this
51  // adjust for apparent altitude with roll
52  altitude /= cosf(radians(_sitl->state.rollDeg)) * cosf(radians(_sitl->state.pitchDeg));
53  }
54  // Add some noise on reading
55  altitude += _sitl->sonar_noise * rand_float();
56 
57  // Altitude in in m, scaler in meters/volt
58  voltage = altitude / _sitl->sonar_scale;
59  // constrain to 0-5V
60  voltage = constrain_float(voltage, 0.0f, 5.0f);
61 
62  // Use glitch defines as the probablility between 0-1 that any given sonar sample will read as max distance
63  if (!is_zero(_sitl->sonar_glitch) && _sitl->sonar_glitch >= (rand_float() + 1.0f) / 2.0f) {
64  voltage = 5.0f;
65  }
66  }
67 
68  sonar_pin_value = 1023 * (voltage / 5.0f);
69 }
70 
71 #endif
double pitchDeg
Definition: SITL.h:20
float height_agl
Definition: SITL.h:80
AP_Float sonar_scale
Definition: SITL.h:115
Quaternion quaternion
Definition: SITL.h:21
AP_Float sonar_noise
Definition: SITL.h:114
double rollDeg
Definition: SITL.h:20
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T z
Definition: vector3.h:67
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
uint16_t sonar_pin_value
Definition: SITL_State.h:65
void _update_rangefinder(float range_value)
AP_Float sonar_glitch
Definition: SITL.h:113
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static constexpr float radians(float deg)
Definition: AP_Math.h:158
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
SITL::SITL * _sitl
Definition: SITL_State.h:165
float rand_float(void)
Definition: AP_Math.cpp:224
float voltage
bool is_zero(void) const
Definition: vector3.h:159
AP_Vector3f rngfnd_pos_offset
Definition: SITL.h:180
struct sitl_fdm state
Definition: SITL.h:71