2
2
#ifndef MARCH_HARDWARE_ETHERCAT_ETHERCATMASTER_H
3
3
#define MARCH_HARDWARE_ETHERCAT_ETHERCATMASTER_H
4
4
#include < atomic>
5
+ #include < exception>
5
6
#include < vector>
6
7
#include < string>
7
8
#include < thread>
@@ -23,7 +24,7 @@ namespace march
23
24
class EthercatMaster
24
25
{
25
26
public:
26
- EthercatMaster (std::string ifname, int max_slave_index, int cycle_time);
27
+ EthercatMaster (std::string ifname, int max_slave_index, int cycle_time, int slave_timeout );
27
28
~EthercatMaster ();
28
29
29
30
/* Delete copy constructor/assignment since the member thread can not be copied */
@@ -37,6 +38,8 @@ class EthercatMaster
37
38
bool isOperational () const ;
38
39
void waitForPdo ();
39
40
41
+ std::exception_ptr getLastException () const noexcept ;
42
+
40
43
/* *
41
44
* Returns the cycle time in milliseconds.
42
45
*/
@@ -75,13 +78,27 @@ class EthercatMaster
75
78
76
79
/* *
77
80
* Sends the PDO and receives the working counter and check if this is lower than expected.
81
+ *
82
+ * @returns true if and only if all PDOs have been successfully sent and received, otherwise false.
78
83
*/
79
- void sendReceivePdo ();
84
+ bool sendReceivePdo ();
80
85
81
86
/* *
82
87
* Checks if all the slaves are connected and in operational state.
83
88
*/
84
- static void monitorSlaveConnection ();
89
+ void monitorSlaveConnection ();
90
+
91
+ /* *
92
+ * Attempts to recover a slave to operational state.
93
+ *
94
+ * @returns true when recovery was successfull, otherwise false.
95
+ */
96
+ bool attemptSlaveRecover (int slave);
97
+
98
+ /* *
99
+ * Sets ethercat state to INIT and closes port.
100
+ */
101
+ void closeEthercat ();
85
102
86
103
/* *
87
104
* Sets the ethercat thread priority and scheduling
@@ -105,7 +122,12 @@ class EthercatMaster
105
122
char io_map_[4096 ] = { 0 };
106
123
int expected_working_counter_ = 0 ;
107
124
125
+ int latest_lost_slave_ = -1 ;
126
+ const int slave_watchdog_timeout_;
127
+ std::chrono::high_resolution_clock::time_point valid_slaves_timestamp_ms_;
128
+
108
129
std::thread ethercat_thread_;
130
+ std::exception_ptr last_exception_;
109
131
};
110
132
111
133
} // namespace march
0 commit comments