AP_Proximity_LightWareSF40C.h 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596
  1. #pragma once
  2. #include "AP_Proximity.h"
  3. #include "AP_Proximity_Backend.h"
  4. #define PROXIMITY_SF40C_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
  5. class AP_Proximity_LightWareSF40C : public AP_Proximity_Backend
  6. {
  7. public:
  8. // constructor
  9. AP_Proximity_LightWareSF40C(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager);
  10. // static detection function
  11. static bool detect(AP_SerialManager &serial_manager);
  12. // update state
  13. void update(void) override;
  14. // get maximum and minimum distances (in meters) of sensor
  15. float distance_max() const override;
  16. float distance_min() const override;
  17. private:
  18. enum RequestType {
  19. RequestType_None = 0,
  20. RequestType_Health,
  21. RequestType_MotorSpeed,
  22. RequestType_MotorDirection,
  23. RequestType_ForwardDirection,
  24. RequestType_DistanceMeasurement
  25. };
  26. // initialise sensor (returns true if sensor is successfully initialised)
  27. bool initialise();
  28. void init_sectors();
  29. void set_motor_speed(bool on_off);
  30. void set_motor_direction();
  31. void set_forward_direction();
  32. // send request for something from sensor
  33. void request_new_data();
  34. void send_request_for_health();
  35. bool send_request_for_distance();
  36. // check and process replies from sensor
  37. bool check_for_reply();
  38. bool process_reply();
  39. void clear_buffers();
  40. // reply related variables
  41. AP_HAL::UARTDriver *uart = nullptr;
  42. char element_buf[2][10];
  43. uint8_t element_len[2];
  44. uint8_t element_num;
  45. bool ignore_reply; // true if we should ignore the incoming message (because it is just echoing our command)
  46. bool wait_for_space; // space marks the start of returned data
  47. // request related variables
  48. enum RequestType _last_request_type; // last request made to sensor
  49. uint8_t _last_sector; // last sector requested
  50. uint32_t _last_request_ms; // system time of last request
  51. uint32_t _last_distance_received_ms; // system time of last distance measurement received from sensor
  52. uint8_t _request_count; // counter used to interleave requests for distance with health requests
  53. // sensor health register
  54. union {
  55. struct PACKED {
  56. uint16_t motor_stopped : 1;
  57. uint16_t motor_dir : 1; // 0 = clockwise, 1 = counter-clockwise
  58. uint16_t motor_fault : 1;
  59. uint16_t torque_control : 1; // 0 = automatic, 1 = manual
  60. uint16_t laser_fault : 1;
  61. uint16_t low_battery : 1;
  62. uint16_t flat_battery : 1;
  63. uint16_t system_restarting : 1;
  64. uint16_t no_results_available : 1;
  65. uint16_t power_saving : 1;
  66. uint16_t user_flag1 : 1;
  67. uint16_t user_flag2 : 1;
  68. uint16_t unused1 : 1;
  69. uint16_t unused2 : 1;
  70. uint16_t spare_input : 1;
  71. uint16_t major_system_abnormal : 1;
  72. } _flags;
  73. uint16_t value;
  74. } _sensor_status;
  75. // sensor config
  76. uint8_t _motor_speed; // motor speed as reported by lidar
  77. uint8_t _motor_direction = 99; // motor direction as reported by lidar
  78. int16_t _forward_direction = 999; // forward direction as reported by lidar
  79. bool _sector_initialised = false;
  80. };