AP_RangeFinder_Wasp.h 1.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. // WASP 200 LRF
  5. // http://www.attolloengineering.com/wasp-200-lrf.html
  6. class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend {
  7. public:
  8. AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state,
  9. AP_RangeFinder_Params &_params,
  10. uint8_t serial_instance);
  11. static bool detect(uint8_t serial_instance);
  12. void update(void) override;
  13. static const struct AP_Param::GroupInfo var_info[];
  14. protected:
  15. virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
  16. return MAV_DISTANCE_SENSOR_LASER;
  17. }
  18. private:
  19. enum wasp_configuration_stage {
  20. WASP_CFG_RATE, // set the baudrate
  21. WASP_CFG_ENCODING, // set the encoding to LBE
  22. WASP_CFG_PROTOCOL, // set the protocol type used
  23. WASP_CFG_FRQ, // set the update frequency
  24. WASP_CFG_GO, // start/resume readings
  25. WASP_CFG_AUT, // set the auto sensitivity threshold
  26. WASP_CFG_THR, // set the sensitivity threshold
  27. WASP_CFG_MAVG, // set the moving average filter
  28. WASP_CFG_MEDF, // set the median filter windows size
  29. WASP_CFG_AVG, // set the multi-pulse averages
  30. WASP_CFG_AUV, // enforce auto voltage
  31. WASP_CFG_DONE // done configuring
  32. };
  33. wasp_configuration_stage configuration_state;
  34. bool get_reading(uint16_t &reading_cm);
  35. void parse_response(void);
  36. AP_HAL::UARTDriver *uart;
  37. char linebuf[10];
  38. uint8_t linebuf_len;
  39. AP_Int16 mavg;
  40. AP_Int16 medf;
  41. AP_Int16 frq;
  42. AP_Int16 avg;
  43. AP_Int16 thr;
  44. AP_Int8 baud;
  45. };