Go to the documentation of this file.
18 using namespace soem_interface;
71 bool startupCommunication()
override;
76 void setBusSafeOperational();
81 void setBusPreOperational();
86 void setBusOperational();
96 void waitForState(
const uint16_t state,
const uint16_t slave = 0,
const unsigned int maxRetries = 40,
97 const double retrySleep = 0.001);
102 void readBus()
override;
107 void writeToBus()
override;
112 void shutdownBus()
override;
131 bool addRokubiminiToBus(
const std::shared_ptr<RokubiminiEthercat>&
rokubimini,
143 void setConfigMode()
override;
156 void setRunMode()
override;
169 bool createRokubimini(
const std::string& rokubiminiName)
override;
177 bool loadBusParameters()
override;
185 double loadTimeStep()
override;
210 std::unique_ptr<rokubimini::soem_interface::EthercatBusBase>
bus_;
std::recursive_mutex busMutex_
Mutex prohibiting simultaneous access to EtherCAT bus manager.
std::string ethercatBusName_
The name of the Ethercat bus.
virtual bool addRokubiminiToBus(const std::shared_ptr< Rokubimini > &rokubimini) const
void publishBusManagerRosDiagnostics() override
Publish the ROS Diagnostics of the Bus Manager.
std::unique_ptr< rokubimini::soem_interface::EthercatBusBase > bus_
The Ethercat bus instance.
Inherits from RokubiminiBusManager. It's used for managing an Ethercat bus.
RokubiminiEthercatBusManager(const NodeHandlePtr &nh)
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
std::shared_ptr< RokubiminiEthercatBusManager > RokubiminiEthercatBusManagerPtr
RokubiminiEthercatBusManager(const std::string &busName, NodeHandlePtr nh)
Constructor with initialization list for the name and NodeHandle.
Class for managing an ethercat bus containing one or multiple slaves.