0.4.1
Loading...
Searching...
No Matches
SkydelNetworkStream.cpp
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
10
11#include <thread>
12#include <string>
13#include <vector>
14#include <chrono>
15#include <cmath>
16#include <sstream>
17
18#include "util/Logger.hpp"
26
27namespace nm = NAV::NodeManager;
28using boost::asio::ip::udp;
29
30namespace NAV::experimental
31{
32
43
48
50{
51 return "SkydelNetworkStream";
52}
53
54std::string SkydelNetworkStream::type() const
55{
56 return typeStatic();
57}
58
60{
61 return "Data Provider";
62}
63
65{
66 std::string str;
67
69 {
70 str = "(loading)";
71 }
72 else
73 {
74 std::ostringstream strs;
75 strs << _dataRate;
76 str = strs.str();
77 }
78
79 ImGui::LabelText(str.c_str(), "data rate [Hz]");
80 ImGui::SameLine();
81 gui::widgets::HelpMarker("The data rate can be adjusted in Skydel: Settings/Plug-ins/<Plug-in-name>/Plug-in UI. Make sure to enable either WiFi or a LAN connection. Enabling both can lead to loss of data, because Skydel only knows one ip address.");
82}
83
85{
86 return true;
87}
88
90{
91 _socket.async_receive_from(
92 boost::asio::buffer(_data, _maxLength), _senderEndpoint,
93 [this](boost::system::error_code errorRcvd, std::size_t bytesRcvd) {
94 if ((!errorRcvd) && (bytesRcvd > 0))
95 {
96 // Splitting the incoming string analogous to 'ImuFile.cpp'
97 std::stringstream lineStream(std::string(_data.begin(), _data.end()));
98 std::string cell;
99 auto obsG = std::make_shared<PosVelAtt>();
100 auto obs = std::make_shared<ImuObs>(this->_imuPos);
101
102 // Inits for simulated measurement variables
103 uint64_t timeSinceStartup = 0;
104
105 double posX = 0.0;
106 double posY = 0.0;
107 double posZ = 0.0;
108 double attRoll = 0.0;
109 double attPitch = 0.0;
110 double attYaw = 0.0;
111
112 double accelX = 0.0;
113 double accelY = 0.0;
114 double accelZ = 0.0;
115 double gyroX = 0.0;
116 double gyroY = 0.0;
117 double gyroZ = 0.0;
118
119 for (size_t i = 0; i < 13; i++)
120 {
121 // Reading string from csv
122 if (std::getline(lineStream, cell, ','))
123 {
124 switch (i)
125 {
126 case 0:
127 timeSinceStartup = static_cast<uint64_t>(std::stod(cell) * 1e6); // [ns] = [ms] * 1e6
128 break;
129 case 1:
130 posX = std::stod(cell);
131 break;
132 case 2:
133 posY = std::stod(cell);
134 break;
135 case 3:
136 posZ = std::stod(cell);
137 break;
138 case 4:
139 attRoll = std::stod(cell);
140 break;
141 case 5:
142 attPitch = std::stod(cell);
143 break;
144 case 6:
145 attYaw = std::stod(cell);
146 break;
147 case 7:
148 accelX = std::stod(cell);
149 break;
150 case 8:
151 accelY = std::stod(cell);
152 break;
153 case 9:
154 accelZ = std::stod(cell);
155 break;
156 case 10:
157 gyroX = std::stod(cell);
158 break;
159 case 11:
160 gyroY = std::stod(cell);
161 break;
162 case 12:
163 gyroZ = std::stod(cell);
164 break;
165
166 default:
167 LOG_ERROR("Error in network stream: Cell index is out of bounds");
168 break;
169 }
170 }
171 else
172 {
173 LOG_ERROR("Error in IMU stream: Reading a string from csv failed");
174 return;
175 }
176 }
177
178 // Set GNSS values
179 Eigen::Vector3d e_position{ posX, posY, posZ };
180 Eigen::Vector3d lla_position = trafo::ecef2lla_WGS84(e_position);
181 Eigen::Quaterniond e_Quat_b;
182 e_Quat_b = trafo::e_Quat_n(lla_position(0), lla_position(1)) * trafo::n_Quat_b(attRoll, attPitch, attYaw);
183
184 obsG->setPosition_e(e_position);
185 Eigen::Vector3d velDummy{ 0, 0, 0 }; // TODO: Add velocity output in Skydel API and NetStream
186 obsG->setVelocity_e(velDummy);
187 obsG->setAttitude_e_Quat_b(e_Quat_b); // Attitude MUST BE set after Position, because the n- to e-sys trafo depends on lla_position
188
189 // Set IMU values
190 obs->p_acceleration = { accelX, accelY, accelZ };
191 obs->p_angularRate = { gyroX, gyroY, gyroZ };
192 // TODO: Add magnetometer model to Skydel API 'InstinctDataStream'
193
194 InsTime currentTime = util::time::GetCurrentInsTime();
195 if (!currentTime.empty())
196 {
197 obs->insTime = currentTime;
198 obsG->insTime = currentTime;
199 }
200
202 {
203 // FIXME: This seems like a bug in clang-tidy. Check if it is working in future versions of clang-tidy
204 // NOLINTNEXTLINE(hicpp-use-nullptr, modernize-use-nullptr)
205 if (timeSinceStartup - _lastMessageTime >= static_cast<uint64_t>(1.5 / _dataRate * 1e9))
206 {
207 LOG_WARN("{}: Potentially lost a message. Previous message was at {} and current message at {} which is a time difference of {} seconds.", nameId(),
208 _lastMessageTime, timeSinceStartup, static_cast<double>(timeSinceStartup - _lastMessageTime) * 1e-9);
209 }
210 }
211 _lastMessageTime = timeSinceStartup;
212
215
216 // Data rate (for visualization in GUI)
218
220 {
221 _packageCount = 0;
223 }
224
225 if (_packageCount == 1)
226 {
227 _startPoint = std::chrono::steady_clock::now();
228 }
229 else if (_packageCount == _packagesNumber)
230 {
231 std::chrono::duration<double> elapsed_seconds = std::chrono::steady_clock::now() - _startPoint;
232 _dataRate = static_cast<double>(_packagesNumber - 1) / elapsed_seconds.count();
233
234 // Dynamic adaptation of data rate to a human-readable display update rate in GUI (~ 1 Hz)
235 if ((_dataRate > 2) && (_dataRate < 1001)) // restriction on 'reasonable' sensor data rates (Skydel max. is 1000 Hz)
236 {
237 _packagesNumber = static_cast<int>(_dataRate);
238 }
239 else if (_dataRate >= 1001)
240 {
241 _packagesNumber = 1000;
242 }
243
244 _packageCount = 0;
245
246 LOG_DATA("Elapsed Seconds = {}", elapsed_seconds.count());
247 LOG_DATA("SkydelNetworkStream: dataRate = {}", _dataRate);
248 }
249 }
250 else
251 {
252 LOG_ERROR("Error receiving the network stream from Skydel");
253 }
254
255 if (!_stop)
256 {
257 do_receive();
258 }
259 });
260}
261
263{
264 LOG_TRACE("{}: called", nameId());
265
266 _stop = false;
267 _packageCount = 0;
268 _startCounter = 0;
269 _packagesNumber = 2;
270
272
273 do_receive();
274
275 if (_isStartup)
276 {
277 _testThread = std::thread([this]() {
278 _ioservice.run();
279 });
280 }
281 else
282 {
283 _testThread = std::thread([this]() {
284 _ioservice.restart();
285 _ioservice.run();
286 });
287 }
288
289 _isStartup = false;
290
291 return true;
292}
293
295{
296 LOG_TRACE("{}: called", nameId());
297
298 _stop = true;
299 _ioservice.stop();
300 _testThread.join();
301}
302
303} // namespace NAV::experimental
Transformation collection.
Save/Load the Nodes.
Text Help Marker (?) with Tooltip.
Parent Class for all IMU Observations.
Utility class for logging to console and file.
#define LOG_DATA
All output which occurs repeatedly every time observations are received.
Definition Logger.hpp:29
#define LOG_ERROR
Error occurred, which stops part of the program to work, but not everything.
Definition Logger.hpp:73
#define LOG_WARN
Error occurred, but a fallback option exists and program continues to work normally.
Definition Logger.hpp:71
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Definition Logger.hpp:65
Manages all Nodes.
Position, Velocity and Attitude Storage Class.
Node receiving UDP packages from the Skydel GNSS simulator Instinct plugin.
Keeps track of the current real/simulation time.
static std::string type()
Returns the type of the data class.
Definition ImuObs.hpp:33
Imu(const Imu &)=delete
Copy constructor.
ImuPos _imuPos
Position and rotation information for conversion from platform to body frame.
Definition Imu.hpp:57
The class is responsible for all time-related tasks.
Definition InsTime.hpp:710
constexpr bool empty() const
Checks if the Time object has a value.
Definition InsTime.hpp:1089
ImVec2 _guiConfigDefaultWindowSize
Definition Node.hpp:410
std::string nameId() const
Node name and id.
Definition Node.cpp:253
bool _onlyRealTime
Whether the node can run in post-processing or only real-time.
Definition Node.hpp:419
void invokeCallbacks(size_t portIndex, const std::shared_ptr< const NodeData > &data)
Calls all registered callbacks on the specified output port.
Definition Node.cpp:180
bool _hasConfig
Flag if the config window should be shown.
Definition Node.hpp:413
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
std::thread _testThread
Thread for receiver fct.
std::string type() const override
String representation of the Class Type.
void deinitialize() override
Deinitialize the node.
bool initialize() override
Initialize the node.
void guiConfig() override
ImGui config window which is shown on double click.
boost::asio::ip::udp::endpoint _senderEndpoint
Boost udp endpoint.
int _startCounter
Counter for packages that are skipped until data rate is shown.
bool resetNode() override
Resets the node. It is guaranteed that the node is initialized when this is called.
static constexpr size_t OUTPUT_PORT_INDEX_IMU_OBS
Port number of the Skydel-ImuObs output.
static constexpr size_t OUTPUT_PORT_INDEX_GNSS_OBS
Port number of the Skydel-GnssObs output.
bool _isStartup
Startup handler: used in 'initialize()' to differentiate between startup and re-initialization.
int _packageCount
Counter for received packages.
static std::string category()
String representation of the Class Category.
bool _stop
Stop handler: once true, the asynchronous receive function stops.
static std::string typeStatic()
String representation of the Class Type.
boost::asio::io_context _ioservice
Asynchronous receive fct.
std::array< char, _maxLength > _data
Network data stream array.
uint64_t _lastMessageTime
Stores the time of the last received message.
boost::asio::ip::udp::socket _socket
Boost udp socket.
std::chrono::steady_clock::time_point _startPoint
Time point where the first package has been received.
double _dataRate
Data rate of the received network stream [Hz].
static constexpr unsigned int _maxLength
Network data stream buffer size (boost::asio)
void do_receive()
Receive Skydel network stream data.
OutputPin * CreateOutputPin(Node *node, const char *name, Pin::Type pinType, const std::vector< std::string > &dataIdentifier, OutputPin::PinData data=static_cast< void * >(nullptr), int idx=-1)
Create an Output Pin object.
void HelpMarker(const char *desc, const char *symbol="(?)")
Text Help Marker, e.g. '(?)', with Tooltip.
Eigen::Vector3< typename Derived::Scalar > ecef2lla_WGS84(const Eigen::MatrixBase< Derived > &e_position)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.
Eigen::Quaternion< Scalar > e_Quat_n(const Scalar &latitude, const Scalar &longitude)
Quaternion for rotations from navigation to Earth-fixed frame.
Eigen::Quaternion< Scalar > n_Quat_b(Scalar roll, Scalar pitch, Scalar yaw)
Quaternion for rotations from body to navigation frame.
@ Flow
NodeData Trigger.
Definition Pin.hpp:52