Aikido
aikido::control::InstantaneousTrajectoryExecutor Class Reference

Instantaneously executes a trajectory in simulation by setting DOF positions to the end of the trajectory. More...

#include <aikido/control/InstantaneousTrajectoryExecutor.hpp>

Inheritance diagram for aikido::control::InstantaneousTrajectoryExecutor:
aikido::control::TrajectoryExecutor aikido::control::Executor

Public Member Functions

 InstantaneousTrajectoryExecutor (::dart::dynamics::MetaSkeletonPtr metaskeleton)
 Constructor. More...
 
virtual ~InstantaneousTrajectoryExecutor ()
 
void validate (const trajectory::Trajectory *traj) override
 Validate the traj in preparation for execution. More...
 
std::future< void > execute (const trajectory::ConstTrajectoryPtr &traj) override
 Instantaneously execute traj and set future upon completion. More...
 
void step (const std::chrono::system_clock::time_point &) override
 Does nothing. More...
 
void cancel () override
 Does nothing. More...
 
- Public Member Functions inherited from aikido::control::TrajectoryExecutor
 TrajectoryExecutor (const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, const std::set< ExecutorType > otherTypes=std::set< ExecutorType >(), const std::chrono::milliseconds threadRate=defaultThreadRate)
 Constructor Documentation Inherited. More...
 
virtual ~TrajectoryExecutor ()=default
 
- Public Member Functions inherited from aikido::control::Executor
 Executor (const std::set< ExecutorType > &types, const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, const std::chrono::milliseconds threadRate=defaultThreadRate)
 Constructor. More...
 
 Executor (const ExecutorType type, const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, std::chrono::milliseconds threadRate=defaultThreadRate)
 Constructor. More...
 
virtual ~Executor ()
 
std::set< ExecutorTypegetTypes () const
 Get all of this Executor's ExecutorTypes. More...
 
const std::vector< dart::dynamics::DegreeOfFreedom * > getDofs () const
 Get list of dofs needed by this Executor. More...
 
void start ()
 Start the underlying ExecutorThread. More...
 
void stop ()
 Stops the underlying ExecutorThread. More...
 
bool registerDofs ()
 Lock the resources required by the DoFs. More...
 
void releaseDofs ()
 Unlock any resources required by the DoFs. More...
 

Private Attributes

::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
 Skeleton to execute trajectories on. More...
 
std::unique_ptr< std::promise< void > > mPromise
 Promise whose future is returned by execute() More...
 
std::mutex mMutex
 Manages access to mPromise. More...
 

Additional Inherited Members

- Protected Attributes inherited from aikido::control::TrajectoryExecutor
std::set< const trajectory::Trajectory * > mValidatedTrajectories
 Set of trajectories validated by executor. More...
 
std::chrono::system_clock::time_point mExecutionStartTime
 Time of previous call. More...
 
- Protected Attributes inherited from aikido::control::Executor
std::set< ExecutorTypemTypes
 Vector of executor types. More...
 
std::vector< dart::dynamics::DegreeOfFreedom * > mDofs
 Vector of dof names. More...
 

Detailed Description

Instantaneously executes a trajectory in simulation by setting DOF positions to the end of the trajectory.

Constructor & Destructor Documentation

◆ InstantaneousTrajectoryExecutor()

aikido::control::InstantaneousTrajectoryExecutor::InstantaneousTrajectoryExecutor ( ::dart::dynamics::MetaSkeletonPtr  metaskeleton)
explicit

Constructor.

Parameters
skeletonSkeleton to execute trajectories on. All trajectories must have dofs only in this skeleton.

◆ ~InstantaneousTrajectoryExecutor()

virtual aikido::control::InstantaneousTrajectoryExecutor::~InstantaneousTrajectoryExecutor ( )
virtual

Member Function Documentation

◆ cancel()

void aikido::control::InstantaneousTrajectoryExecutor::cancel ( )
overridevirtual

Does nothing.

Implements aikido::control::TrajectoryExecutor.

◆ execute()

std::future<void> aikido::control::InstantaneousTrajectoryExecutor::execute ( const trajectory::ConstTrajectoryPtr traj)
overridevirtual

Instantaneously execute traj and set future upon completion.

Parameters
trajTrajectory to be executed. Its StateSpace should be a MetaSkeletonStateSpace, where the dofs are all in the skeleton passed to this constructor.
Returns
future<void> for trajectory execution. If trajectory terminates before completion, future will be set to a runtime_error.
Exceptions
invalid_argumentif traj is invalid.

Implements aikido::control::TrajectoryExecutor.

◆ step()

void aikido::control::InstantaneousTrajectoryExecutor::step ( const std::chrono::system_clock::time_point &  )
overridevirtual

Does nothing.

Implements aikido::control::TrajectoryExecutor.

◆ validate()

void aikido::control::InstantaneousTrajectoryExecutor::validate ( const trajectory::Trajectory traj)
overridevirtual

Validate the traj in preparation for execution.

Parameters
trajTrajectory to be validated

Implements aikido::control::TrajectoryExecutor.

Member Data Documentation

◆ mMetaSkeleton

::dart::dynamics::MetaSkeletonPtr aikido::control::InstantaneousTrajectoryExecutor::mMetaSkeleton
private

Skeleton to execute trajectories on.

◆ mMutex

std::mutex aikido::control::InstantaneousTrajectoryExecutor::mMutex
mutableprivate

Manages access to mPromise.

◆ mPromise

std::unique_ptr<std::promise<void> > aikido::control::InstantaneousTrajectoryExecutor::mPromise
private

Promise whose future is returned by execute()