13 std::string ethercat_bus_string = rokubiminiName +
"/setup/ethercat_bus";
14 if (nh->hasParam(ethercat_bus_string))
20 ROS_ERROR(
"Could not find ethercat bus in Parameter Server: %s", ethercat_bus_string.c_str());
23 std::string ethercat_address_string = rokubiminiName +
"/setup/ethercat_address";
24 if (nh->hasParam(ethercat_address_string))
27 nh->getParam(ethercat_address_string, ethercat_address);
28 if (ethercat_address <= 0)
30 throw ros::Exception(
"The EtherCAT address is not a positive number");
36 ROS_ERROR(
"Could not find ethercat address in Parameter Server: %s", ethercat_address_string.c_str());
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
virtual void load(const std::string &rokubiminiName, NodeHandlePtr nh)
void load(const std::string &rokubiminiName, NodeHandlePtr nh) override
Loads the sensor configuration from the parameter server.
uint32_t ethercatAddress_
The ethercat address.
std::string ethercatBus_
The ethercat bus name.