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