Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
Loading...
Searching...
No Matches
src
ardupilot
ArduPilotProtocol.h
1
#pragma once
2
3
#include "../network/websocket/WebSocketProtocol.h"
4
#include "../network/websocket/WebSocketServer.h"
5
#include "../world_interface/data.h"
6
7
#include <
mutex
>
8
9
#include <Eigen/Geometry>
10
11
namespace
net {
12
namespace
ardupilot {
13
14
/* @brief A protocol in order to handle messages from an ArduPilot enabled device */
15
class
ArduPilotProtocol {
16
public
:
17
ArduPilotProtocol(
net::websocket::SingleClientWSServer
& websocketServer);
18
~ArduPilotProtocol();
19
ArduPilotProtocol(
const
ArduPilotProtocol& other) =
delete
;
20
ArduPilotProtocol& operator=(
const
ArduPilotProtocol& other) =
delete
;
21
22
/* @brief Gets the last reported GPS position (lat, lon)
23
*
24
* @return Last reported GPS position
25
*/
26
robot::types::DataPoint<navtypes::gpscoords_t>
getGPS();
27
28
/* @brief Gets the last reported orientation from the IMU
29
*
30
* @return Last reported orientation
31
*/
32
robot::types::DataPoint<Eigen::Quaterniond>
getIMU();
33
34
private
:
35
/* @brief Validates GPS request
36
*
37
* @param json message
38
*
39
* @return True if message is valid, false otherwise
40
*/
41
static
bool
validateGPSRequest(
const
nlohmann::json
& j);
42
43
/* @brief Validates IMU request
44
*
45
* @param json message
46
*
47
* @return True if message is valid, false otherwise
48
*/
49
static
bool
validateIMURequest(
const
nlohmann::json
& j);
50
51
/* @brief Destructures GPS json message and updates last reported GPS values
52
*
53
* @param json message
54
*/
55
void
handleGPSRequest(
const
nlohmann::json
& j);
56
57
/* @brief Destructures IMU json message and updates last reported GPS values
58
*
59
* @param json message
60
*/
61
void
handleIMURequest(
const
nlohmann::json
& j);
62
63
/* @brief Checks if the ArduPilotProtocol is connected
64
*
65
* @return True if connected, false if not connected
66
*/
67
bool
isArduPilotConnected();
68
69
/* @brief Registers the protocol with the websocket server
70
*
71
* @param websocket server of which to add protocol
72
*/
73
void
initArduPilotServer(
net::websocket::SingleClientWSServer
& websocketServer);
74
75
/* @brief Connection handler for websocket server */
76
void
clientConnected();
77
78
/* @brief Disconnect handler for websocket server */
79
void
clientDisconnected();
80
81
std::mutex
_connectionMutex;
82
bool
_arduPilotProtocolConnected;
83
84
std::mutex
_lastGPSMutex;
85
robot::types::DataPoint<navtypes::gpscoords_t>
_lastGPS;
86
87
std::mutex
_lastOrientationMutex;
88
robot::types::DataPoint<Eigen::Quaterniond>
_lastOrientation;
89
};
90
91
}
// namespace ardupilot
92
}
// namespace net
mutex
std::mutex
net::websocket::SingleClientWSServer
A WebSocket server class that only accepts a single client at a time to each endpoint served by this ...
Definition
WebSocketServer.h:35
robot::types::DataPoint
Represents data measured using a sensor at a given time.
Definition
data.h:136
nlohmann::json
basic_json<> json
Generated by
1.13.2