/
MAVLinkReader.h
63 lines (48 loc) · 1.34 KB
/
MAVLinkReader.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
#pragma once
// MAVLinkReader.h
#ifndef _MAVLINKREADER_h
#define _MAVLINKREADER_h
#if defined(ARDUINO) && ARDUINO >= 100
#include "arduino.h"
#else
#include "WProgram.h"
#endif
#include "MAVLinkEventReceiver.h"
/**
* @brief Base class for reading MAVLink message from a byte source. The messages captured create events to be sent to a MAVLinkEventReceiver
*/
class MAVLinkReader
{
public:
/**
* @brief Constructor
* @param mavlinkEventReceiver The event receiver to send events to when a message is received.
*
*/
MAVLinkReader( MAVLinkEventReceiver* mavlinkEventReceiver );
/**
* @brief Base function for reading MAVLink bytes from source
* @return True if a complete message has been read from source
*/
virtual bool receiveMAVLinkMessages();
/**
* @brief Semd a MavLink message to change the rover mode to the flight controller
* @param roverMode
*/
virtual void sendChangeMode( ROVER_MODE roverMode ) {};
/**
* @brief This is used by the scheduling system to give the MAVLink reader execution time
*/
virtual void tick();
/**
* @brief Get the mission time in milliseconds
* @return Milliseconds for mission time
*/
virtual uint32_t getMissionTime();
protected:
virtual bool readByte( uint8_t* buffer );
uint32_t _systemBootTimeMilliseconds = 0;
private:
MAVLinkEventReceiver* _mavlinkEventReceiver;
};
#endif