sitl_rangefinder.cpp 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  1. /*
  2. SITL handling
  3. This simulates a rangefinder
  4. */
  5. #include <AP_HAL/AP_HAL.h>
  6. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  7. #include "AP_HAL_SITL.h"
  8. #include "AP_HAL_SITL_Namespace.h"
  9. #include "HAL_SITL_Class.h"
  10. #include "SITL_State.h"
  11. #include <SITL/SITL.h>
  12. #include <AP_Math/AP_Math.h>
  13. extern const AP_HAL::HAL& hal;
  14. using namespace HALSITL;
  15. /*
  16. setup the rangefinder with new input
  17. */
  18. void SITL_State::_update_rangefinder(float range_value)
  19. {
  20. float altitude = range_value;
  21. if (is_equal(range_value, -1.0f)) { // Use SITL altitude as reading by default
  22. altitude = _sitl->height_agl;
  23. }
  24. // sensor position offset in body frame
  25. const Vector3f relPosSensorBF = _sitl->rngfnd_pos_offset;
  26. // adjust altitude for position of the sensor on the vehicle if position offset is non-zero
  27. if (!relPosSensorBF.is_zero()) {
  28. // get a rotation matrix following DCM conventions (body to earth)
  29. Matrix3f rotmat;
  30. _sitl->state.quaternion.rotation_matrix(rotmat);
  31. // rotate the offset into earth frame
  32. const Vector3f relPosSensorEF = rotmat * relPosSensorBF;
  33. // correct the altitude at the sensor
  34. altitude -= relPosSensorEF.z;
  35. }
  36. float voltage = 5.0f; // Start the reading at max value = 5V
  37. // If the attidude is non reversed for SITL OR we are using rangefinder from external simulator,
  38. // We adjust the reading with noise, glitch and scaler as the reading is on analog port.
  39. if ((fabs(_sitl->state.rollDeg) < 90.0 && fabs(_sitl->state.pitchDeg) < 90.0) || !is_equal(range_value, -1.0f)) {
  40. if (is_equal(range_value, -1.0f)) { // disable for external reading that already handle this
  41. // adjust for apparent altitude with roll
  42. altitude /= cosf(radians(_sitl->state.rollDeg)) * cosf(radians(_sitl->state.pitchDeg));
  43. }
  44. // Add some noise on reading
  45. altitude += _sitl->sonar_noise * rand_float();
  46. // Altitude in in m, scaler in meters/volt
  47. voltage = altitude / _sitl->sonar_scale;
  48. // constrain to 0-5V
  49. voltage = constrain_float(voltage, 0.0f, 5.0f);
  50. // Use glitch defines as the probablility between 0-1 that any given sonar sample will read as max distance
  51. if (!is_zero(_sitl->sonar_glitch) && _sitl->sonar_glitch >= (rand_float() + 1.0f) / 2.0f) {
  52. voltage = 5.0f;
  53. }
  54. }
  55. sonar_pin_value = 1023 * (voltage / 5.0f);
  56. }
  57. #endif