APM:Libraries
AP_RangeFinder_LeddarOne.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "RangeFinder.h"
4 #include "RangeFinder_Backend.h"
5 
6 // defines
7 #define LEDDARONE_DEFAULT_ADDRESS 0x01
8 #define LEDDARONE_MODOBUS_FUNCTION_CODE 0x04
9 #define LEDDARONE_MODOBUS_FUNCTION_REGISTER_ADDRESS 20
10 #define LEDDARONE_MODOBUS_FUNCTION_READ_NUMBER 10
11 
12 #define LEDDARONE_SERIAL_PORT_MAX 250
13 #define LEDDARONE_READ_BUFFER_SIZE 25
14 
15 #define LEDDARONE_DETECTIONS_MAX 3
16 #define LEDDARONE_DETECTION_DATA_NUMBER_INDEX 10
17 #define LEDDARONE_DETECTION_DATA_INDEX_OFFSET 11
18 #define LEDDARONE_DETECTION_DATA_OFFSET 4
19 
20 // LeddarOne status
30 };
31 
32 // LeddarOne Modbus status
38 };
39 
41 {
42 
43 public:
44  // constructor
47  uint8_t serial_instance);
48 
49  // static detection function
50  static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
51 
52  // update state
53  void update(void);
54 
55 protected:
56 
57  virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
58  return MAV_DISTANCE_SENSOR_LASER;
59  }
60 
61 private:
62  // get a reading
63  bool get_reading(uint16_t &reading_cm);
64 
65  // CRC16
66  bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck);
67 
68  // parse a response message from ModBus
69  LeddarOne_Status parse_response(uint8_t &number_detections);
70 
72  uint32_t last_reading_ms;
75 
77  uint32_t sum_distance;
78 
81  uint32_t read_len;
82 
83  // Modbus send request buffer
84  // read input register (function code 0x04)
85  const uint8_t send_request_buffer[8] = {
88  0,
89  LEDDARONE_MODOBUS_FUNCTION_REGISTER_ADDRESS, // 20: Address of first register to read
90  0,
91  LEDDARONE_MODOBUS_FUNCTION_READ_NUMBER, // 10: The number of consecutive registers to read
92  0x30, // CRC Lo
93  0x09 // CRC Hi
94  };
95 };
bool get_reading(uint16_t &reading_cm)
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
#define LEDDARONE_DEFAULT_ADDRESS
#define LEDDARONE_READ_BUFFER_SIZE
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
uint16_t detections[LEDDARONE_DETECTIONS_MAX]
#define LEDDARONE_DETECTIONS_MAX
#define LEDDARONE_MODOBUS_FUNCTION_READ_NUMBER
LeddarOne_ModbusStatus modbus_status
LeddarOne_Status parse_response(uint8_t &number_detections)
#define LEDDARONE_MODOBUS_FUNCTION_REGISTER_ADDRESS
#define LEDDARONE_MODOBUS_FUNCTION_CODE
uint8_t read_buffer[LEDDARONE_READ_BUFFER_SIZE]
LeddarOne_ModbusStatus
bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override