setup/RokubiminiEthercat.cpp
Go to the documentation of this file.
1 // rokubimini
3 
4 namespace rokubimini
5 {
6 namespace ethercat
7 {
8 namespace setup
9 {
10 void RokubiminiEthercat::load(const std::string& rokubiminiName, NodeHandlePtr nh)
11 {
12  Rokubimini::load(rokubiminiName, nh);
13  std::string ethercat_bus_string = rokubiminiName + "/setup/ethercat_bus";
14  if (nh->hasParam(ethercat_bus_string))
15  {
16  nh->getParam(ethercat_bus_string, ethercatBus_);
17  }
18  else
19  {
20  ROS_ERROR("Could not find ethercat bus in Parameter Server: %s", ethercat_bus_string.c_str());
21  }
22 
23  std::string ethercat_address_string = rokubiminiName + "/setup/ethercat_address";
24  if (nh->hasParam(ethercat_address_string))
25  {
26  int ethercat_address;
27  nh->getParam(ethercat_address_string, ethercat_address);
28  if (ethercat_address <= 0)
29  {
30  throw ros::Exception("The EtherCAT address is not a positive number");
31  }
32  ethercatAddress_ = static_cast<uint32_t>(ethercat_address);
33  }
34  else
35  {
36  ROS_ERROR("Could not find ethercat address in Parameter Server: %s", ethercat_address_string.c_str());
37  }
38 }
39 } // namespace setup
40 } // namespace ethercat
41 } // namespace rokubimini
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.
unsigned int uint32_t
#define ROS_ERROR(...)


rokubimini_ethercat
Author(s):
autogenerated on Wed Mar 3 2021 03:09:16