diff --git a/include/dynamic_graph_bridge/sot_loader.hh b/include/dynamic_graph_bridge/sot_loader.hh index 53f88d4f8a66761a68e28cc2b5f4b7ec2781d712..33d7a273ab63185ccf5b7ebbaed3de8db6440fdc 100644 --- a/include/dynamic_graph_bridge/sot_loader.hh +++ b/include/dynamic_graph_bridge/sot_loader.hh @@ -88,7 +88,7 @@ class SotLoader : public SotLoaderBasic { // \brief Compute one iteration of control. // Basically calls fillSensors, the SoT and the readControl. - void oneIteration(); + void oneIteration(const double& period); // \brief Fill the sensors value for the SoT. void fillSensors(std::map<std::string, dgs::SensorValues> &sensorsIn); diff --git a/src/sot_loader.cpp b/src/sot_loader.cpp index 09a68c8b7b9c4f5bea8e6d1dd1da0ac04010dea8..24627863d597e3dda184c49185f5ec2a84222f7a 100644 --- a/src/sot_loader.cpp +++ b/src/sot_loader.cpp @@ -59,8 +59,9 @@ struct DataToLog { void workThreadLoader(SotLoader *aSotLoader) { ros::Rate rate(1000); // 1 kHz + double periodd (1e-3); + if (ros::param::has("/sot_controller/dt")) { - double periodd; ros::param::get("/sot_controller/dt", periodd); rate = ros::Rate(1 / periodd); } @@ -80,7 +81,7 @@ void workThreadLoader(SotLoader *aSotLoader) { if (!paused) { time = ros::Time::now(); - aSotLoader->oneIteration(); + aSotLoader->oneIteration(periodd); ros::Duration d = ros::Time::now() - time; dataToLog.record((time - timeOrigin).toSec(), d.toSec()); @@ -200,15 +201,15 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) { void SotLoader::setup() { fillSensors(sensorsIn_); sotController_->setupSetSensors(sensorsIn_); - sotController_->getControl(controlValues_); + sotController_->getControl(controlValues_, 0); readControl(controlValues_); } -void SotLoader::oneIteration() { +void SotLoader::oneIteration(const double& period) { fillSensors(sensorsIn_); try { sotController_->nominalSetSensors(sensorsIn_); - sotController_->getControl(controlValues_); + sotController_->getControl(controlValues_, period); } catch (std::exception &) { throw; }