diff --git a/include/aikido/control/BarrettHandKinematicSimulationPositionCommandExecutor.hpp b/include/aikido/control/BarrettHandKinematicSimulationPositionCommandExecutor.hpp index c83c477e92..08f93f52a3 100644 --- a/include/aikido/control/BarrettHandKinematicSimulationPositionCommandExecutor.hpp +++ b/include/aikido/control/BarrettHandKinematicSimulationPositionCommandExecutor.hpp @@ -47,7 +47,9 @@ class BarrettHandKinematicSimulationPositionCommandExecutor /// \return Future which becomes available when the execution completes. std::future execute(const Eigen::VectorXd& goalPositions) override; - // Documentation inherited. + /// If multiple threads are accessing this function or the skeleton associated + /// with this executor, it is necessary to lock the skeleton before + /// calling this method. void step() override; /// Resets CollisionGroup to check collision with fingers. diff --git a/include/aikido/control/KinematicSimulationTrajectoryExecutor.hpp b/include/aikido/control/KinematicSimulationTrajectoryExecutor.hpp index 945129e6d2..61e01996a9 100644 --- a/include/aikido/control/KinematicSimulationTrajectoryExecutor.hpp +++ b/include/aikido/control/KinematicSimulationTrajectoryExecutor.hpp @@ -35,7 +35,9 @@ class KinematicSimulationTrajectoryExecutor : public TrajectoryExecutor std::future execute( trajectory::TrajectoryPtr traj) override; - // Documentation inherited. + /// If multiple threads are accessing this function or the skeleton associated + /// with this executor, it is necessary to lock the skeleton before + /// calling this method. void step() override; private: diff --git a/src/control/KinematicSimulationTrajectoryExecutor.cpp b/src/control/KinematicSimulationTrajectoryExecutor.cpp index 2a127d9098..0fd2aafe51 100644 --- a/src/control/KinematicSimulationTrajectoryExecutor.cpp +++ b/src/control/KinematicSimulationTrajectoryExecutor.cpp @@ -106,7 +106,7 @@ void KinematicSimulationTrajectoryExecutor::step() } auto timeSinceBeginning = system_clock::now() - mExecutionStartTime; - double t = duration_cast(timeSinceBeginning).count(); + auto t = duration(timeSinceBeginning).count(); // Can't do static here because MetaSkeletonStateSpace inherits // CartesianProduct which inherits virtual StateSpace @@ -117,10 +117,7 @@ void KinematicSimulationTrajectoryExecutor::step() mTraj->evaluate(t, state); - // Lock the skeleton, set state. - std::unique_lock skeleton_lock(mSkeleton->getMutex()); space->setState(state); - skeleton_lock.unlock(); // Check if trajectory has completed. bool const is_done = (t >= mTraj->getEndTime()); @@ -129,6 +126,7 @@ void KinematicSimulationTrajectoryExecutor::step() mPromise->set_value(); mInExecution = false; } + } }