12 bool BotaDeviceDriver::init()
14 const bool is_standalone =
false;
15 const bool install_signal_handler =
false;
17 std::string setup_file;
18 nh_->param<
double>(
"time_step", time_step, 0.01);
19 nh_->param<std::string>(
"rokubimini_setup_file", setup_file,
"");
21 rokubiminiManager_ = std::make_unique<RokubiminiManager>(is_standalone, install_signal_handler, time_step, nh_);
23 if (!rokubiminiManager_->loadSetup())
28 if (!rokubiminiManager_->startup())
33 rokubiminiManager_->setNodeHandle(nh_);
34 rokubiminiManager_->createRokubiminiRosPublishers();
35 rokubiminiManager_->createRokubiminiRosServices();
36 std::vector<std::shared_ptr<Rokubimini>> rokubiminis;
38 rokubiminis = rokubiminiManager_->getRokubiminis();
39 if (rokubiminis.empty())
46 options.
callback_ = std::bind(&BotaDeviceDriver::update,
this, std::placeholders::_1);
48 options.
name_ =
"BotaDeviceDriver::updateWorker";
50 int minimumft_sampling_rate = std::numeric_limits<int>::max();
56 rokubimini->getForceTorqueSamplingRate(ft_sampling_rate);
57 minimumft_sampling_rate = std::min(minimumft_sampling_rate, ft_sampling_rate);
61 if (time_step <= 0.000001)
63 options.
timeStep_ = 1.0 /
static_cast<float>(minimumft_sampling_rate);
72 if (!this->addWorker(options))
77 ROS_DEBUG(
"Finished initializing device driver");
83 ROS_DEBUG(
"[BotaDeviceDriver]: update called");
84 rokubiminiManager_->updateCommunicationManagerReadMessages();
85 rokubiminiManager_->updateProcessReadings();
87 rokubiminiManager_->updateCommunicationManagerWriteMessages();
89 rokubiminiManager_->publishRosMessages();
93 void BotaDeviceDriver::cleanup()
95 rokubiminiManager_->shutdown();