RokubiminiEthercatBusManager.cpp
Go to the documentation of this file.
2 #include <thread>
3 namespace rokubimini
4 {
5 namespace ethercat
6 {
8 {
9  double time_step;
10  if (!nh_->getParam("time_step", time_step))
11  {
12  ROS_INFO("[%s] Could not find the 'time_step' parameter in Parameter Server. Setting it to minimum sampling rate.",
13  name_.c_str());
14 
15  int minimumft_sampling_rate = std::numeric_limits<int>::max();
16  /* the following function has to be after setting the filter in order Sampling rate Object to be updated.
17  * The filters are set inside the startup function above */
18  for (const auto& rokubimini : rokubiminis_)
19  {
20  int ft_sampling_rate;
21  rokubimini->getForceTorqueSamplingRate(ft_sampling_rate);
22  auto rokubimini_ethercat = std::dynamic_pointer_cast<RokubiminiEthercat>(rokubimini);
23  rokubimini_ethercat->setRunsAsync(true);
24  minimumft_sampling_rate = std::min(minimumft_sampling_rate, ft_sampling_rate);
25  }
26  time_step = 1.0 / static_cast<float>(minimumft_sampling_rate);
27  }
28  else
29  {
30  ROS_WARN_STREAM("[" << name_.c_str() << "] Starting publishing worker at " << 1.0 / time_step
31  << " Hz, based on time step.");
32  }
33  return time_step;
34 }
35 bool RokubiminiEthercatBusManager::createRokubimini(const std::string& rokubiminiName)
36 {
37  auto rokubimini = std::make_shared<RokubiminiEthercat>(rokubiminiName, nh_);
38  rokubimini->load();
39  rokubiminis_.emplace_back(rokubimini);
40  // Create a new bus.
42  bus_ = std::unique_ptr<rokubimini::soem_interface::EthercatBusBase>(bus);
43  if (!addRokubiminiToBus(rokubimini, bus))
44  {
45  ROS_ERROR("[%s] Could not add rokubimini to bus", name_.c_str());
46  return false;
47  }
48  return true;
49 }
50 
52 {
53  std::string ethercat_bus_string = "ethercat_bus";
54  if (nh_->hasParam(ethercat_bus_string))
55  {
56  nh_->getParam(ethercat_bus_string, ethercatBusName_);
57  }
58  else
59  {
60  ROS_ERROR("[%s] Could not find ethercat bus in Parameter Server: %s", name_.c_str(), ethercat_bus_string.c_str());
61  return false;
62  }
63  return true;
64 }
65 
66 bool RokubiminiEthercatBusManager::addRokubiminiToBus(const std::shared_ptr<RokubiminiEthercat>& rokubimini,
68 {
69  std::string ethercat_address_string = "rokubiminis/" + rokubimini->getName() + "/ethercat_address";
70  uint32_t ethercat_addr;
71  if (nh_->hasParam(ethercat_address_string))
72  {
73  int ethercat_address;
74  nh_->getParam(ethercat_address_string, ethercat_address);
75  if (ethercat_address <= 0)
76  {
77  throw ros::Exception("The EtherCAT address is not a positive number");
78  }
79  ethercat_addr = static_cast<uint32_t>(ethercat_address);
80  }
81  else
82  {
83  ROS_ERROR("Could not find ethercat address in Parameter Server: %s", ethercat_address_string.c_str());
84  return false;
85  }
86  PdoTypeEnum ethercat_pdo_enum = PdoTypeEnum::A;
87  auto slave = std::make_shared<RokubiminiEthercatSlave>(rokubimini->getName(), bus, ethercat_addr, ethercat_pdo_enum);
88  slave->setProductName(rokubimini->getProductName());
89  if (!bus->addSlave(slave))
90  {
91  return false;
92  }
93 
94  rokubimini->setSlavePointer(slave);
95  return true;
96 }
97 
99 {
101  // Sleep for some time to give the slave time to execute the pre-op cb
102  std::this_thread::sleep_for(std::chrono::milliseconds(500));
103 }
105 {
108 }
109 
111 {
112  bool success = startupCommunication();
114  return success;
115 }
116 
118 {
119  std::lock_guard<std::recursive_mutex> lock(busMutex_);
120  // Only set the state but do not wait for it, since some devices (e.g. junctions) might not be able to reach it.
121  bus_->setState(EC_STATE_OPERATIONAL);
122 }
123 
125 {
126  std::lock_guard<std::recursive_mutex> lock(busMutex_);
127  // Only set the state but do not wait for it, since some devices (e.g. junctions) might not be able to reach it.
128  bus_->setState(EC_STATE_PRE_OP);
129 }
130 
132 {
133  std::lock_guard<std::recursive_mutex> lock(busMutex_);
134  // Only set the state but do not wait for it, since some devices (e.g. junctions) might not be able to reach it.
135  bus_->setState(EC_STATE_SAFE_OP);
136 }
137 
139  const unsigned int maxRetries, const double retrySleep)
140 {
141  std::lock_guard<std::recursive_mutex> lock(busMutex_);
142  bus_->waitForState(state, slave, maxRetries, retrySleep);
143 }
144 
146 {
147  std::lock_guard<std::recursive_mutex> lock(busMutex_);
148  if (!bus_->startup())
149  {
150  ROS_ERROR("Failed to startup bus %s.", ethercatBusName_.c_str());
151  return false;
152  }
153  return true;
154 }
155 
157 {
158  std::lock_guard<std::recursive_mutex> lock(busMutex_);
159  bus_->updateRead();
160 }
161 
163 {
164  std::lock_guard<std::recursive_mutex> lock(busMutex_);
165  bus_->updateWrite();
166 }
167 
169 {
170  std::lock_guard<std::recursive_mutex> lock(busMutex_);
171  bus_->shutdown();
172 }
173 
174 } // namespace ethercat
175 } // namespace rokubimini
rokubimini::ethercat::RokubiminiEthercatBusManager::readBus
void readBus() override
Calls update read on the bus.
Definition: RokubiminiEthercatBusManager.cpp:156
rokubimini::ethercat::RokubiminiEthercatBusManager::createRokubimini
bool createRokubimini(const std::string &rokubiminiName) override
Creates an RokubiminiEthercat instance.
Definition: RokubiminiEthercatBusManager.cpp:35
slave
int slave
rokubimini::RokubiminiBusManager::rokubiminis_
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
rokubimini::ethercat::RokubiminiEthercatBusManager::startupBus
bool startupBus()
Starts up the bus and puts them in operational mode.
Definition: RokubiminiEthercatBusManager.cpp:110
rokubimini::ethercat::RokubiminiEthercatBusManager::busMutex_
std::recursive_mutex busMutex_
Mutex prohibiting simultaneous access to EtherCAT bus manager.
Definition: RokubiminiEthercatBusManager.hpp:203
rokubimini::RokubiminiBusManager::name_
std::string name_
uint16_t
unsigned short uint16_t
rokubimini::ethercat::RokubiminiEthercatBusManager::startupCommunication
bool startupCommunication() override
Starts up the bus.
Definition: RokubiminiEthercatBusManager.cpp:145
rokubimini::ethercat::RokubiminiEthercatBusManager::shutdownBus
void shutdownBus() override
Calls shutdown on the bus.
Definition: RokubiminiEthercatBusManager.cpp:168
rokubimini::soem_interface::EthercatBusBase::addSlave
bool addSlave(const EthercatSlaveBasePtr &slave)
Definition: EthercatBusBase.cpp:61
rokubimini::ethercat::PdoTypeEnum::A
@ A
ros::Exception
rokubimini::RokubiminiBusManager::nh_
NodeHandlePtr nh_
EC_STATE_SAFE_OP
EC_STATE_SAFE_OP
rokubimini::ethercat::RokubiminiEthercatBusManager::ethercatBusName_
std::string ethercatBusName_
The name of the Ethercat bus.
Definition: RokubiminiEthercatBusManager.hpp:218
rokubimini::ethercat::PdoTypeEnum
PdoTypeEnum
Definition: PdoTypeEnum.hpp:8
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
EC_STATE_PRE_OP
EC_STATE_PRE_OP
uint32_t
unsigned int uint32_t
rokubimini
RokubiminiEthercatBusManager.hpp
rokubimini::ethercat::RokubiminiEthercatBusManager::bus_
std::unique_ptr< rokubimini::soem_interface::EthercatBusBase > bus_
The Ethercat bus instance.
Definition: RokubiminiEthercatBusManager.hpp:210
rokubimini::ethercat::RokubiminiEthercatBusManager::setBusPreOperational
void setBusPreOperational()
Sets bus to pre operational state.
Definition: RokubiminiEthercatBusManager.cpp:124
rokubimini::ethercat::RokubiminiEthercatBusManager::addRokubiminiToBus
bool addRokubiminiToBus(const std::shared_ptr< RokubiminiEthercat > &rokubimini, rokubimini::soem_interface::EthercatBusBase *bus) const
Adds a Rokubimini to Bus.
Definition: RokubiminiEthercatBusManager.cpp:66
rokubimini::ethercat::RokubiminiEthercatBusManager::setBusSafeOperational
void setBusSafeOperational()
Sets bus to safe operational state.
Definition: RokubiminiEthercatBusManager.cpp:131
ROS_ERROR
#define ROS_ERROR(...)
rokubimini::ethercat::RokubiminiEthercatBusManager::waitForState
void waitForState(const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
Waits for the slave to reach a state.
Definition: RokubiminiEthercatBusManager.cpp:138
rokubimini::ethercat::RokubiminiEthercatBusManager::setRunMode
void setRunMode() override
Definition: RokubiminiEthercatBusManager.cpp:104
rokubimini::ethercat::RokubiminiEthercatBusManager::loadBusParameters
bool loadBusParameters() override
Loads ethercat bus parameters from parameter server.
Definition: RokubiminiEthercatBusManager.cpp:51
rokubimini::ethercat::RokubiminiEthercatBusManager::writeToBus
void writeToBus() override
Calls update write on the bus.
Definition: RokubiminiEthercatBusManager.cpp:162
ROS_INFO
#define ROS_INFO(...)
rokubimini::soem_interface::EthercatBusBase
Class for managing an ethercat bus containing one or multiple slaves.
Definition: EthercatBusBase.hpp:28
rokubimini::ethercat::RokubiminiEthercatBusManager::setBusOperational
void setBusOperational()
Sets bus to operational state.
Definition: RokubiminiEthercatBusManager.cpp:117
rokubimini::ethercat::RokubiminiEthercatBusManager::loadTimeStep
double loadTimeStep() override
Loads the time_step from the Parameter Server.
Definition: RokubiminiEthercatBusManager.cpp:7
EC_STATE_OPERATIONAL
EC_STATE_OPERATIONAL
rokubimini::ethercat::RokubiminiEthercatBusManager::setConfigMode
void setConfigMode() override
Definition: RokubiminiEthercatBusManager.cpp:98


rokubimini_ethercat
Author(s):
autogenerated on Sat Apr 15 2023 02:53:56