RokubiminiFactory.cpp
Go to the documentation of this file.
1 
2 
4 
10 #include <utility>
11 
12 using namespace std;
13 using namespace rokubimini::ethercat;
14 using namespace rokubimini::serial;
15 
16 namespace rokubimini
17 {
18 std::shared_ptr<rokubimini::setup::Rokubimini>
19 createRokubiminiSetup(const std::string& rokubiminiName,
20  std::vector<std::unique_ptr<RokubiminiBusManager>>& busManagers, const NodeHandlePtr& nh)
21 {
22  std::shared_ptr<rokubimini::setup::Rokubimini> rokubimini_setup;
23  busType product_code;
24  std::string product_code_string = rokubiminiName + "/setup/product_code";
25  if (nh->hasParam(product_code_string))
26  {
27  product_code = parseProductCode(product_code_string, nh);
28  switch (product_code)
29  {
30  case ETHERCAT:
31  {
32  auto ethercat_setup = make_shared<rokubimini::ethercat::setup::RokubiminiEthercat>();
33  ethercat_setup->load(rokubiminiName, nh);
34  // check TODO in doxygen.
35  bool bus_manager_found = false;
36  for (auto& bus_manager : busManagers)
37  {
38  // To check if the busManager is a
39  // RokubiminiEthercatBusManager, we use it's first
40  // attached RokubiminiSetup's productCode.
41  if (bus_manager->getRokubiminiSetups()[0]->productCode_ == ETHERCAT)
42  {
43  bus_manager->addRokubiminiSetupToList(ethercat_setup);
44  bus_manager_found = true;
45  break;
46  };
47  }
48  if (!bus_manager_found)
49  {
50  auto bus_manager = make_unique<RokubiminiEthercatBusManager>();
51  bus_manager->addRokubiminiSetupToList(ethercat_setup);
52  busManagers.push_back(move(bus_manager));
53  }
54  rokubimini_setup = static_pointer_cast<rokubimini::setup::Rokubimini>(ethercat_setup);
55  break;
56  }
57  case SERIAL:
58  {
59  auto serial_setup = make_shared<rokubimini::serial::setup::RokubiminiSerial>();
60  serial_setup->load(rokubiminiName, nh);
61  // check TODO in doxygen.
62  bool bus_manager_found = false;
63  for (auto& bus_manager : busManagers)
64  {
65  // To check if the busManager is a
66  // RokubiminiSerialBusManager, we use it's first
67  // attached RokubiminiSetup's productCode.
68  if (bus_manager->getRokubiminiSetups()[0]->productCode_ == SERIAL)
69  {
70  bus_manager->addRokubiminiSetupToList(serial_setup);
71  bus_manager_found = true;
72  break;
73  };
74  }
75  if (!bus_manager_found)
76  {
77  auto bus_manager = make_unique<RokubiminiSerialBusManager>();
78  bus_manager->addRokubiminiSetupToList(serial_setup);
79  busManagers.push_back(move(bus_manager));
80  }
81  rokubimini_setup = static_pointer_cast<rokubimini::setup::Rokubimini>(serial_setup);
82  break;
83  }
84  default:
85  ROS_ERROR("Product code of rokubimini is not valid");
86  rokubimini_setup = nullptr;
87  break;
88  }
89  }
90  else
91  {
92  ROS_ERROR("Could not find product code of one Rokubimini in the Bus Setup");
93  rokubimini_setup = nullptr;
94  }
95  return rokubimini_setup;
96 }
97 
98 busType parseProductCode(const std::string& productCode, const NodeHandlePtr& nh)
99 {
100  int product_code;
101  nh->getParam(productCode, product_code);
102  return (busType) static_cast<std::uint32_t>(product_code);
103 }
104 
105 std::shared_ptr<rokubimini::Rokubimini>
106 createRokubiminiFactory(const std::shared_ptr<rokubimini::setup::Rokubimini>& rokubiminiSetup, const NodeHandlePtr& nh)
107 {
108  std::shared_ptr<rokubimini::Rokubimini> rokubimini = nullptr;
109  auto product_code = rokubiminiSetup->productCode_;
110  switch (product_code)
111  {
112  case ETHERCAT:
113  {
114  rokubimini = make_shared<RokubiminiEthercat>();
115  rokubimini->setNodeHandle(nh);
116  break;
117  }
118  case SERIAL:
119  {
120  rokubimini = make_shared<RokubiminiSerial>();
121  rokubimini->setNodeHandle(nh);
122  break;
123  }
124  default:
125  ROS_ERROR("Product code of rokubimini with name '%s' is not valid: %u", rokubiminiSetup->name_.c_str(),
126  rokubiminiSetup->productCode_);
127  break;
128  }
129  return rokubimini;
130 }
132  std::vector<unique_ptr<RokubiminiBusManager>>& busManagers, const NodeHandlePtr& nh)
133 {
134  ROS_INFO("Loading bus setup");
135  try
136  {
137  std::vector<std::string> keys;
138  std::string rokubimini_name;
139  // Clear the rokubiminis first.
140  setup->rokubiminis_.clear();
141  nh->getParamNames(keys);
142 
143  for (const auto& key : keys)
144  {
145  // append only parameter names starting with "/rokubimini" and have "/setup/name"
146  if (key.find("/rokubimini") == 0 && key.find("/setup/name") != std::string::npos)
147  {
148  nh->getParam(key, rokubimini_name);
149  ROS_DEBUG("Key is: %s and name is: %s", key.c_str(), rokubimini_name.c_str());
150  auto rokubimini = createRokubiminiSetup(rokubimini_name, busManagers, nh);
151  ROS_DEBUG("New rokubimini with name: %s and product code: %u", rokubimini->name_.c_str(),
152  rokubimini->productCode_);
153  setup->rokubiminis_.push_back(rokubimini);
154  }
155  }
156  ROS_DEBUG("Number of bus managers: %zu", busManagers.size());
157  ROS_DEBUG("Number of RokubiminiSetups: %zu", setup->rokubiminis_.size());
158  }
159  catch (const ros::Exception& exception)
160  {
161  ROS_ERROR_STREAM("Caught an exception while loading the setup: " << exception.what());
162  return false;
163  }
164  return true;
165 }
166 
168 {
170 }
171 rokubimini::setup::SetupPtr loadBusSetup(std::vector<std::unique_ptr<RokubiminiBusManager>>& busManagers,
172  const NodeHandlePtr& nh)
173 {
174  auto setup = createSetup();
175  if (!loadBusSetupFromParamServer(setup, busManagers, nh))
176  {
177  ROS_ERROR("Could not load Bus Setup!");
178  return nullptr;
179  }
180  return setup;
181 }
182 
183 } // namespace rokubimini
busType parseProductCode(const std::string &productCode, const NodeHandlePtr &nh)
#define ROS_INFO(...)
std::shared_ptr< Setup > SetupPtr
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
rokubimini::setup::SetupPtr createSetup()
Creates an empty generic Setup. This will have in a list all the Rokubimini Setups.
enum rokubimini::BusType busType
std::shared_ptr< rokubimini::setup::Rokubimini > createRokubiminiSetup(const std::string &rokubiminiName, std::vector< std::unique_ptr< RokubiminiBusManager >> &busManagers, const NodeHandlePtr &nh)
#define ROS_ERROR_STREAM(args)
std::shared_ptr< rokubimini::Rokubimini > createRokubiminiFactory(const std::shared_ptr< rokubimini::setup::Rokubimini > &rokubiminiSetup, const NodeHandlePtr &nh)
#define ROS_ERROR(...)
rokubimini::setup::SetupPtr loadBusSetup(std::vector< std::unique_ptr< RokubiminiBusManager >> &busManagers, const NodeHandlePtr &nh)
bool loadBusSetupFromParamServer(const rokubimini::setup::SetupPtr &setup, std::vector< unique_ptr< RokubiminiBusManager >> &busManagers, const NodeHandlePtr &nh)
#define ROS_DEBUG(...)


rokubimini_factory
Author(s):
autogenerated on Wed Mar 3 2021 03:09:19