Skip to content
Snippets Groups Projects
Commit 17a992fb authored by Florent Lamiraux's avatar Florent Lamiraux
Browse files

[SotLoader] Update to recent modifications in sot-core.

parent 32055950
No related branches found
No related tags found
No related merge requests found
...@@ -88,7 +88,7 @@ class SotLoader : public SotLoaderBasic { ...@@ -88,7 +88,7 @@ class SotLoader : public SotLoaderBasic {
// \brief Compute one iteration of control. // \brief Compute one iteration of control.
// Basically calls fillSensors, the SoT and the readControl. // Basically calls fillSensors, the SoT and the readControl.
void oneIteration(); void oneIteration(const double& period);
// \brief Fill the sensors value for the SoT. // \brief Fill the sensors value for the SoT.
void fillSensors(std::map<std::string, dgs::SensorValues> &sensorsIn); void fillSensors(std::map<std::string, dgs::SensorValues> &sensorsIn);
......
...@@ -59,8 +59,9 @@ struct DataToLog { ...@@ -59,8 +59,9 @@ struct DataToLog {
void workThreadLoader(SotLoader *aSotLoader) { void workThreadLoader(SotLoader *aSotLoader) {
ros::Rate rate(1000); // 1 kHz ros::Rate rate(1000); // 1 kHz
double periodd (1e-3);
if (ros::param::has("/sot_controller/dt")) { if (ros::param::has("/sot_controller/dt")) {
double periodd;
ros::param::get("/sot_controller/dt", periodd); ros::param::get("/sot_controller/dt", periodd);
rate = ros::Rate(1 / periodd); rate = ros::Rate(1 / periodd);
} }
...@@ -80,7 +81,7 @@ void workThreadLoader(SotLoader *aSotLoader) { ...@@ -80,7 +81,7 @@ void workThreadLoader(SotLoader *aSotLoader) {
if (!paused) { if (!paused) {
time = ros::Time::now(); time = ros::Time::now();
aSotLoader->oneIteration(); aSotLoader->oneIteration(periodd);
ros::Duration d = ros::Time::now() - time; ros::Duration d = ros::Time::now() - time;
dataToLog.record((time - timeOrigin).toSec(), d.toSec()); dataToLog.record((time - timeOrigin).toSec(), d.toSec());
...@@ -200,15 +201,15 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) { ...@@ -200,15 +201,15 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) {
void SotLoader::setup() { void SotLoader::setup() {
fillSensors(sensorsIn_); fillSensors(sensorsIn_);
sotController_->setupSetSensors(sensorsIn_); sotController_->setupSetSensors(sensorsIn_);
sotController_->getControl(controlValues_); sotController_->getControl(controlValues_, 0);
readControl(controlValues_); readControl(controlValues_);
} }
void SotLoader::oneIteration() { void SotLoader::oneIteration(const double& period) {
fillSensors(sensorsIn_); fillSensors(sensorsIn_);
try { try {
sotController_->nominalSetSensors(sensorsIn_); sotController_->nominalSetSensors(sensorsIn_);
sotController_->getControl(controlValues_); sotController_->getControl(controlValues_, period);
} catch (std::exception &) { } catch (std::exception &) {
throw; throw;
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment