Skip to content

Commit

Permalink
Convert NULL domain debug to string, add additional NULL checks
Browse files Browse the repository at this point in the history
  • Loading branch information
tony-laza committed May 1, 2024
1 parent 7dd8957 commit af7a7e4
Showing 1 changed file with 17 additions and 3 deletions.
20 changes: 17 additions & 3 deletions ethercat_interface/src/ec_master.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,9 @@ EcMaster::~EcMaster()
//
}
for (auto & domain : domain_info_) {
delete domain.second;
if (domain.second != NULL) {
delete domain.second;
}
}
}

Expand Down Expand Up @@ -218,6 +220,9 @@ bool EcMaster::activate()
// register domain
for (auto & iter : domain_info_) {
DomainInfo * domain_info = iter.second;
if (domain_info == NULL) {
throw std::runtime_error("Null domain info: " + std::to_string(iter.first));
}
bool domain_status = ecrt_domain_reg_pdo_entry_list(
domain_info->domain,
&(domain_info->domain_regs[0]));
Expand All @@ -241,6 +246,9 @@ bool EcMaster::activate()
// retrieve domain data
for (auto & iter : domain_info_) {
DomainInfo * domain_info = iter.second;
if (domain_info == NULL) {
throw std::runtime_error("Null domain info: " + std::to_string(iter.first));
}
domain_info->domain_pd = ecrt_domain_data(domain_info->domain);
if (domain_info->domain_pd == NULL) {
printWarning("Activate. Failed to retrieve domain process data.");
Expand All @@ -256,6 +264,9 @@ void EcMaster::update(uint32_t domain)
ecrt_master_receive(master_);

DomainInfo * domain_info = domain_info_.at(domain);
if (domain_info == NULL) {
throw std::runtime_error("Null domain info: " + std::to_string(domain));
}

ecrt_domain_process(domain_info->domain);

Expand Down Expand Up @@ -296,7 +307,7 @@ void EcMaster::readData(uint32_t domain)

DomainInfo * domain_info = domain_info_.at(domain);
if (domain_info == NULL) {
throw std::runtime_error("Null domain info " + domain);
throw std::runtime_error("Null domain info: " + std::to_string(domain));
}

ecrt_domain_process(domain_info->domain);
Expand Down Expand Up @@ -324,7 +335,7 @@ void EcMaster::writeData(uint32_t domain)
{
DomainInfo * domain_info = domain_info_.at(domain);
if (domain_info == NULL) {
throw std::runtime_error("Null domain info " + domain);
throw std::runtime_error("Null domain info: " + std::to_string(domain));
}

// read and write process data
Expand Down Expand Up @@ -438,6 +449,9 @@ void EcMaster::setThreadRealTime()
void EcMaster::checkDomainState(uint32_t domain)
{
DomainInfo * domain_info = domain_info_.at(domain);
if (domain_info == NULL) {
throw std::runtime_error("Null domain info: " + std::to_string(domain));
}

ec_domain_state_t ds;
ecrt_domain_state(domain_info->domain, &ds);
Expand Down

0 comments on commit af7a7e4

Please sign in to comment.