Skip to content

Warning fixes #177

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class EthercatDriver : public hardware_interface::SystemInterface
"ethercat_interface", "ethercat_interface::EcSlave"};

int control_frequency_;
ethercat_interface::EcMaster master_;
std::unique_ptr<ethercat_interface::EcMaster> master_;
std::mutex ec_mutex_;
bool activated_;
};
Expand Down
31 changes: 22 additions & 9 deletions ethercat_driver/src/ethercat_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,16 @@ CallbackReturn EthercatDriver::on_init(
const std::lock_guard<std::mutex> lock(ec_mutex_);
activated_ = false;

// Parse master_id from hardware parameters
int master_id = 0; // Default to 0 if not specified
if (info_.hardware_parameters.find("master_id") != info_.hardware_parameters.end()) {
master_id = std::stoi(info_.hardware_parameters["master_id"]);
}
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Master ID: %d", master_id);

// Initialize master with the specified ID
master_ = std::make_unique<ethercat_interface::EcMaster>(master_id);

hw_joint_states_.resize(info_.joints.size());
for (uint j = 0; j < info_.joints.size(); j++) {
hw_joint_states_[j].resize(
Expand Down Expand Up @@ -282,10 +292,10 @@ CallbackReturn EthercatDriver::on_activate(

// start EC and wait until state operative

master_.setCtrlFrequency(control_frequency_);
master_->setCtrlFrequency(control_frequency_);

for (auto i = 0ul; i < ec_modules_.size(); i++) {
master_.addSlave(
master_->addSlave(
std::stod(ec_module_parameters_[i]["alias"]),
std::stod(ec_module_parameters_[i]["position"]),
ec_modules_[i].get());
Expand All @@ -295,7 +305,7 @@ CallbackReturn EthercatDriver::on_activate(
for (auto i = 0ul; i < ec_modules_.size(); i++) {
for (auto & sdo : ec_modules_[i]->sdo_config) {
uint32_t abort_code;
int ret = master_.configSlaveSdo(
int ret = master_->configSlaveSdo(
std::stod(ec_module_parameters_[i]["position"]),
sdo,
&abort_code
Expand All @@ -311,7 +321,7 @@ CallbackReturn EthercatDriver::on_activate(
}
}

if (!master_.activate()) {
if (!master_->activate()) {
RCLCPP_ERROR(rclcpp::get_logger("EthercatDriver"), "Activate EcMaster failed");
return CallbackReturn::ERROR;
}
Expand All @@ -328,7 +338,7 @@ CallbackReturn EthercatDriver::on_activate(
clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &t, NULL);
// update EtherCAT bus

master_.update();
master_->update();
RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "updated!");

// check if operational
Expand All @@ -340,7 +350,7 @@ CallbackReturn EthercatDriver::on_activate(
running = false;
}
// calculate next shot. carry over nanoseconds into microseconds.
t.tv_nsec += master_.getInterval();
t.tv_nsec += master_->getInterval();
while (t.tv_nsec >= 1000000000) {
t.tv_nsec -= 1000000000;
t.tv_sec++;
Expand All @@ -363,8 +373,11 @@ CallbackReturn EthercatDriver::on_deactivate(

RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Stopping ...please wait...");

// Clean up all modules before stopping the master
ec_modules_.clear();

// stop EC and disconnect
master_.stop();
master_->stop();

RCLCPP_INFO(
rclcpp::get_logger("EthercatDriver"), "System successfully stopped!");
Expand All @@ -379,7 +392,7 @@ hardware_interface::return_type EthercatDriver::read(
// try to lock so we can avoid blocking the read/write loop on the lock.
const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
if (lock.owns_lock() && activated_) {
master_.readData();
master_->readData();
}
return hardware_interface::return_type::OK;
}
Expand All @@ -391,7 +404,7 @@ hardware_interface::return_type EthercatDriver::write(
// try to lock so we can avoid blocking the read/write loop on the lock.
const std::unique_lock<std::mutex> lock(ec_mutex_, std::try_to_lock);
if (lock.owns_lock() && activated_) {
master_.writeData();
master_->writeData();
}
return hardware_interface::return_type::OK;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ size_t type2bytes(std::string type)
} else if (type == "int64" || type == "uint64") {
return 8;
}
return 0;
}

namespace ethercat_generic_plugins
Expand Down Expand Up @@ -67,20 +68,22 @@ void GenericEcSlave::setup_syncs()
if (sm_configs_.size() == 0) {
syncs_.push_back({0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE});
syncs_.push_back({1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE});
syncs_.push_back({2, EC_DIR_OUTPUT, rpdos_.size(), rpdos_.data(), EC_WD_ENABLE});
syncs_.push_back({3, EC_DIR_INPUT, tpdos_.size(), tpdos_.data(), EC_WD_DISABLE});
syncs_.push_back({2, EC_DIR_OUTPUT, static_cast<unsigned int>(rpdos_.size()), rpdos_.data(), EC_WD_ENABLE});
syncs_.push_back({3, EC_DIR_INPUT, static_cast<unsigned int>(tpdos_.size()), tpdos_.data(), EC_WD_DISABLE});
} else {
for (auto & sm : sm_configs_) {
if (sm.pdo_name == "null") {
syncs_.push_back({sm.index, sm.type, 0, NULL, sm.watchdog});
} else if (sm.pdo_name == "rpdo") {
syncs_.push_back({sm.index, sm.type, rpdos_.size(), rpdos_.data(), sm.watchdog});
syncs_.push_back({sm.index, sm.type, static_cast<unsigned int>(rpdos_.size()), rpdos_.data(), sm.watchdog});
} else if (sm.pdo_name == "tpdo") {
syncs_.push_back({sm.index, sm.type, tpdos_.size(), tpdos_.data(), sm.watchdog});
syncs_.push_back({sm.index, sm.type, static_cast<unsigned int>(tpdos_.size()), tpdos_.data(), sm.watchdog});
}
}
}
syncs_.push_back({0xff});
//syncs_.push_back({0xff});
syncs_.push_back(ec_sync_info_t{0xff, EC_DIR_INPUT, 0, nullptr, EC_WD_DISABLE});

}

bool GenericEcSlave::setupSlave(
Expand Down Expand Up @@ -173,7 +176,7 @@ bool GenericEcSlave::setup_from_config(YAML::Node slave_config)
rpdos_.push_back(
{
slave_config["rpdo"][i]["index"].as<uint16_t>(),
rpdo_channels_size,
static_cast<unsigned int>(rpdo_channels_size),
all_channels_.data() + channels_nbr
}
);
Expand All @@ -195,7 +198,7 @@ bool GenericEcSlave::setup_from_config(YAML::Node slave_config)
tpdos_.push_back(
{
slave_config["tpdo"][i]["index"].as<uint16_t>(),
tpdo_channels_size,
static_cast<unsigned int>(tpdo_channels_size),
all_channels_.data() + channels_nbr
}
);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ class EcMaster
{
EcSlave * slave = NULL;
ec_slave_config_t * config = NULL;
ec_slave_config_state_t config_state = {0};
ec_slave_config_state_t config_state{};
};

std::vector<SlaveInfo> slave_info_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ class SdoConfigEntry
} else if (type == "int64" || type == "uint64") {
return 8;
}
return 0;
}
};

Expand Down
12 changes: 6 additions & 6 deletions ethercat_interface/src/ec_master.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ EcMaster::DomainInfo::DomainInfo(ec_master_t * master)
return;
}

const ec_pdo_entry_reg_t empty = {0};
const ec_pdo_entry_reg_t empty{};
domain_regs.push_back(empty);
}

Expand All @@ -66,7 +66,7 @@ EcMaster::EcMaster(const int master)

EcMaster::~EcMaster()
{
for (SlaveInfo & slave : slave_info_) {
for ([[maybe_unused]] SlaveInfo & slave : slave_info_) {
//
}
for (auto & domain : domain_info_) {
Expand Down Expand Up @@ -211,7 +211,7 @@ void EcMaster::registerPDOInDomain(
}

// set the last element to null
ec_pdo_entry_reg_t empty = {0};
ec_pdo_entry_reg_t empty{};
domain_info->domain_regs.back() = empty;
}

Expand Down Expand Up @@ -441,9 +441,9 @@ void EcMaster::setThreadRealTime()
/* Pre-fault our stack
8*1024 is the maximum stack size
which is guaranteed safe to access without faulting */
int MAX_SAFE_STACK = 8 * 1024;
unsigned char dummy[MAX_SAFE_STACK];
memset(dummy, 0, MAX_SAFE_STACK);
constexpr int MAX_SAFE_STACK = 8 * 1024;
unsigned char dummy[MAX_SAFE_STACK]{};
//memset(dummy, 0, MAX_SAFE_STACK);
}

void EcMaster::checkDomainState(uint32_t domain)
Expand Down