Aikido
aikido::control::TrajectoryExecutor Class Referenceabstract

Abstract class for executing trajectories. More...

#include <aikido/control/TrajectoryExecutor.hpp>

Inheritance diagram for aikido::control::TrajectoryExecutor:
aikido::control::Executor aikido::control::InstantaneousTrajectoryExecutor aikido::control::KinematicSimulationTrajectoryExecutor aikido::control::QueuedTrajectoryExecutor aikido::control::ros::RosTrajectoryExecutor

Public Member Functions

 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
 
virtual void validate (const trajectory::Trajectory *traj)=0
 Validate the traj in preparation for execution. More...
 
virtual std::future< void > execute (const trajectory::ConstTrajectoryPtr &traj)=0
 Validate and execute traj, setting future upon completion. More...
 
virtual void step (const std::chrono::system_clock::time_point &timepoint) override=0
 Step to a point in time. More...
 
virtual void cancel ()=0
 Cancel the current trajectory. More...
 
- 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...
 

Protected Attributes

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

Abstract class for executing trajectories.

Constructor & Destructor Documentation

◆ TrajectoryExecutor()

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 
)
inline

Constructor Documentation Inherited.

Parameters
[in]otherTypesOther resources this executor needs beyond TRAJECTORY

◆ ~TrajectoryExecutor()

virtual aikido::control::TrajectoryExecutor::~TrajectoryExecutor ( )
virtualdefault

Member Function Documentation

◆ cancel()

virtual void aikido::control::TrajectoryExecutor::cancel ( )
pure virtual

◆ execute()

virtual std::future<void> aikido::control::TrajectoryExecutor::execute ( const trajectory::ConstTrajectoryPtr traj)
pure virtual

Validate and execute traj, setting future upon completion.

If a trajectory is already running, raise an exception unless the executor supports queuing.

Parameters
trajTrajectory to be executed.
Returns
future<void> for trajectory execution. If trajectory terminates before completion, future will be set to a runtime_error.

Implemented in aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::InstantaneousTrajectoryExecutor, and aikido::control::QueuedTrajectoryExecutor.

◆ step()

virtual void aikido::control::TrajectoryExecutor::step ( const std::chrono::system_clock::time_point &  )
overridepure virtual

Step to a point in time.

Note
timepoint can be a time in the future to enable faster than real-time execution.
Parameters
timepointTime to simulate to

Reimplemented from aikido::control::Executor.

Implemented in aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::QueuedTrajectoryExecutor, and aikido::control::InstantaneousTrajectoryExecutor.

◆ validate()

virtual void aikido::control::TrajectoryExecutor::validate ( const trajectory::Trajectory traj)
pure virtual

Member Data Documentation

◆ mExecutionStartTime

std::chrono::system_clock::time_point aikido::control::TrajectoryExecutor::mExecutionStartTime
protected

Time of previous call.

◆ mValidatedTrajectories

std::set<const trajectory::Trajectory*> aikido::control::TrajectoryExecutor::mValidatedTrajectories
protected

Set of trajectories validated by executor.