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
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
/*      File: slave.cpp
*       This file is part of the program ethercatcpp-core
*       Program description : EtherCAT driver libraries for UNIX
*       Copyright (C) 2017-2024 -  Robin Passama (LIRMM / CNRS) Arnaud Meline (LIRMM / CNRS) Benjamin Navarro (LIRMM / CNRS). All Right reserved.
*
*       This software is free software: you can redistribute it and/or modify
*       it under the terms of the CeCILL-C license as published by
*       the CEA CNRS INRIA, either version 1
*       of the License, or (at your option) any later version.
*       This software is distributed in the hope that it will be useful,
*       but WITHOUT ANY WARRANTY without even the implied warranty of
*       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
*       CeCILL-C License for more details.
*
*       You should have received a copy of the CeCILL-C License
*       along with this software. If not, it can be found on the official website
*       of the CeCILL licenses family (http://www.cecill.info/index.en.html).
*/
#include "slave.h"
#include <ethercatcpp/slave_device.h>

#include <cassert>
#include <cstring>

#if defined EOE_AVAILABLE
#include <arpa/inet.h>
#endif

#include <pid/log/ethercatcpp-core_ethercatcpp-core.h>

namespace ethercatcpp {

void SlaveInfo::init_soem_data() {
    // output pointer in IOmap buffer
    slave_soem_.outputs = nullptr;
    // inputs pointer in IOmap buffer
    slave_soem_.inputs = nullptr;
    // registered configuration function PO->SO
    slave_soem_.PO2SOconfig = nullptr;

    // Initialize all var
    slave_soem_.state = 0;
    slave_soem_.ALstatuscode = 0;
    slave_soem_.configadr = 0;
    slave_soem_.aliasadr = 0;
    slave_soem_.eep_man = 0;
    slave_soem_.eep_id = 0;
    slave_soem_.eep_rev = 0;
    slave_soem_.Itype = 0;
    slave_soem_.Dtype = 0;
    slave_soem_.Obits = 0;
    slave_soem_.Obytes = 0;
    slave_soem_.Ostartbit = 0;
    slave_soem_.Ibits = 0;
    slave_soem_.Ibytes = 0;
    slave_soem_.Istartbit = 0;
    for (int it = 0; it < EC_MAXSM; it++) {
        slave_soem_.SM[it].SMflags = 0;
        slave_soem_.SM[it].SMlength = 0;
        slave_soem_.SM[it].StartAddr = 0;
        slave_soem_.SMtype[it] = 0;
    }
    for (int it = 0; it < EC_MAXFMMU; it++) {
        slave_soem_.FMMU[it].FMMUactive = 0;
        slave_soem_.FMMU[it].FMMUtype = 0;
        slave_soem_.FMMU[it].LogEndbit = 0;
        slave_soem_.FMMU[it].LogLength = 0;
        slave_soem_.FMMU[it].LogStart = 0;
        slave_soem_.FMMU[it].LogStartbit = 0;
        slave_soem_.FMMU[it].PhysStart = 0;
        slave_soem_.FMMU[it].PhysStartBit = 0;
    }
    slave_soem_.FMMU0func = 0;
    slave_soem_.FMMU1func = 0;
    slave_soem_.FMMU2func = 0;
    slave_soem_.FMMU3func = 0;
    slave_soem_.mbx_l = 0;
    slave_soem_.mbx_wo = 0;
    slave_soem_.mbx_rl = 0;
    slave_soem_.mbx_ro = 0;
    slave_soem_.mbx_proto = 0;
    slave_soem_.mbx_cnt = 0;
    slave_soem_.ptype = 0;
    slave_soem_.topology = 0;
    slave_soem_.activeports = 0;
    slave_soem_.consumedports = 0;
    slave_soem_.parent = 0;
    slave_soem_.parentport = 0;
    slave_soem_.entryport = 0;
    slave_soem_.DCrtA = 0;
    slave_soem_.DCrtB = 0;
    slave_soem_.DCrtC = 0;
    slave_soem_.DCrtD = 0;
    slave_soem_.pdelay = 0;
    slave_soem_.DCnext = 0;
    slave_soem_.DCprevious = 0;
    slave_soem_.DCcycle = 0;
    slave_soem_.DCshift = 0;
    slave_soem_.DCactive = 0;
    slave_soem_.configindex = 0;
    slave_soem_.SIIindex = 0;
    slave_soem_.eep_8byte = 0;
    slave_soem_.eep_pdi = 0;
    slave_soem_.CoEdetails = 0;
    slave_soem_.FoEdetails = 0;
    slave_soem_.EoEdetails = 0;
    slave_soem_.SoEdetails = 0;
    slave_soem_.Ebuscurrent = 0;
    slave_soem_.blockLRW = 0;
    slave_soem_.group = 0;
    slave_soem_.FMMUunused = 0;
    slave_soem_.hasdc = FALSE;
    slave_soem_.islost = FALSE;
    strcpy(slave_soem_.name, "");
}

SlaveInfo::SlaveInfo(SlaveDevice* dev)<--- Member variable 'SlaveInfo::ec_bus_pos_' is not initialized in the constructor.<--- Function 'SlaveInfo' argument 1 names different: declaration 'unit_dev_ptr' definition 'dev'.
    : device_(dev),
      context_(nullptr),
      serial_number_(0),
      current_step_(0),
      timewait_step_(0),
      dc_sync0_is_used_(false),
      dc_sync0_1_is_used_(false),
      dc_sync_cycle_shift_(0),
      dc_sync0_cycle_time_(0),
      dc_sync1_cycle_time_(0) {
    init_soem_data();
}

SlaveInfo::~SlaveInfo() = default;

// -----------------------------------------------

//
uint16_t SlaveInfo::ec_bus_position() const {
    return ec_bus_pos_;
}

void SlaveInfo::set_ec_bus_position(uint16_t position) {
    ec_bus_pos_ = position;
}

void SlaveInfo::set_master_context(ecx_contextt* context) {
    context_ = context;
}

uint16_t SlaveInfo::state() const {
    return slave_soem_.state;
}

void SlaveInfo::set_state(uint16_t state) {
    slave_soem_.state = state;
}

uint16_t SlaveInfo::configured_addr() const {
    return slave_soem_.configadr;
}

void SlaveInfo::configure_address(uint16_t configadr) {
    slave_soem_.configadr = configadr;
}

uint16_t SlaveInfo::alias_addr() const {
    return slave_soem_.aliasadr;
}

void SlaveInfo::set_alias_addr(uint16_t aliasadr) {
    slave_soem_.aliasadr = aliasadr;
}

int32_t SlaveInfo::delay() const {
    return slave_soem_.pdelay;
}

void SlaveInfo::set_delay(int32_t delay) {
    slave_soem_.pdelay = delay;
}

uint32_t SlaveInfo::eep_manufacturer() const {
    return slave_soem_.eep_man;
}

void SlaveInfo::set_eep_manufacturer(uint32_t eep_man) {
    slave_soem_.eep_man = eep_man;
}

uint32_t SlaveInfo::eep_device() const {
    return slave_soem_.eep_id;
}

void SlaveInfo::set_eep_device(uint32_t eep_id) {
    slave_soem_.eep_id = eep_id;
}

uint32_t SlaveInfo::serial_number() const {
    return serial_number_;
}

void SlaveInfo::set_serial_number(uint32_t serial_number) {
    serial_number_ = serial_number;
}

// -----------------------------------------------------
// Outputs config from Master to Slave (input for slave)

uint8_t* SlaveInfo::output_address() const {
    return slave_soem_.outputs;
} // output_address

void SlaveInfo::set_output_address(uint8_t* output_address_ptr) {
    slave_soem_.outputs = output_address_ptr;
}

uint16_t SlaveInfo::output_size_bits() const {
    return slave_soem_.Obits;
}

void SlaveInfo::set_output_size_bits(uint16_t outputs_size_bits) {
    slave_soem_.Obits = outputs_size_bits;
}

uint32_t SlaveInfo::output_size() const {
    return slave_soem_.Obytes;
}

void SlaveInfo::set_output_size(uint16_t outputs_size_bytes) {
    slave_soem_.Obytes = outputs_size_bytes;
}

uint8_t SlaveInfo::output_start_bit() const {
    return slave_soem_.Ostartbit;
}

void SlaveInfo::set_output_start_bit(uint8_t output_start_bit) {
    slave_soem_.Ostartbit = output_start_bit;
}

// ----------------------------------------------------
// inputs config from SlaveInfo to Master (output for slave)

uint8_t* SlaveInfo::input_address() const {
    return slave_soem_.inputs;
}

void SlaveInfo::set_input_address(uint8_t* input_address_ptr) {
    slave_soem_.inputs = input_address_ptr;
}

uint16_t SlaveInfo::input_size_bits() const {
    return slave_soem_.Ibits;
}

void SlaveInfo::set_input_size_bits(uint16_t inputs_size_bits) {
    slave_soem_.Ibits = inputs_size_bits;
}

uint32_t SlaveInfo::input_size() const {
    return slave_soem_.Ibytes;
}

void SlaveInfo::set_input_size(uint16_t inputs_size_bytes) {
    slave_soem_.Ibytes = inputs_size_bytes;
}

uint8_t SlaveInfo::input_start_bit() const {
    return slave_soem_.Istartbit;
}

void SlaveInfo::set_input_start_bit(uint8_t input_start_bit) {
    slave_soem_.Istartbit = input_start_bit;
}

// --------------------------------------------------------
// SyncManager configuration (ec_smt)
//  sm_id < EC_MAXSM !!

uint16_t SlaveInfo::SM_start_address(const int& sm_id) const {
    assert(sm_id < EC_MAXSM);
    return slave_soem_.SM[sm_id].StartAddr;
}

void SlaveInfo::set_SM_start_address(const int& sm_id, uint16_t startaddr) {
    assert(sm_id < EC_MAXSM);
    slave_soem_.SM[sm_id].StartAddr = startaddr;
}

uint16_t SlaveInfo::SM_length(const int& sm_id) const {
    assert(sm_id < EC_MAXSM);
    return slave_soem_.SM[sm_id].SMlength;
}

void SlaveInfo::set_SM_length(const int& sm_id, uint16_t sm_length) {
    assert(sm_id < EC_MAXSM);
    slave_soem_.SM[sm_id].SMlength = sm_length;
}

uint32_t SlaveInfo::SM_flags(const int& sm_id) const {
    assert(sm_id < EC_MAXSM);
    return slave_soem_.SM[sm_id].SMflags;
}

void SlaveInfo::set_SM_flags(const int& sm_id, uint32_t sm_flag) {
    assert(sm_id < EC_MAXSM);
    slave_soem_.SM[sm_id].SMflags = sm_flag;
}

uint8_t SlaveInfo::SM_type(const int& sm_id) const {
    assert(sm_id < EC_MAXSM);
    return slave_soem_.SMtype[sm_id];
}

void SlaveInfo::set_SM_type(const int& sm_id, uint8_t sm_type) {
    assert(sm_id < EC_MAXSM);
    slave_soem_.SMtype[sm_id] = sm_type;
}
// ---------------------------------------------------------
// FMMU configurations (ec_fmmut)

uint32_t SlaveInfo::FMMU_logical_start(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].LogStart;
}

void SlaveInfo::set_FMMU_logical_start(const int& fmmu_id,
                                       uint32_t logical_start) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].LogStart = logical_start;
}

uint16_t SlaveInfo::FMMU_logical_length(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].LogLength;
}

void SlaveInfo::set_FMMU_logical_length(const int& fmmu_id,
                                        uint16_t logical_length) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].LogLength = logical_length;
}
//

uint8_t SlaveInfo::FMMU_logical_start_bit(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].LogStartbit;
}

void SlaveInfo::set_FMMU_logical_start_bit(const int& fmmu_id,
                                           uint8_t logical_start_bit) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].LogStartbit = logical_start_bit;
}

uint8_t SlaveInfo::FMMU_logical_end_bit(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].LogEndbit;
}

void SlaveInfo::set_FMMU_logical_end_bit(const int& fmmu_id,
                                         uint8_t logical_end_bit) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].LogEndbit = logical_end_bit;
}

uint16_t SlaveInfo::FMMU_physical_start(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].PhysStart;
}

void SlaveInfo::set_FMMU_physical_start(const int& fmmu_id,
                                        uint16_t physical_start) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].PhysStart = physical_start;
}

uint8_t SlaveInfo::FMMU_physical_start_bit(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].PhysStartBit;
}

void SlaveInfo::set_FMMU_physical_start_bit(const int& fmmu_id,
                                            uint8_t physical_start_bit) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].PhysStartBit = physical_start_bit;
}

uint8_t SlaveInfo::FMMU_type(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].FMMUtype;
}

void SlaveInfo::set_FMMU_type(const int& fmmu_id, uint8_t fmmu_type) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].FMMUtype = fmmu_type;
}

uint8_t SlaveInfo::FMMU_active(const int& fmmu_id) const {
    assert(fmmu_id < EC_MAXFMMU);
    return slave_soem_.FMMU[fmmu_id].FMMUactive;
}

void SlaveInfo::set_FMMU_active(const int& fmmu_id, uint8_t fmmu_active) {
    assert(fmmu_id < EC_MAXFMMU);
    slave_soem_.FMMU[fmmu_id].FMMUactive = fmmu_active;
}

uint8_t SlaveInfo::FMMU_unused() const {
    return slave_soem_.FMMUunused;
}

void SlaveInfo::set_FMMU_unused(uint8_t FMMUunused) {
    slave_soem_.FMMUunused = FMMUunused;
}

// ----------------------------------------------------
// DC config

bool SlaveInfo::has_dc() const {
    return static_cast<bool>(slave_soem_.hasdc);
}

void SlaveInfo::set_dc(bool hasdc) {
    slave_soem_.hasdc = hasdc;
}

uint8_t SlaveInfo::dc_active() {
    return slave_soem_.DCactive;
}

void SlaveInfo::activate_dc(uint8_t dc_active) {
    slave_soem_.DCactive = dc_active;
}

// ----------------------------------------------------
// < 0 if slave config forced.
uint16_t SlaveInfo::configured_index() const {
    return slave_soem_.configindex;
}

void SlaveInfo::set_configured_index(uint16_t configindex) {
    slave_soem_.configindex = configindex;
}

// ---------------------------------------------------
// group

uint8_t SlaveInfo::group_id() const {
    return slave_soem_.group;
}

void SlaveInfo::set_group_id(uint8_t group_id) {
    slave_soem_.group = group_id;
}

// ----------------------------------------------------
// Slave Name

const std::string SlaveInfo::name() const {
    return std::string(slave_soem_.name);
}

void SlaveInfo::set_name(const std::string& name) {
    assert(name.size() < EC_MAXNAME + 1);
    strcpy(slave_soem_.name, name.c_str());
}
//----------------------------------------------------------
// size of SM and FMMU max
int SlaveInfo::max_SMs() const {
    return EC_MAXSM;
}

int SlaveInfo::max_FMMUs() const {
    return EC_MAXFMMU;
}

//----------------------------------------------------------------------------
// defining steps functions

uint8_t SlaveInfo::run_steps() const {
    return device_->run_steps();
}

void SlaveInfo::pre_run_step(uint8_t step) {
    return device_->pre_run_step(step);
}

void SlaveInfo::post_run_step(uint8_t step) {
    return device_->post_run_step(step);
}

uint8_t SlaveInfo::init_steps() const {
    return device_->init_steps();
}

void SlaveInfo::pre_init_step(uint8_t step) {
    return device_->pre_init_step(step);
}

void SlaveInfo::post_init_step(uint8_t step) {
    return device_->post_init_step(step);
}

uint8_t SlaveInfo::end_steps() const {
    return device_->end_steps();
}

void SlaveInfo::pre_end_step(uint8_t step) {
    return device_->pre_end_step(step);
}

void SlaveInfo::post_end_step(uint8_t step) {
    return device_->post_end_step(step);
}

void SlaveInfo::update_device_buffers() {
    device_->update_buffers();
}

uint8_t SlaveInfo::current_step() const {
    return current_step_;
}

void SlaveInfo::set_current_step(uint8_t step) {
    current_step_ = step;
}

void SlaveInfo::increment_current_step() {
    ++current_step_;
}

int SlaveInfo::step_wait_time() const {
    return timewait_step_;
}

void SlaveInfo::set_step_wait_time(int timewait) {
    timewait_step_ = timewait;
}

//-----------------------------------------------------------------------------
// define of Canopen Over Ethercat (CoE) function

// // CoE SDO write, blocking. Single subindex or Complete Access.
//  *
//  * A "normal" download request is issued, unless we have
//  * small data, then a "expedited" transfer is used. If the parameter is
//  larger than
//  * the mailbox size then the download is segmented. The function will split
//  the
//  * parameter data in segments and send them to the slave one by one.
//  *
//  * @param[in]  context    = context struct
//  * @param[in]  ec_bus_pos_= SlaveInfo number
//  * @param[in]  index      = Index to write
//  * @param[in]  sub_index  = Subindex to write, must be 0 or 1 if CA is used.
//  * @param[in]  CA         = FALSE = single subindex. TRUE = Complete Access,
//  all subindexes written.
//  * @param[in]  buffer_size= Size in bytes of parameter buffer.
//  * @param[out] buffer_ptr = Pointer to parameter buffer
//  * @param[in]  Timeout    = Timeout in us, standard is EC_TIMEOUTRXM
//  * @return Workcounter from last slave response
int SlaveInfo::write_sdo(uint16_t index, uint8_t sub_index, int buffer_size,
                         void* buffer_ptr) {
    return (ecx_SDOwrite(context_, ec_bus_pos_, index, sub_index, FALSE,
                         buffer_size, buffer_ptr, EC_TIMEOUTRXM));
}
// // CoE SDO read, blocking. Single subindex or Complete Access.
//  *
//  * Only a "normal" upload request is issued. If the requested parameter is <=
//  4bytes
//  * then a "expedited" response is returned, otherwise a "normal" response. If
//  a "normal"
//  * response is larger than the mailbox size then the response is segmented.
//  The function
//  * will combine all segments and copy them to the parameter buffer.
//  *
//  * @param[in]  context    = context struct
//  * @param[in]  slave      = SlaveInfo number
//  * @param[in]  index      = Index to read
//  * @param[in]  subindex   = Subindex to read, must be 0 or 1 if CA is used.
//  * @param[in]  CA         = FALSE = single subindex. TRUE = Complete Access,
//  all subindexes read.
//  * @param[in,out] psize   = Size in bytes of parameter buffer, returns bytes
//  read from SDO.
//  * @param[out] p          = Pointer to parameter buffer
//  * @param[in]  timeout    = Timeout in us, standard is EC_TIMEOUTRXM
//  * @return Workcounter from last slave response
int SlaveInfo::read_sdo(uint16_t index, uint8_t sub_index, int psize,
                        void* buffer_ptr) {
    return (ecx_SDOread(context_, ec_bus_pos_, index, sub_index, FALSE, &psize,
                        buffer_ptr, EC_TIMEOUTRXM));
}

void SlaveInfo::launch_init_configuration() {
    device_->launch_init_configuration();
}

void SlaveInfo::launch_end_configuration() {
    device_->launch_end_configuration();
}

//-----------------------------------------------------------------------------
// Function to used and set the DC synchro signal 0

// function to Configure the distributed clock sync0
uint32_t SlaveInfo::sync0_cycle_time() {
    return dc_sync0_cycle_time_;
}

int32_t SlaveInfo::sync_cycle_shift() {
    return dc_sync_cycle_shift_;
}

bool SlaveInfo::sync0_used() {
    return dc_sync0_is_used_;
}

void SlaveInfo::config_sync0(uint32_t cycle_time_0, int32_t cycle_shift) {
    dc_sync0_cycle_time_ = cycle_time_0;
    dc_sync_cycle_shift_ = cycle_shift;
    dc_sync0_is_used_ = true;
}

uint32_t SlaveInfo::sync1_cycle_time() {
    return dc_sync1_cycle_time_;
}

bool SlaveInfo::sync0_1_used() {
    return dc_sync0_1_is_used_;
}

void SlaveInfo::config_sync0_1(uint32_t cycle_time_0, uint32_t cycle_time_1,
                               int32_t cycle_shift) {
    dc_sync_cycle_shift_ = cycle_shift;
    dc_sync0_cycle_time_ = cycle_time_0;
    dc_sync1_cycle_time_ = cycle_time_1;
    dc_sync0_1_is_used_ = true;
}

// --------  functions for file access--------

int32_t SlaveInfo::read_file(std::string_view filename, uint32_t password,
                             int32_t size, uint8_t* buffer) {
    int wkc =
        ecx_FOEread(context_, ec_bus_pos_, const_cast<char*>(filename.data()),
                    password, &size, buffer, EC_TIMEOUTRXM);

    if (wkc > 0) {
        return size;
    } else {
        switch (wkc) {
        case -EC_ERR_TYPE_FOE_FILE_NOTFOUND:
            pid_log << pid::error << "File " << std::string(filename)
                    << " not found on device or not allowed to read"
                    << pid::flush;
            break;
        case -EC_ERR_TYPE_PACKET_ERROR:
            pid_log << pid::error << "Packet reading error when reading file "
                    << std::string(filename) << pid::flush;
            break;
        case -EC_ERR_TYPE_FOE_ERROR:
            pid_log << pid::error << "FoE Error when writing file "
                    << std::string(filename)
                    << ": check that device supports FoE" << pid::flush;
            break;
        case -EC_ERR_TYPE_FOE_BUF2SMALL:
            pid_log << pid::error << "File " << std::string(filename)
                    << " cannot be read because buffer is too small"
                    << pid::flush;
            break;
        default:
            pid_log << pid::error << "FoE unknown error when reading file "
                    << std::string(filename) << pid::flush;
            break;
        }
    }
    return -1;
}
bool SlaveInfo::write_file(std::string_view filename, uint32_t password,
                           int32_t size, uint8_t* buffer) {
    int wkc = ecx_FOEwrite(context_, ec_bus_pos_,
                           const_cast<char*>(filename.data()), password, size,
                           reinterpret_cast<void*>(buffer), EC_TIMEOUTRXM);

    if (wkc > 0) {
        return true;
    } else {
        switch (wkc) {
        case -EC_ERR_TYPE_FOE_FILE_NOTFOUND:
            pid_log << pid::error << "File " << std::string(filename)
                    << " not found on device or not allowed to write"
                    << pid::flush;
            break;
        case -EC_ERR_TYPE_FOE_ERROR:
            pid_log << pid::error << "FoE Error when writing file "
                    << std::string(filename)
                    << ": check that device supports FoE" << pid::flush;
            break;
        default:
            pid_log << pid::error << "FoE unknown error when writing file "
                    << std::string(filename) << pid::flush;
            break;
        }
        return false;
    }
}

bool SlaveInfo::read_sercos(uint8_t drive, uint8_t flags, uint16_t idn,
                            int32_t size, uint8_t* buffer) {
    return (ecx_SoEread(context_, ec_bus_pos_, drive, flags, idn, &size, buffer,
                        EC_TIMEOUTRXM) > 0);
}

bool SlaveInfo::write_sercos(uint8_t drive, uint8_t flags, uint16_t idn,
                             int32_t size, uint8_t* buffer) {
    return ecx_SoEwrite(context_, ec_bus_pos_, drive, flags, idn, size, buffer,
                        EC_TIMEOUTRXM) > 0;
}

#ifdef EOE_AVAILABLE
namespace {

uint32_t ip_string_to_code(std::string_view ip_str) {
    // Utilise inet_addr pour convertir une adresse IP en uint32_t
    return inet_addr(ip_str.data());
}

std::string ip_code_to_string(uint32_t ip_uint32) {
    struct in_addr addr;
    addr.s_addr = ip_uint32;
    std::string ret = inet_ntoa(addr);
    return ret;
}

void mac_string_to_code(std::string_view mac_str, uint8_t mac_code[6]) {
    uint8_t value;
    char* pos = const_cast<char*>(mac_str.data());
    for (int i = 0; i < 6; i++) {
        sscanf(pos, "%2hhx", &value);
        mac_code[i] = value;
        pos += 3; // Move past the two hex digits and the separator
    }
}

std::string mac_code_to_string(uint8_t mac_code[6]) {
    char mac_str[18];
    sprintf(mac_str, "%02X:%02X:%02X:%02X:%02X:%02X", mac_code[0], mac_code[1],
            mac_code[2], mac_code[3], mac_code[4], mac_code[5]);
    return std::string(mac_str);
}
} // namespace

bool SlaveInfo::detect_ethernet_configuration(
    uint8_t port, SlaveDevice::EthernetConfiguration& config) {
    eoe_param_t ret;
    if (ecx_EOEgetIp(context_, ec_bus_pos_, port, &ret, EC_TIMEOUTRXM) > 0) {
        if (ret.ip_set) {
            config.ip = ip_code_to_string(ret.ip.addr);
        }
        if (ret.mac_set) {
            config.mac = mac_code_to_string(ret.mac.addr);
        }
        if (ret.subnet_set) {
            config.mask = ip_code_to_string(ret.subnet.addr);
        }
        if (ret.default_gateway_set) {
            config.gateway = ip_code_to_string(ret.default_gateway.addr);
        }
        if (ret.dns_ip_set) {
            config.dns = ip_code_to_string(ret.dns_ip.addr);
        }
        return true;
    }
    return false;
}

bool SlaveInfo::configure_ethernet(
    uint8_t port, const SlaveDevice::EthernetConfiguration& config) {
    eoe_param_t ret;
    if (config.ip.empty() && config.mac.empty() && config.mask.empty() &&
        config.gateway.empty() && config.dns.empty()) {
        return true;
    }
    if (not config.ip.empty()) {
        ret.ip_set = 1;
        ret.ip.addr = ip_string_to_code(config.ip);
    }
    if (not config.mask.empty()) {
        ret.subnet_set = 1;
        ret.subnet.addr = ip_string_to_code(config.mask);
    }
    if (not config.mac.empty()) {
        ret.mac_set = 1;
        mac_string_to_code(config.mac, ret.mac.addr);
    }
    if (not config.gateway.empty()) {
        ret.default_gateway_set = 1;
        ret.default_gateway.addr = ip_string_to_code(config.gateway);
    }
    if (not config.dns.empty()) {
        ret.dns_ip_set = 1;
        ret.dns_ip.addr = ip_string_to_code(config.dns);
    }
    return (ecx_EOEsetIp(context_, ec_bus_pos_, port, &ret, EC_TIMEOUTRXM) > 0);
}

int32_t SlaveInfo::read_ethernet(uint8_t port, int32_t size, uint8_t* buffer) {
    if (ecx_EOErecv(context_, ec_bus_pos_, port, &size, buffer, EC_TIMEOUTRXM) >
        0) {
        return size;
    }
    return -1;
}

bool SlaveInfo::write_ethernet(uint8_t port, int32_t size, uint8_t* buffer) {
    return ecx_EOEsend(context_, ec_bus_pos_, port, size, buffer,
                       EC_TIMEOUTRXM) > 0;
}

#endif

} // namespace ethercatcpp