APM:Libraries
AP_RangeFinder_Wasp.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "RangeFinder.h"
4 #include "RangeFinder_Backend.h"
5 
6 // WASP 200 LRF
7 // http://www.attolloengineering.com/wasp-200-lrf.html
8 
10 
11 public:
14  uint8_t serial_instance);
15 
16  static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
17 
18  void update(void) override;
19 
20  static const struct AP_Param::GroupInfo var_info[];
21 
22 protected:
23 
24  virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
25  return MAV_DISTANCE_SENSOR_LASER;
26  }
27 
28 private:
29 
31  WASP_CFG_RATE, // set the baudrate
32  WASP_CFG_ENCODING, // set the encoding to LBE
33  WASP_CFG_PROTOCOL, // set the protocol type used
34  WASP_CFG_FRQ, // set the update frequency
35  WASP_CFG_GO, // start/resume readings
36  WASP_CFG_AUT, // set the auto sensitivity threshold
37  WASP_CFG_THR, // set the sensitivity threshold
38  WASP_CFG_MAVG, // set the moving average filter
39  WASP_CFG_MEDF, // set the median filter windows size
40  WASP_CFG_AVG, // set the multi-pulse averages
41  WASP_CFG_AUV, // enforce auto voltage
42  WASP_CFG_DONE // done configuring
43  };
44 
46 
47  bool get_reading(uint16_t &reading_cm);
48 
49  void parse_response(void);
50 
52  uint32_t last_reading_ms;
53  char linebuf[10];
54  uint8_t linebuf_len;
55  AP_Int16 mavg;
56  AP_Int16 medf;
57  AP_Int16 frq;
58  AP_Int16 avg;
59  AP_Int16 thr;
60  AP_Int8 baud;
61 };
wasp_configuration_stage configuration_state
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
void update(void) override
bool get_reading(uint16_t &reading_cm)
AP_HAL::UARTDriver * uart
static const struct AP_Param::GroupInfo var_info[]
AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)