@@ -70,7 +70,9 @@ EcMaster::~EcMaster()
7070 //
7171 }
7272 for (auto & domain : domain_info_) {
73- delete domain.second ;
73+ if (domain.second != NULL ) {
74+ delete domain.second ;
75+ }
7476 }
7577}
7678
@@ -128,7 +130,10 @@ void EcMaster::addSlave(uint16_t alias, uint16_t position, EcSlave * slave)
128130 for (auto & iter : domain_map) {
129131 // get the domain info, create if necessary
130132 uint32_t domain_index = iter.first ;
131- DomainInfo * domain_info = domain_info_[domain_index];
133+ DomainInfo * domain_info = NULL ;
134+ if (domain_info_.count (domain_index)) {
135+ domain_info = domain_info_.at (domain_index);
136+ }
132137 if (domain_info == NULL ) {
133138 domain_info = new DomainInfo (master_);
134139 domain_info_[domain_index] = domain_info;
@@ -210,17 +215,20 @@ void EcMaster::registerPDOInDomain(
210215 domain_info->domain_regs .back () = empty;
211216}
212217
213- void EcMaster::activate ()
218+ bool EcMaster::activate ()
214219{
215220 // register domain
216221 for (auto & iter : domain_info_) {
217222 DomainInfo * domain_info = iter.second ;
223+ if (domain_info == NULL ) {
224+ throw std::runtime_error (" Null domain info: " + std::to_string (iter.first ));
225+ }
218226 bool domain_status = ecrt_domain_reg_pdo_entry_list (
219227 domain_info->domain ,
220228 &(domain_info->domain_regs [0 ]));
221229 if (domain_status) {
222230 printWarning (" Activate. Failed to register domain PDO entries." );
223- return ;
231+ return false ;
224232 }
225233 }
226234 // set application time
@@ -232,26 +240,33 @@ void EcMaster::activate()
232240 bool activate_status = ecrt_master_activate (master_);
233241 if (activate_status) {
234242 printWarning (" Activate. Failed to activate master." );
235- return ;
243+ return false ;
236244 }
237245
238246 // retrieve domain data
239247 for (auto & iter : domain_info_) {
240248 DomainInfo * domain_info = iter.second ;
249+ if (domain_info == NULL ) {
250+ throw std::runtime_error (" Null domain info: " + std::to_string (iter.first ));
251+ }
241252 domain_info->domain_pd = ecrt_domain_data (domain_info->domain );
242253 if (domain_info->domain_pd == NULL ) {
243254 printWarning (" Activate. Failed to retrieve domain process data." );
244- return ;
255+ return false ;
245256 }
246257 }
258+ return true ;
247259}
248260
249261void EcMaster::update (uint32_t domain)
250262{
251263 // receive process data
252264 ecrt_master_receive (master_);
253265
254- DomainInfo * domain_info = domain_info_[domain];
266+ DomainInfo * domain_info = domain_info_.at (domain);
267+ if (domain_info == NULL ) {
268+ throw std::runtime_error (" Null domain info: " + std::to_string (domain));
269+ }
255270
256271 ecrt_domain_process (domain_info->domain );
257272
@@ -290,7 +305,10 @@ void EcMaster::readData(uint32_t domain)
290305 // receive process data
291306 ecrt_master_receive (master_);
292307
293- DomainInfo * domain_info = domain_info_[domain];
308+ DomainInfo * domain_info = domain_info_.at (domain);
309+ if (domain_info == NULL ) {
310+ throw std::runtime_error (" Null domain info: " + std::to_string (domain));
311+ }
294312
295313 ecrt_domain_process (domain_info->domain );
296314
@@ -315,7 +333,11 @@ void EcMaster::readData(uint32_t domain)
315333
316334void EcMaster::writeData (uint32_t domain)
317335{
318- DomainInfo * domain_info = domain_info_[domain];
336+ DomainInfo * domain_info = domain_info_.at (domain);
337+ if (domain_info == NULL ) {
338+ throw std::runtime_error (" Null domain info: " + std::to_string (domain));
339+ }
340+
319341 // read and write process data
320342 for (DomainInfo::Entry & entry : domain_info->entries ) {
321343 for (int i = 0 ; i < entry.num_pdos ; ++i) {
@@ -426,7 +448,10 @@ void EcMaster::setThreadRealTime()
426448
427449void EcMaster::checkDomainState (uint32_t domain)
428450{
429- DomainInfo * domain_info = domain_info_[domain];
451+ DomainInfo * domain_info = domain_info_.at (domain);
452+ if (domain_info == NULL ) {
453+ throw std::runtime_error (" Null domain info: " + std::to_string (domain));
454+ }
430455
431456 ec_domain_state_t ds;
432457 ecrt_domain_state (domain_info->domain , &ds);
0 commit comments