0.5.0
Loading...
Searching...
No Matches
udpSend.hpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
9/// @file udpSend.hpp
10/// @brief Asynchronous data link - sender node
11/// @author M. Maier (marcel.maier@ins.uni-stuttgart.de)
12/// @date 2023-07-19
13
14#pragma once
15
18
20
21#ifdef _WIN32
22 // Set the proper SDK version before including boost/Asio
23 #include <SDKDDKVer.h>
24 // Note boost/ASIO includes Windows.h.
25 #include <boost/asio.hpp>
26#else // _WIN32
27 #include <boost/asio.hpp>
28#endif //_WIN32
29
30#include <cstddef>
31#include <vector>
32#include <string>
33
34namespace NAV
35{
36/// UDP Client
37class UdpSend : public Node
38{
39 public:
40 /// @brief Default constructor
41 UdpSend();
42 /// @brief Destructor
43 ~UdpSend() override;
44 /// @brief Copy constructor
45 UdpSend(const UdpSend&) = delete;
46 /// @brief Move constructor
47 UdpSend(UdpSend&&) = delete;
48 /// @brief Copy assignment operator
49 UdpSend& operator=(const UdpSend&) = delete;
50 /// @brief Move assignment operator
52
53 /// @brief String representation of the Class Type
54 [[nodiscard]] static std::string typeStatic();
55
56 /// @brief String representation of the Class Type
57 [[nodiscard]] std::string type() const override;
58
59 /// @brief String representation of the Class Category
60 [[nodiscard]] static std::string category();
61
62 /// @brief ImGui config window which is shown on double click
63 /// @attention Don't forget to set _hasConfig to true in the constructor of the node
64 void guiConfig() override;
65
66 /// @brief Saves the node into a json object
67 [[nodiscard]] json save() const override;
68
69 /// @brief Restores the node from a json object
70 /// @param[in] j Json object with the node state
71 void restore(const json& j) override;
72
73 /// @brief Resets the node. Moves the read cursor to the start
74 bool resetNode() override;
75
76 private:
77 constexpr static size_t INPUT_PORT_INDEX_NODE_DATA = 0; ///< @brief Object (NodeData)
78
79 /// @brief Initialize the node
80 bool initialize() override;
81
82 /// @brief Deinitialize the node
83 void deinitialize() override;
84
85 /// @brief Callback when receiving data on a port
86 /// @param[in] queue Queue with all the received data messages
87 /// @param[in] pinIdx Index of the pin the data is received on
88 void receiveData(InputPin::NodeDataQueue& queue, size_t pinIdx);
89
90 /// @brief Set the Msg Type And Time object
91 /// @param[in] data2send Reference to the data that is to be sent
92 /// @param[in] insTime InsTime of the nodeData
93 void setMsgTypeAndTime(std::vector<char>& data2send, const InsTime& insTime);
94
95 /// IPv4 address
96 std::array<int, 4> _ip{};
97
98 /// UDP port number
99 int _port = 4567;
100
101 /// Message Type: 0 = posVelAtt, 1 = gnssObs
103
104 /// Range an IPv4 address can be in [0, 2^8-1]
105 static constexpr std::array<int, 2> IP_LIMITS = { 0, 255 };
106
107 /// Asynchronous receive fct
108 boost::asio::io_context _io_context;
109 /// Boost udp socket
110 boost::asio::ip::udp::socket _socket;
111 /// Boost udp resolver
112 boost::asio::ip::udp::resolver _resolver;
113 /// Boost udp endpoint
114 boost::asio::ip::udp::resolver::results_type _endpoints;
115};
116} // namespace NAV
nlohmann::json json
json namespace
The class is responsible for all time-related tasks.
Node Class.
Utility for the UDP Send and Receive nodes.
TsDeque< std::shared_ptr< const NAV::NodeData > > NodeDataQueue
Node data queue type.
Definition Pin.hpp:707
The class is responsible for all time-related tasks.
Definition InsTime.hpp:710
Node(std::string name)
Constructor.
Definition Node.cpp:30
boost::asio::ip::udp::resolver::results_type _endpoints
Boost udp endpoint.
Definition udpSend.hpp:114
UdpSend & operator=(UdpSend &&)=delete
Move assignment operator.
UdpUtil::MessageType _msgType
Message Type: 0 = posVelAtt, 1 = gnssObs.
Definition udpSend.hpp:102
static constexpr size_t INPUT_PORT_INDEX_NODE_DATA
Object (NodeData)
Definition udpSend.hpp:77
bool initialize() override
Initialize the node.
Definition udpSend.cpp:118
UdpSend()
Default constructor.
Definition udpSend.cpp:43
static constexpr std::array< int, 2 > IP_LIMITS
Range an IPv4 address can be in [0, 2^8-1].
Definition udpSend.hpp:105
boost::asio::ip::udp::resolver _resolver
Boost udp resolver.
Definition udpSend.hpp:112
bool resetNode() override
Resets the node. Moves the read cursor to the start.
Definition udpSend.cpp:88
void deinitialize() override
Deinitialize the node.
Definition udpSend.cpp:134
static std::string category()
String representation of the Class Category.
Definition udpSend.cpp:69
std::string type() const override
String representation of the Class Type.
Definition udpSend.cpp:64
boost::asio::io_context _io_context
Asynchronous receive fct.
Definition udpSend.hpp:108
void receiveData(InputPin::NodeDataQueue &queue, size_t pinIdx)
Callback when receiving data on a port.
Definition udpSend.cpp:141
void restore(const json &j) override
Restores the node from a json object.
Definition udpSend.cpp:105
void guiConfig() override
ImGui config window which is shown on double click.
Definition udpSend.cpp:74
UdpSend(UdpSend &&)=delete
Move constructor.
void setMsgTypeAndTime(std::vector< char > &data2send, const InsTime &insTime)
Set the Msg Type And Time object.
Definition udpSend.cpp:214
static std::string typeStatic()
String representation of the Class Type.
Definition udpSend.cpp:59
UdpSend(const UdpSend &)=delete
Copy constructor.
UdpSend & operator=(const UdpSend &)=delete
Copy assignment operator.
int _port
UDP port number.
Definition udpSend.hpp:99
boost::asio::ip::udp::socket _socket
Boost udp socket.
Definition udpSend.hpp:110
std::array< int, 4 > _ip
IPv4 address.
Definition udpSend.hpp:96
json save() const override
Saves the node into a json object.
Definition udpSend.cpp:93
~UdpSend() override
Destructor.
Definition udpSend.cpp:54
MessageType
Enum specifying the type of the output message.
Definition UdpUtil.hpp:28
@ PosVelAtt
Extract PosVelAtt data.
Definition UdpUtil.hpp:29