Motion Master
Loading...
Searching...
No Matches
util.h
Go to the documentation of this file.
1#pragma once
2
3#include <chrono>
4#include <cmath>
5#include <deque>
6#include <future>
7#include <list>
8#include <nlohmann/json.hpp>
9#include <numeric>
10#include <semver.hpp>
11#include <string>
12#include <thread>
13#include <utility>
14
15#include "cia402_drive.h"
16#include "motion-master.pb.h"
17#include "notifier.h"
19#include "virtual_device.h"
20
21const char* const HARDWARE_DESCRIPTION_FILENAME = ".hardware_description";
22const char* const STACK_INFO_FILENAME = "stack_info.json";
23const char* const STACK_IMAGE_FILENAME = "stack_image.svg";
24const char* const ESI_FILENAME = "SOMANET_CiA_402.xml";
25const char* const CONFIG_FILENAME = "config.csv";
26const char* const PLANT_MODEL_FILENAME = "plant_model.csv";
27const char* const VARIANT_FILENAME = ".variant";
28
29struct PlantModel {
30 std::vector<double> numerator;
31 std::vector<double> denominator;
32 double start_frequency = 0.0; // Hz
33 double end_frequency = 0.0; // Hz
34 uint16_t torque_amplitude = 0; // ‰ of rated torque
35 double duration_seconds = 0.0; // seconds
36 uint8_t signal_type = 0; // 0 - logarithmic, 1 - linear
37 nlohmann::json to_json() {
38 nlohmann::json j;
39 j["numerator"] = numerator;
40 j["denominator"] = denominator;
41 j["start_frequency"] = start_frequency;
42 j["end_frequency"] = end_frequency;
43 j["torque_amplitude"] = torque_amplitude;
44 j["duration_seconds"] = duration_seconds;
45 j["signal_type"] = signal_type;
46 return j;
47 }
48 std::string bode_file_content;
49};
50
51enum class ControllerType { kPiP, kPpi };
52
54
62
70
72
73#define JSON_TO_DOUBLE(jx) jx.is_number() ? static_cast<double>(jx) : 0.0
74
75// clang-format off
77 uint8_t vel_lp_type = 1; // 0 - disabled, 1 - 1st order, 2 - 2nd order (0x2021, 1)
78 uint32_t vel_lp_fc = 300; // [Hz] (0x2021, 2)
79 uint8_t pos_lp_type = 1; // 0 - disabled, 1 - 1st order, 2 - 2nd order (0x2022, 1)
80 uint32_t pos_lp_fc = 300; // [Hz] (0x2022, 2)
81 bool notch_en = true; // Enabled / disabled (0x2023, 1)
82 uint16_t notch_fw = 10; // [Hz] (0x2023, 3)
83 uint16_t notch_fc = 1000; // [Hz] (0x2023, 2)
84 int16_t vel_ff_gain = 0; // Permill, 0 - disabled (0x2015, 1)
85 uint16_t vel_ff_fc = 1000; // [Hz] (0x2015, 2)
86 int32_t L = 200; // Inductance, [μH] (0x2003, 4)
87 int32_t R = 300000; // Resistance, [μOhm] (0x2003, 3)
88 uint32_t vdc = 48000; // DC voltage, [mV] (0x6079, 0)
89 double current_ratio = 16384; // ADC conversion factor, [mA / inc] (from BSP file)
90 double tc_kp = 2500; // kp gain from FW v4.x.x, [-] (0x2010, 1)
91 double tc_ki = 40000; // ki gain from FW v4.x.x, [-] (0x2010, 2)
92 uint8_t switch_F = 0; // Switching frequency: 0 - 16kHz, 1 - 32kHz, 2 - 64kHz (0x2010, 9)
93 uint16_t tc_st = 1000; // Torque controller settling time, FW v5.x.x, [us] (0x2010, 10)
94 uint16_t tc_damping = 2000; // Torque controller damping ratio, FW v5.x.x, [permill] (0x2010, 11)
95 std::string software_version = "v4.4.1"; // FW version
96 unsigned int rated_torque; // Motor rated torque, [mNm]
97 double max_vel_noise; // Max value of the pre-recorded encoder noise, [RPM]
98 nlohmann::json to_json() {
99 nlohmann::json j;
100 j["vel_lp_type"] = vel_lp_type;
101 j["vel_lp_fc"] = vel_lp_fc;
102 j["pos_lp_type"] = pos_lp_type;
103 j["pos_lp_fc"] = pos_lp_fc;
104 j["notch_en"] = notch_en;
105 j["notch_fw"] = notch_fw;
106 j["notch_fc"] = notch_fc;
107 j["vel_ff_gain"] = vel_ff_gain;
108 j["vel_ff_fc"] = vel_ff_fc;
109 j["L"] = L;
110 j["R"] = R;
111 j["vdc"] = vdc;
112 j["current_ratio"] = current_ratio;
113 j["tc_kp"] = tc_kp;
114 j["tc_ki"] = tc_ki;
115 j["switch_F"] = switch_F;
116 j["tc_st"] = tc_st;
117 j["tc_damping"] = tc_damping;
118 j["software_version"] = software_version;
119 j["rated_torque"] = rated_torque;
120 j["max_vel_noise"] = max_vel_noise;
121 return j;
122 }
124// clang-format on
125
126typedef struct SystemParametersClass {
127 double time_step = 0.001;
128 uint32_t nominal_torque = 0;
129 uint32_t max_torque_mnm_ = 0;
132
133typedef struct TuningParametersClass {
134 // Chirp parameters
135 double duration_seconds = 5.0;
136 uint16_t torque_amplitude = 500;
137 double start_frequency = 3.0;
138 double end_frequency = 60.0;
139 double cutoff_frequency = 30.0;
140
141 // Position auto-tuning parameters
143 double settling_time = 0.2;
144 double position_damping = 2.0;
145 int16_t alpha_mult = 1;
146 uint8_t order = 4;
147
148 // Velocity auto-tuning parameters
150 float velocity_damping = 0.7f;
151
152 // Tuning sharpness limiter (nominal torque * warn_torque_const)
153 double warn_torque_const = 3.0;
154
155 // Position auto-tuning optimization boundaries
156 double lb = 2.0;
157 double ub = 314.0;
159
161
167
168const std::map<MotionMasterWarning, std::string>
170 {WAR_NONE, "No warning!"},
172 "Slave profile: The amplitude is outside of the configured limits - "
173 "using a limit value as the new amplitude!"},
174 {WAR_INTERNAL_LIMIT_REACHED, "Internal limit reached!"}};
175
176const std::map<int32_t, std::string> slave_error_map_ = {
177 {0x2110, "Short circuit/earth leakage (input)"},
178 {0x2120, "Earth leakage (input)"},
179 {0x2121, "Earth leakage phase L1"},
180 {0x2122, "Earth leakage phase L2"},
181 {0x2123, "Earth leakage phase L3"},
182 {0x2130, "Short circuit (input)"},
183 {0x2131, "Short circuit phases L1-L2"},
184 {0x2132, "Short circuit phases L2-L3"},
185 {0x2133, "Short circuit phases L3-L1"},
186 {0x2211, "Internal current no.1"},
187 {0x2212, "Internal current no.2"},
188 {0x2213, "Over-current in ramp function"},
189 {0x2214, "Over-current in the sequence"},
190 {0x2220, "Continuous over current (device internal)"},
191 {0x2221, "Continuous over current no.1"},
192 {0x2222, "Continuous over current no.2"},
193 {0x2230, "Short circuit/earth leakage (device internal)"},
194 {0x2240, "Earth leakage (device internal)"},
195 {0x2250, "Short circuit (device internal)"},
196 {0x2310, "Continuous over current"},
197 {0x2311, "Continuous over current no.1"},
198 {0x2312, "Continuous over current no.2"},
199 {0x2320, "Short circuit/earth leakage (motor-side)"},
200 {0x2330, "Earth leakage (motor-side)"},
201 {0x2331, "Earth leakage phase U"},
202 {0x2332, "Earth leakage phase V"},
203 {0x2333, "Earth leakage phase W"},
204 {0x2340, "Short circuit (motor-side)"},
205 {0x2341, "Short circuit phases U-V"},
206 {0x2342, "Earth leakage phase V-W"},
207 {0x2343, "Earth leakage phase W-U"},
208 {0x2350, "Load level fault (I2t, thermal state)"},
209 {0x2351, "Load level warning (I2t, thermal state)"},
210 {0x3110, "Mains overvoltage"},
211 {0x3111, "Mains overvoltage phase L1"},
212 {0x3112, "Mains overvoltage phase L2"},
213 {0x3113, "Mains overvoltage phase L3"},
214 {0x3120, "Mains undervoltage"},
215 {0x3121, "Mains undervoltage phase L1"},
216 {0x3122, "Mains undervoltage phase L2"},
217 {0x3123, "Mains undervoltage phase L3"},
218 {0x3130, "Phase failure"},
219 {0x3131, "Phase failure L1"},
220 {0x3132, "Phase failure L2"},
221 {0x3133, "Phase failure L3"},
222 {0x3134, "Phase sequence"},
223 {0x3140, "Mains frequency"},
224 {0x3141, "Mains frequency too great"},
225 {0x3142, "Mains frequency too small"},
226 {0x3210, "DC link overvoltage"},
227 {0x3211, "Overvoltage no. 1"},
228 {0x3212, "Overvoltage no. 2"},
229 {0x3220, "DC link undervoltage"},
230 {0x3221, "Undervoltage no. 1"},
231 {0x3222, "Undervoltage no. 2"},
232 {0x3230, "Load error"},
233 {0x3310, "Output overvoltage"},
234 {0x3311, "Output overvoltage phase U"},
235 {0x3312, "Output overvoltage phase V"},
236 {0x3313, "Output overvoltage phase W"},
237 {0x3320, "Armature circuit"},
238 {0x3321, "Armature circuit interrupted"},
239 {0x3330, "Field circuit"},
240 {0x3331, "Field circuit interrupted"},
241 {0x4110, "Excess ambient temperature"},
242 {0x4120, "Too low ambient temperature"},
243 {0x4130, "Temperature supply air"},
244 {0x4140, "Temperature air outlet"},
245 {0x4210, "Excess temperature device"},
246 {0x4220, "Too low temperature device"},
247 {0x4300, "Temperature drive"},
248 {0x4310, "Excess temperature drive"},
249 {0x4320, "Too low temperature drive"},
250 {0x4400, "Temperature supply"},
251 {0x4410, "Excess temperature supply"},
252 {0x4420, "Too low temperature supply"},
253 {0x5100, "Supply"},
254 {0x5110, "Supply low voltage"},
255 {0x5111, "U1 = supply ±15V"},
256 {0x5112, "U2 = supply +24 V"},
257 {0x5113, "U3 = supply +5 V"},
258 {0x5114, "U4 = manufacturer-specific"},
259 {0x5115, "U5 = manufacturer-specific"},
260 {0x5116, "U6 = manufacturer-specific"},
261 {0x5117, "U7 = manufacturer-specific"},
262 {0x5118, "U8 = manufacturer-specific"},
263 {0x5119, "U9 = manufacturer-specific"},
264 {0x5120, "Supply intermediate circuit"},
265 {0x5200, "Control"},
266 {0x5210, "Measurement circuit"},
267 {0x5220, "Computing circuit"},
268 {0x5300, "Operating unit"},
269 {0x5400, "Power section"},
270 {0x5410, "Output stages"},
271 {0x5420, "Chopper"},
272 {0x5430, "Input stages"},
273 {0x5440, "Contacts"},
274 {0x5441, "Contact 1 = manufacturer-specific"},
275 {0x5442, "Contact 2 = manufacturer-specific"},
276 {0x5443, "Contact 3 = manufacturer-specific"},
277 {0x5444, "Contact 4 = manufacturer-specific"},
278 {0x5445, "Contact 5 = manufacturer-specific"},
279 {0x5450, "Fuses"},
280 {0x5451, "S1 = l1"},
281 {0x5452, "S2 = l2"},
282 {0x5453, "S3 = l3"},
283 {0x5454, "S4 = manufacturer-specific"},
284 {0x5455, "S5 = manufacturer-specific"},
285 {0x5456, "S6 = manufacturer-specific"},
286 {0x5457, "S7 = manufacturer-specific"},
287 {0x5458, "S8 = manufacturer-specific"},
288 {0x5459, "S9 = manufacturer-specific"},
289 {0x5500, "Hardware memory"},
290 {0x5510, "RAM"},
291 {0x5520, "ROM/EPROM"},
292 {0x5530, "EEPROM"},
293 {0x6010, "Software reset (watchdog)"},
294 {0x6301, "to 630Fh Data record no. 1 to no. 15"},
295 {0x6310, "Loss of parameters"},
296 {0x6320, "Parameter error"},
297 {0x7100, "Power"},
298 {0x7110, "Brake chopper"},
299 {0x7111, "Failure brake chopper"},
300 {0x7112, "Over current brake chopper"},
301 {0x7113, "Protective circuit brake chopper"},
302 {0x7120, "Motor"},
303 {0x7121, "Motor blocked"},
304 {0x7122, "Motor error or commutation malfunction."},
305 {0x7123, "Motor tilted"},
306 {0x7200, "Measurement circuit"},
307 {0x7300, "Sensor"},
308 {0x7301, "Tacho fault"},
309 {0x7302, "Tacho wrong polarity"},
310 {0x7303, "Resolver 1 fault"},
311 {0x7304, "Resolver 2 fault"},
312 {0x7305, "Incremental encoder 1 fault"},
313 {0x7306, "Incremental encoder 2 fault"},
314 {0x7307, "Incremental encoder 3 fault"},
315 {0x7310, "Speed"},
316 {0x7320, "Position"},
317 {0x7400, "Computation circuit"},
318 {0x7500, "Communication"},
319 {0x7510, "Serial interface no. 1"},
320 {0x7520, "Serial interface no. 2"},
321 {0x7600, "Data storage (external)"},
322 {0x8300, "Torque control"},
323 {0x8311, "Excess torque"},
324 {0x8312, "Difficult start up"},
325 {0x8313, "Standstill torque"},
326 {0x8321, "Insufficient torque"},
327 {0x8331, "Torque fault"},
328 {0x8400, "Velocity speed controller"},
329 {0x8500, "Position controller"},
330 {0x8600, "Positioning controller"},
331 {0x8611, "Following error"},
332 {0x8612, "Reference limit"},
333 {0x8700, "Sync controller"},
334 {0x8800, "Winding controller"},
335 {0x8900, "Process data monitoring"},
336 {0x8A00, "Control"},
337 {0xF001, "Deceleration"},
338 {0xF002, "Sub-synchronous run"},
339 {0xF003, "Stroke operation"},
340 {0xF004, "Control"},
341 {0xFF03, "Warning - Excess temperature device"},
342 {0xFF04, "Pull brake voltage higher than measured on DC bus"},
343 {0xFF05, "Hold brake voltage higher than measured on DC bus"},
344 {0xFF06, "Open circuit: High FET in phase A"},
345 {0xFF07, "Open circuit: Low FET in phase A"},
346 {0xFF08, "Open circuit: High FET in phase B"},
347 {0xFF09, "Open circuit: Low FET in phase B"},
348 {0xFF0A, "Open circuit: High FET in phase C"},
349 {0xFF0B, "Open circuit: Low FET in phase C"},
350 {0xFF0C, "Commutation offset is missing"}};
351
352const std::map<int32_t, std::map<int32_t, int32_t>>
354 {8500, {{01, 20480}, {02, 24576}, {03, 16384}}},
355 {8501, {{01, 8192}, {02, 8192}, {03, 16384}}},
356 {8502, {{01, 20480}, {02, 24576}, {03, 16384}}},
357 {8503, {{01, 8192}, {02, 8192}, {03, 16384}}},
358 {8504, {{01, 20480}, {02, 24576}, {03, 16384}}},
359 {8505, {{01, 8192}, {02, 8192}, {03, 16384}}},
360 {9500, {{00, 32768}, {01, 32768}, {02, 32768}}},
361 {9501, {{01, 81920}, {02, 81920}}},
362 {9502, {{01, 16384}}},
363 {9506, {{01, 32768}}},
364 {9507, {{01, 81920}}},
365 {9508, {{01, 16384}}},
366 {9600, {{01, 32768}}},
367 {9601, {{01, 81920}}},
368 {9602, {{01, 16384}}},
369 {9606, {{01, 32768}}},
370 {9607, {{01, 81920}}},
371 {9608, {{01, 16384}}}};
372
373const std::map<int32_t, std::map<int32_t, int32_t>>
375 {8500, {{01, 40960}, {02, 49152}, {03, 32768}}},
376 {8501, {{01, 16384}, {02, 16384}, {03, 16384}}},
377 {8502, {{01, 40960}, {02, 49152}, {03, 32768}}},
378 {8503, {{01, 16384}, {02, 16384}, {03, 16384}}},
379 {8504, {{01, 40960}, {02, 49152}, {03, 32768}}},
380 {8505, {{01, 16384}, {02, 16384}, {03, 16384}}},
381 {9500, {{00, 32768}, {01, 32768}, {02, 32768}}},
382 {9501, {{01, 81920}, {02, 81920}}},
383 {9502, {{01, 16384}}},
384 {9506, {{01, 32768}}},
385 {9507, {{01, 81920}}},
386 {9508, {{01, 16384}}},
387 {9600, {{01, 32768}}},
388 {9601, {{01, 81920}}},
389 {9602, {{01, 16384}}},
390 {9606, {{01, 32768}}},
391 {9607, {{01, 81920}}},
392 {9608, {{01, 16384}}}};
393
395 kNotFound = 0x00008001,
396 kAccessDenied = 0x00008002,
397 kDiskFull = 0x00008003,
398 kIllegal = 0x00008004,
399 kPacketNumberWrong = 0x00008005,
400 kAlreadyExists = 0x00008006,
401 kNoUser = 0x00008007,
402 kBootstrapOnly = 0x00008008,
403 kNotBootstrap = 0x00008009,
404 kNoRights = 0x0000800a,
405 kProgramError = 0x0000800b
406};
407
416
424std::string get_slave_error_message(int32_t error_code);
425
426#ifdef __linux__
432int32_t set_default_thread_priority();
433
445int32_t set_max_thread_priority();
446#endif
447
456std::string etg1004_unit_string(uint32_t etg1004_unit_value);
457
466int32_t get_pdo_id(uint16_t index, uint8_t subindex,
467 std::map<int32_t, int32_t>& pdo_position_map);
468
469#ifdef __linux__
478std::string execute_system_command(const char* cmd);
479#endif
480
489bool abs_compare(float a, float b);
490
499template <typename T>
500bool opposite_signs(const T& a, const T& b) {
501 return ((a ^ b) >> (sizeof(T) * 8 - 1));
502}
503
509void interruptable_wait(size_t seconds);
510
520int32_t wrap_target_position(int32_t target, int32_t max_limit,
521 int32_t min_limit);
522
529
535void unregister_sync_signal(uint32_t signal_id);
536
544uint64_t wait_for_sync_signal(uint32_t signal_id);
552uint64_t wait_for_signal(int signal_fd);
553uint64_t wait_for_signal(uint32_t signal_id);
554
564std::vector<double> linspace(double lb, double ub, size_t n);
565
575
585 const ControllerGains& gains);
586
596 const ControllerGains& gains);
597
608bool check_gains(Cia402Drive& cia402_drive);
609
618bool string_ends_with(const std::string& value, const std::string& ending);
619
627std::vector<uint8_t> read_file_content(const std::string& path);
628
635void set_csv_configuration(VirtualDevice* virtual_device,
636 const std::vector<uint8_t>& csv_data);
637
648uint8_t calculate_crc(const std::vector<uint8_t>& data);
649
658uint32_t random_uint32(uint32_t min = 0, uint32_t max = UINT32_MAX);
659
665unsigned char random_char();
666
674std::string generate_uuid(size_t length);
675
683int32_t limit_int32_target(int64_t target);
684
690std::string run_env_info();
691
700bool validate_sii_data(const std::vector<uint8_t>& content, uint32_t device_id);
701
709bool file_exists(const std::string& path);
710
718std::string string_bytes_to_hex_array_string(const std::string& bytes);
719
729std::string get_firmware_version_string(Cia402Drive& cia402_drive);
730
740semver::version<> get_firmware_version(Cia402Drive& cia402_drive);
741
751
764 Cia402Drive& cia402_drive);
765
775 ControllerGains gains, uint32_t singleturn_resolution);
776
784CirculoType get_circulo_type(int32_t hardware_id);
785
795bool is_fw_based_on_v5(Cia402Drive& cia402_drive);
796
805bool is_fw_at_least(Cia402Drive& cia402_drive, const std::string& version);
806
815std::vector<uint8_t> zip(const std::string& file_name,
816 std::vector<uint8_t> data);
817
827std::vector<uint8_t> unzip(const std::vector<uint8_t>& data);
828
837uint32_t generate_od_entry_map_key(uint16_t index, uint8_t subindex);
838
847std::list<std::string> get_file_parts(std::list<std::string> file_list,
848 const std::string& file_name);
849
859 uint8_t encoder_ordinal);
860
868template <typename T>
869int32_t find_local_min_index_from_right(std::vector<T>& x) {
870 T min_value = x[x.size() - 1];
871
872 for (int32_t i = x.size() - 2; i >= 0; i--) {
873 if (x[i] <= min_value) {
874 min_value = x[i];
875 } else {
876 return i + 1;
877 }
878 }
879
880 return 1;
881}
882
890template <typename T>
891double compute_mean(const std::vector<T>& numbers) {
892 if (numbers.empty()) {
893 return 0.0;
894 }
895
896 return std::accumulate(numbers.begin(), numbers.end(), 0.0) / numbers.size();
897}
898
906template <typename T>
907double compute_standard_deviation(const std::vector<T>& numbers) {
908 if (numbers.empty()) {
909 return 0.0;
910 }
911
912 double mean = compute_mean(numbers);
913
914 std::vector<double> tmp(numbers.size());
915 std::transform(numbers.begin(), numbers.end(), tmp.begin(),
916 [mean](double x) { return x - mean; });
917
918 double sq_sum = std::inner_product(tmp.begin(), tmp.end(), tmp.begin(), 0.0);
919 return std::sqrt(sq_sum / (numbers.size() - 1));
920}
921
931template <typename T>
932double compute_section_mean(const std::vector<T>& numbers, size_t start,
933 size_t end) {
934 std::vector<T> section(numbers.begin() + start, numbers.begin() + end);
935
936 if (section.empty()) {
937 return 0.0;
938 }
939
940 return std::accumulate(section.begin(), section.end(), 0.0) / section.size();
941}
942
951template <typename T>
952std::vector<T> erase_edge_elements(std::vector<T> v, size_t length) {
953 v.erase(v.begin(), v.begin() + length);
954 v.erase(v.end() - length, v.end());
955 return v;
956}
957
965template <typename R>
966bool is_future_done(std::future<R> const& f) {
967 try {
968 return f.wait_for(std::chrono::seconds(0)) == std::future_status::ready;
969 } catch (std::future_error& e) {
970 return true; // The future is not running since there is an error
971 }
972}
973
981template <typename T>
982auto to_integral(T e) {
983 return static_cast<std::underlying_type_t<T>>(e);
984}
985
994template <typename T>
995static std::vector<T> diff(std::vector<T> vector) {
996 std::vector<T> result;
997 result.reserve(vector.size() - 1);
998
999 for (size_t i = 1; i < vector.size(); i++) {
1000 result.push_back(vector[i] - vector[i - 1]);
1001 }
1002
1003 return result;
1004}
1005
1009template <typename... Args>
1010std::string string_format(const std::string& format, Args... args) {
1011 int size_s = std::snprintf(nullptr, 0, format.c_str(), args...) +
1012 1; // Extra space for '\0'
1013 if (size_s <= 0) {
1014 throw std::runtime_error("Error during formatting.");
1015 }
1016 auto size = static_cast<size_t>(size_s);
1017 std::unique_ptr<char[]> buf(new char[size]);
1018 std::snprintf(buf.get(), size, format.c_str(), args...);
1019 return std::string(buf.get(),
1020 buf.get() + size - 1); // We don't want the '\0' inside
1021}
1022
1033 public:
1034 LowPassFilter(uint16_t cutoff_frequency, double ts);
1035
1036 double filter(double value);
1037
1038 private:
1039 std::deque<double> input_data_;
1040 std::deque<double> output_data_;
1041 double fc_, a0_, a1_, a2_, b0_, b1_, b2_;
1042};
1043
1053 public:
1054 HighPassFilter(uint16_t cutoff_frequency, double ts);
1055
1056 double filter(double value);
1057
1058 private:
1059 std::deque<double> input_data_;
1060 std::deque<double> output_data_;
1061 double fc_, a0_, a1_, a2_, a3_, a4_, b0_, b1_, b2_, b3_, b4_;
1062};
1063
1065
1066bool compareStringsCaseInsensitive(const std::string& s1,
1067 const std::string& s2);
1068
1070const uint16_t kDefaultEthernetPort = 8080;
1071
1084std::pair<std::string, uint16_t> parse_ethernet_endpoint(
1085 const std::string& endpoint);
std::vector< uint8_t > unzip(const std::vector< uint8_t > &data)
Unzip data containing a single file.
Definition util.cc:1489
const std::map< int32_t, std::string > slave_error_map_
Definition util.h:176
ControllerGains get_position_controller_gains(Cia402Drive &cia402_drive)
Get the current position controller gains of a drive.
Definition util.cc:278
const char *const HARDWARE_DESCRIPTION_FILENAME
Definition util.h:21
const uint16_t kDefaultEthernetPort
Default port used for SPoE Ethernet endpoints when none is specified.
Definition util.h:1070
double compute_section_mean(const std::vector< T > &numbers, size_t start, size_t end)
Compute the mean of a section of a given vector of integers.
Definition util.h:932
ControllerGains convert_auto_tuning_controller_gains(ControllerGains gains, uint32_t singleturn_resolution)
Convert gains to inc pos values and rpm velocity values.
Definition util.cc:1363
const std::map< int32_t, std::map< int32_t, int32_t > > adc_current_ratio_fw_v4_4_2_map
Definition util.h:374
uint64_t wait_for_signal(int signal_fd)
Wait for the system signal.
std::string controllerTypeToString(ControllerType ct)
Definition util.cc:148
uint32_t register_sync_signal()
Register a thread sync signal.
bool string_ends_with(const std::string &value, const std::string &ending)
Check if a string ends with another string.
Definition util.cc:433
const std::map< int32_t, std::map< int32_t, int32_t > > adc_current_ratio_fw_v4_4_1_map
Definition util.h:353
std::string generate_uuid(size_t length)
Generate a UUID of a custom length.
Definition util.cc:610
bool set_velocity_controller_gains(Cia402Drive &cia402_drive, const ControllerGains &gains)
Set the velocity controller gains.
Definition util.cc:380
semver::version get_firmware_version(Cia402Drive &cia402_drive)
Get the (semver) version of the used firmware.
Definition util.cc:894
std::pair< std::string, uint16_t > parse_ethernet_endpoint(const std::string &endpoint)
Parse an SPoE Ethernet endpoint of the form "ip" or "ip:port".
Definition util.cc:1713
std::string get_slave_error_message(int32_t error_code)
Return the appropriate error message.
Definition util.cc:48
int32_t find_local_min_index_from_right(std::vector< T > &x)
Find a local minimum (from right) in the supplied vector.
Definition util.h:869
struct AutoTuningDriveConfigurationClass AutoTuningDriveConfiguration
const char *const STACK_INFO_FILENAME
Definition util.h:22
bool validate_sii_data(const std::vector< uint8_t > &content, uint32_t device_id)
Validate an SII data before writing.
double compute_mean(const std::vector< T > &numbers)
Compute mean given a vector of numbers.
Definition util.h:891
bool opposite_signs(const T &a, const T &b)
Check if parameters have opposite signs.
Definition util.h:500
bool get_plant_model_from_flash(Cia402Drive &cia402_drive, PlantModel *m)
Get the plant model from the flash memory of the device.
Definition util.cc:943
const char *const ESI_FILENAME
Definition util.h:24
const std::map< MotionMasterWarning, std::string > motion_master_warning_to_message_map_
Definition util.h:169
void unregister_sync_signal(uint32_t signal_id)
Unregister a thread sync signal.
int32_t limit_int32_target(int64_t target)
Limit a target to integer 32 if necessary.
Definition util.cc:622
std::string run_env_info()
Get all sorts of run environment information.
Definition util.cc:642
const char *const CONFIG_FILENAME
Definition util.h:25
bool compareStringsCaseInsensitive(const std::string &s1, const std::string &s2)
Definition util.cc:1706
int32_t wrap_target_position(int32_t target, int32_t max_limit, int32_t min_limit)
Wrap the target position over limit.
std::vector< double > linspace(double lb, double ub, size_t n)
Generate equally spaced points inside an interval.
Definition util.cc:262
CirculoType
Definition util.h:55
@ kCirculo7
Definition util.h:57
@ kCirculo9Smm
Definition util.h:60
@ kCirculo7Smm
Definition util.h:58
@ kCirculo9
Definition util.h:59
PositionControlStrategy
Definition util.h:160
@ kSimple
Definition util.h:160
@ kNone
Definition util.h:160
@ kCascaded
Definition util.h:160
ControllerType
Definition util.h:51
@ kPpi
Definition util.h:51
@ kPiP
Definition util.h:51
uint64_t wait_for_sync_signal(uint32_t signal_id)
Wait for the system sync signal.
std::string etg1004_unit_string(uint32_t etg1004_unit_value)
Convert ETG.1004 unit format to string.
Definition util.cc:84
EncoderLocation
Definition util.h:71
@ kMotorShaft
Definition util.h:71
@ kDrivingShaft
Definition util.h:71
MotionMasterWarning
Definition util.h:162
@ WAR_PROFILE_TARGET_LIMITED
Definition util.h:164
@ WAR_INTERNAL_LIMIT_REACHED
Definition util.h:165
@ WAR_NONE
Definition util.h:163
const char *const VARIANT_FILENAME
Definition util.h:27
std::vector< uint8_t > read_file_content(const std::string &path)
Read a file into a byte (uint8_t) vector.
Definition util.cc:441
uint8_t calculate_crc(const std::vector< uint8_t > &data)
Definition util.cc:571
uint32_t generate_od_entry_map_key(uint16_t index, uint8_t subindex)
Generate a map key for an OD entry using index/subindex.
Definition util.cc:1530
unsigned char random_char()
Generate a random character.
Definition util.cc:603
std::vector< uint8_t > zip(const std::string &file_name, std::vector< uint8_t > data)
Zip a single file.
Definition util.cc:1437
bool file_exists(const std::string &path)
Check if a file exists on the system where Motion Master is running.
Definition util.cc:856
std::string get_master_warning_message(MotionMasterWarning warning)
Return the appropriate warning message.
Definition util.cc:40
bool set_position_controller_gains(Cia402Drive &cia402_drive, const ControllerGains &gains)
Set the position controller gains.
Definition util.cc:332
bool check_gains(Cia402Drive &cia402_drive)
Check if the required gains are properly set.
Definition util.cc:402
CirculoEncoderType
Definition util.h:63
@ kCirculo7Inner
Definition util.h:65
@ kCirculo9Outer
Definition util.h:68
@ kUndefined
Definition util.h:64
@ kCirculo7Outer
Definition util.h:66
@ kCirculo9Inner
Definition util.h:67
bool abs_compare(float a, float b)
Compare absolute values of the input parameters.
Definition util.cc:199
void interruptable_wait(size_t seconds)
Blocks for the set amount of time, but allows to be interrupted.
Definition util.cc:201
uint32_t random_uint32(uint32_t min=0, uint32_t max=UINT32_MAX)
Generate a random unsigned 32-bit integer in a certain range.
Definition util.cc:596
double compute_standard_deviation(const std::vector< T > &numbers)
Compute the standard deviation given a vector of numbers.
Definition util.h:907
std::list< std::string > get_file_parts(std::list< std::string > file_list, const std::string &file_name)
Process the provided file list and find the file or its parts.
Definition util.cc:1534
std::vector< T > erase_edge_elements(std::vector< T > v, size_t length)
Remove a number of the first and last elements in the vector.
Definition util.h:952
int get_soem_slaves_responding()
Definition util.cc:1700
EncoderLocation get_encoder_location(Cia402Drive &cia402_drive, uint8_t encoder_ordinal)
Get the location of an encoder.
Definition util.cc:1578
int32_t get_pdo_id(uint16_t index, uint8_t subindex, std::map< int32_t, int32_t > &pdo_position_map)
Uses a special map and its keys to get the PDO array positions.
Definition util.cc:135
const char *const STACK_IMAGE_FILENAME
Definition util.h:23
std::string string_bytes_to_hex_array_string(const std::string &bytes)
Convert bytes (as string) to a string of hex values.
Definition util.cc:861
bool is_fw_based_on_v5(Cia402Drive &cia402_drive)
Check if the device requires the newer encoder configuration (FW >= v5 or FW >= v0....
Definition util.cc:1402
EcatSlaveFoeError
Definition util.h:394
@ kAccessDenied
Definition util.h:396
@ kNotBootstrap
Definition util.h:403
@ kProgramError
Definition util.h:405
@ kBootstrapOnly
Definition util.h:402
@ kNoRights
Definition util.h:404
@ kIllegal
Definition util.h:398
@ kAlreadyExists
Definition util.h:400
@ kNotFound
Definition util.h:395
@ kPacketNumberWrong
Definition util.h:399
@ kNoUser
Definition util.h:401
@ kDiskFull
Definition util.h:397
bool is_future_done(std::future< R > const &f)
Check if the future has finished executing.
Definition util.h:966
bool is_fw_at_least(Cia402Drive &cia402_drive, const std::string &version)
Check if the drive uses at least a certain FW version.
Definition util.cc:1422
struct TuningParametersClass TuningParameters
struct SystemParametersClass SystemParameters
const char *const PLANT_MODEL_FILENAME
Definition util.h:26
std::string get_firmware_version_string(Cia402Drive &cia402_drive)
Get the (string) version of the used firmware.
Definition util.cc:873
std::string string_format(const std::string &format, Args... args)
Format a string like printf()
Definition util.h:1010
auto to_integral(T e)
Return an integral type value of an enum class.
Definition util.h:982
AutoTuningDriveConfiguration get_auto_tuning_drive_configuration(Cia402Drive &cia402_drive)
Get the configuration required for full auto-tuning.
Definition util.cc:973
CirculoType get_circulo_type(int32_t hardware_id)
Get the Circulo type based on the hardware ID.
void set_csv_configuration(VirtualDevice *virtual_device, const std::vector< uint8_t > &csv_data)
Set the configuration parameter values from CSV data.
Definition util.cc:471
Definition cia402_drive.h:120
Holds position and velocity PID gains for a controller.
Definition standalone_autotuning.h:60
HighPassFilter(uint16_t cutoff_frequency, double ts)
Definition util.cc:1665
double filter(double value)
Definition util.cc:1686
double filter(double value)
Definition util.cc:1652
LowPassFilter(uint16_t cutoff_frequency, double ts)
Definition util.cc:1635
Definition virtual_device.h:22
uint8_t * value
Definition co_dictionary.h:9
uint16_t index
Definition co_dictionary.h:0
@ kUnspecified
Definition global.h:35
uint16_t notch_fw
Definition util.h:82
int32_t R
Definition util.h:87
int32_t L
Definition util.h:86
nlohmann::json to_json()
Definition util.h:98
double tc_kp
Definition util.h:90
uint16_t notch_fc
Definition util.h:83
int16_t vel_ff_gain
Definition util.h:84
uint16_t tc_st
Definition util.h:93
uint16_t tc_damping
Definition util.h:94
double max_vel_noise
Definition util.h:97
uint32_t vdc
Definition util.h:88
uint8_t vel_lp_type
Definition util.h:77
uint8_t switch_F
Definition util.h:92
uint32_t vel_lp_fc
Definition util.h:78
bool notch_en
Definition util.h:81
double tc_ki
Definition util.h:91
uint8_t pos_lp_type
Definition util.h:79
uint32_t pos_lp_fc
Definition util.h:80
std::string software_version
Definition util.h:95
unsigned int rated_torque
Definition util.h:96
uint16_t vel_ff_fc
Definition util.h:85
double current_ratio
Definition util.h:89
Definition util.h:29
double end_frequency
Definition util.h:33
uint16_t torque_amplitude
Definition util.h:34
double start_frequency
Definition util.h:32
std::string bode_file_content
Definition util.h:48
std::vector< double > denominator
Definition util.h:31
uint8_t signal_type
Definition util.h:36
double duration_seconds
Definition util.h:35
nlohmann::json to_json()
Definition util.h:37
std::vector< double > numerator
Definition util.h:30
Definition util.h:126
uint32_t nominal_torque
Definition util.h:128
double time_step
Definition util.h:127
uint32_t max_torque_mnm_
Definition util.h:129
uint32_t singleturn_resolution
Definition util.h:130
Definition util.h:133
int16_t alpha_mult
Definition util.h:145
double end_frequency
Definition util.h:138
double warn_torque_const
Definition util.h:153
double cutoff_frequency
Definition util.h:139
double lb
Definition util.h:156
uint16_t torque_amplitude
Definition util.h:136
float velocity_loop_bandwidth
Definition util.h:149
float velocity_damping
Definition util.h:150
double start_frequency
Definition util.h:137
ControllerType controller_type
Definition util.h:142
double duration_seconds
Definition util.h:135
double position_damping
Definition util.h:144
double ub
Definition util.h:157
double settling_time
Definition util.h:143
uint8_t order
Definition util.h:146