AP_RangeFinder_LightWareI2C.h 1.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. #pragma once
  2. #include "RangeFinder.h"
  3. #include "RangeFinder_Backend.h"
  4. #include <AP_HAL/I2CDevice.h>
  5. #define NUM_SF20_DATA_STREAMS 1
  6. class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend
  7. {
  8. public:
  9. // static detection function
  10. static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
  11. AP_RangeFinder_Params &_params,
  12. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  13. // update state
  14. void update(void) override;
  15. protected:
  16. virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override
  17. {
  18. return MAV_DISTANCE_SENSOR_LASER;
  19. }
  20. private:
  21. uint16_t sf20_stream_val[NUM_SF20_DATA_STREAMS];
  22. int currentStreamSequenceIndex = 0;
  23. // constructor
  24. AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state,
  25. AP_RangeFinder_Params &_params,
  26. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
  27. bool write_bytes(uint8_t *write_buf_u8, uint32_t len_u8);
  28. void sf20_disable_address_tagging();
  29. bool sf20_send_and_expect(const char* send, const char* expected_reply);
  30. bool sf20_set_lost_signal_confirmations();
  31. void sf20_get_version(const char* send_msg, const char *reply_prefix, char reply[5]);
  32. bool sf20_wait_on_reply(uint8_t *rx_two_bytes);
  33. bool init();
  34. bool legacy_init();
  35. bool sf20_init();
  36. void sf20_init_streamRecovery();
  37. void legacy_timer();
  38. void sf20_timer();
  39. // get a reading
  40. bool legacy_get_reading(uint16_t &reading_cm);
  41. bool sf20_get_reading(uint16_t &reading_cm);
  42. bool sf20_parse_stream(uint8_t *stream_buf,
  43. size_t *p_num_processed_chars,
  44. const char *string_identifier,
  45. uint16_t &val);
  46. void data_log(uint16_t *val);
  47. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  48. };