Skip to content

Commit 52be2c2

Browse files
authored
Fix Startup Crash Caused by Read() and Write() on Un-activated Ethercat (#120)
* Use at() instead of [], propagate activation failures, lock ethercat * Convert NULL domain debug to string, add additional NULL checks
1 parent 3aaca92 commit 52be2c2

File tree

4 files changed

+65
-14
lines changed

4 files changed

+65
-14
lines changed

ethercat_driver/include/ethercat_driver/ethercat_driver.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,8 @@ class EthercatDriver : public hardware_interface::SystemInterface
8484

8585
int control_frequency_;
8686
ethercat_interface::EcMaster master_;
87+
std::mutex ec_mutex_;
88+
bool activated_;
8789
};
8890
} // namespace ethercat_driver
8991

ethercat_driver/src/ethercat_driver.cpp

Lines changed: 27 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,9 @@ CallbackReturn EthercatDriver::on_init(
3030
return CallbackReturn::ERROR;
3131
}
3232

33+
const std::lock_guard<std::mutex> lock(ec_mutex_);
34+
activated_ = false;
35+
3336
hw_joint_states_.resize(info_.joints.size());
3437
for (uint j = 0; j < info_.joints.size(); j++) {
3538
hw_joint_states_[j].resize(
@@ -259,6 +262,11 @@ EthercatDriver::export_command_interfaces()
259262
CallbackReturn EthercatDriver::on_activate(
260263
const rclcpp_lifecycle::State & /*previous_state*/)
261264
{
265+
const std::lock_guard<std::mutex> lock(ec_mutex_);
266+
if (activated_) {
267+
RCLCPP_FATAL(rclcpp::get_logger("EthercatDriver"), "Double on_activate()");
268+
return CallbackReturn::ERROR;
269+
}
262270
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Starting ...please wait...");
263271
if (info_.hardware_parameters.find("control_frequency") == info_.hardware_parameters.end()) {
264272
control_frequency_ = 100;
@@ -303,7 +311,10 @@ CallbackReturn EthercatDriver::on_activate(
303311
}
304312
}
305313

306-
master_.activate();
314+
if (!master_.activate()) {
315+
RCLCPP_ERROR(rclcpp::get_logger("EthercatDriver"), "Activate EcMaster failed");
316+
return CallbackReturn::ERROR;
317+
}
307318
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Activated EcMaster!");
308319

309320
// start after one second
@@ -339,12 +350,17 @@ CallbackReturn EthercatDriver::on_activate(
339350
RCLCPP_INFO(
340351
rclcpp::get_logger("EthercatDriver"), "System Successfully started!");
341352

353+
activated_ = true;
354+
342355
return CallbackReturn::SUCCESS;
343356
}
344357

345358
CallbackReturn EthercatDriver::on_deactivate(
346359
const rclcpp_lifecycle::State & /*previous_state*/)
347360
{
361+
const std::lock_guard<std::mutex> lock(ec_mutex_);
362+
activated_ = false;
363+
348364
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Stopping ...please wait...");
349365

350366
// stop EC and disconnect
@@ -360,15 +376,23 @@ hardware_interface::return_type EthercatDriver::read(
360376
const rclcpp::Time & /*time*/,
361377
const rclcpp::Duration & /*period*/)
362378
{
363-
master_.readData();
379+
// try to lock so we can avoid blocking the read/write loop on the lock.
380+
const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
381+
if (lock.owns_lock() && activated_) {
382+
master_.readData();
383+
}
364384
return hardware_interface::return_type::OK;
365385
}
366386

367387
hardware_interface::return_type EthercatDriver::write(
368388
const rclcpp::Time & /*time*/,
369389
const rclcpp::Duration & /*period*/)
370390
{
371-
master_.writeData();
391+
// try to lock so we can avoid blocking the read/write loop on the lock.
392+
const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
393+
if (lock.owns_lock() && activated_) {
394+
master_.writeData();
395+
}
372396
return hardware_interface::return_type::OK;
373397
}
374398

ethercat_interface/include/ethercat_interface/ec_master.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ class EcMaster
4646
int configSlaveSdo(uint16_t slave_position, SdoConfigEntry sdo_config, uint32_t * abort_code);
4747

4848
/** call after adding all slaves, and before update */
49-
void activate();
49+
bool activate();
5050

5151
/** perform one EtherCAT cycle, passing the domain to the slaves */
5252
virtual void update(uint32_t domain = 0);

ethercat_interface/src/ec_master.cpp

Lines changed: 35 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -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

249261
void 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

316334
void 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

427449
void 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

Comments
 (0)