Skip to content
Snippets Groups Projects
Commit 6336ce7b authored by Mirko Wächter's avatar Mirko Wächter
Browse files

trajectory controller: avoid memory allocations

parent 234b2bf0
No related branches found
No related tags found
No related merge requests found
......@@ -61,14 +61,14 @@ namespace armarx
{
TrajectoryController& contr = *rtGetControlStruct().trajectoryCtrl;
auto dimNames = contr.getTraj()->getDimensionNames();
const auto& dimNames = contr.getTraj()->getDimensionNames();
for (size_t i = 0; i < dimNames.size(); i++)
{
const auto& jointName = dimNames.at(i);
currentPos(i) = (sensors.count(jointName) == 1) ? sensors[jointName]->position : 0.0f;
currentPos(i) = (sensors.count(jointName) == 1) ? sensors.at(jointName)->position : 0.0f;
}
auto newVelocities = contr.update(timeSinceLastIteration.toSecondsDouble() * direction, currentPos);
auto& newVelocities = contr.update(timeSinceLastIteration.toSecondsDouble() * direction, currentPos);
currentTimestamp = contr.getCurrentTimestamp();
finished = (currentTimestamp >= contr.getTraj()->rbegin()->getTimestamp() && direction == 1.0)
|| (currentTimestamp <= contr.getTraj()->begin()->getTimestamp() && direction == -1.0);
......
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