-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathxv11lidar.h
67 lines (58 loc) · 1.62 KB
/
xv11lidar.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
/*
* xv11lidar-arduino library header
*
* Copyright 2018 (C) Bartosz Meglicki <[email protected]>
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
*/
#ifndef XV11LIDAR_H
#define XV11LIDAR_H
#include "Arduino.h"
#include <stdint.h>
#include <PID_v1.h> //uses modified PID library (float instead of double implementation)
struct XV11Packet
{
uint32_t timestamp_us;//timestamp in microseconds
uint8_t angle_quad; //0-89 for readings 0-4 356-359
uint16_t speed64; //divide by 64 for speed in rpm
uint16_t distances[4]; //flags and distance or error code
uint16_t signals[4]; //signal strengths
};
class XV11Lidar
{
enum State {AwaitingStartByte, CollectingPacket};
enum {PacketBytes=22};
const float SpeedMultiplier=1.0f/64.0f;
public:
/* Setup */
XV11Lidar(HardwareSerial &serial, int pwm_pin);
void setup(int motor_rpm);
/* Cyclic */
bool processAvailable(XV11Packet *packet);
bool applyMotorPID();
private:
void decodePacket(const uint8_t *data, XV11Packet *packet) const;
uint16_t checksum(const uint8_t data[PacketBytes]) const;
inline uint16_t decode_u16(const uint8_t *data) const
{
return (uint16_t)data[1] << 8 | data[0];
}
private:
/* Hardware */
HardwareSerial &m_serial;
const int m_pwm_pin;
/* Packet & Decoding */
State m_state;
uint8_t m_packet[PacketBytes];
int m_packet_bytes;
uint32_t m_packet_timestamp_us;
/* Motor control */
PID m_motor_pid;
double m_motor_actual_rpm;
double m_motor_setpoint_rpm;
double m_motor_pwm;
};
#endif