18 std::shared_ptr<rokubimini::setup::Rokubimini>
20 std::vector<std::unique_ptr<RokubiminiBusManager>>& busManagers,
const NodeHandlePtr& nh)
22 std::shared_ptr<rokubimini::setup::Rokubimini> rokubimini_setup;
24 std::string product_code_string = rokubiminiName +
"/setup/product_code";
25 if (nh->hasParam(product_code_string))
32 auto ethercat_setup = make_shared<rokubimini::ethercat::setup::RokubiminiEthercat>();
33 ethercat_setup->load(rokubiminiName, nh);
35 bool bus_manager_found =
false;
36 for (
auto& bus_manager : busManagers)
41 if (bus_manager->getRokubiminiSetups()[0]->productCode_ ==
ETHERCAT)
43 bus_manager->addRokubiminiSetupToList(ethercat_setup);
44 bus_manager_found =
true;
48 if (!bus_manager_found)
50 auto bus_manager = make_unique<RokubiminiEthercatBusManager>();
51 bus_manager->addRokubiminiSetupToList(ethercat_setup);
52 busManagers.push_back(move(bus_manager));
59 auto serial_setup = make_shared<rokubimini::serial::setup::RokubiminiSerial>();
60 serial_setup->load(rokubiminiName, nh);
62 bool bus_manager_found =
false;
63 for (
auto& bus_manager : busManagers)
68 if (bus_manager->getRokubiminiSetups()[0]->productCode_ ==
SERIAL)
70 bus_manager->addRokubiminiSetupToList(serial_setup);
71 bus_manager_found =
true;
75 if (!bus_manager_found)
77 auto bus_manager = make_unique<RokubiminiSerialBusManager>();
78 bus_manager->addRokubiminiSetupToList(serial_setup);
79 busManagers.push_back(move(bus_manager));
85 ROS_ERROR(
"Product code of rokubimini is not valid");
86 rokubimini_setup =
nullptr;
92 ROS_ERROR(
"Could not find product code of one Rokubimini in the Bus Setup");
93 rokubimini_setup =
nullptr;
95 return rokubimini_setup;
101 nh->getParam(productCode, product_code);
102 return (
busType)
static_cast<std::uint32_t
>(product_code);
105 std::shared_ptr<rokubimini::Rokubimini>
108 std::shared_ptr<rokubimini::Rokubimini>
rokubimini =
nullptr;
109 auto product_code = rokubiminiSetup->productCode_;
110 switch (product_code)
114 rokubimini = make_shared<RokubiminiEthercat>();
115 rokubimini->setNodeHandle(nh);
120 rokubimini = make_shared<RokubiminiSerial>();
121 rokubimini->setNodeHandle(nh);
125 ROS_ERROR(
"Product code of rokubimini with name '%s' is not valid: %u", rokubiminiSetup->name_.c_str(),
126 rokubiminiSetup->productCode_);
132 std::vector<unique_ptr<RokubiminiBusManager>>& busManagers,
const NodeHandlePtr& nh)
137 std::vector<std::string> keys;
138 std::string rokubimini_name;
140 setup->rokubiminis_.clear();
141 nh->getParamNames(keys);
143 for (
const auto& key : keys)
146 if (key.find(
"/rokubimini") == 0 && key.find(
"/setup/name") != std::string::npos)
148 nh->getParam(key, rokubimini_name);
149 ROS_DEBUG(
"Key is: %s and name is: %s", key.c_str(), rokubimini_name.c_str());
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);
156 ROS_DEBUG(
"Number of bus managers: %zu", busManagers.size());
157 ROS_DEBUG(
"Number of RokubiminiSetups: %zu", setup->rokubiminis_.size());
161 ROS_ERROR_STREAM(
"Caught an exception while loading the setup: " << exception.what());
busType parseProductCode(const std::string &productCode, const NodeHandlePtr &nh)
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)
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)