Aikido
|
Abstract class for executing trajectories. More...
#include <aikido/control/TrajectoryExecutor.hpp>
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... | |
![]() | |
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< ExecutorType > | getTypes () 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... | |
![]() | |
std::set< ExecutorType > | mTypes |
Vector of executor types. More... | |
std::vector< dart::dynamics::DegreeOfFreedom * > | mDofs |
Vector of dof names. More... | |
Abstract class for executing trajectories.
|
inline |
Constructor Documentation Inherited.
[in] | otherTypes | Other resources this executor needs beyond TRAJECTORY |
|
virtualdefault |
|
pure virtual |
Cancel the current trajectory.
Reimplemented from aikido::control::Executor.
Implemented in aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::InstantaneousTrajectoryExecutor, and aikido::control::QueuedTrajectoryExecutor.
|
pure virtual |
Validate and execute traj, setting future upon completion.
If a trajectory is already running, raise an exception unless the executor supports queuing.
traj | Trajectory to be executed. |
Implemented in aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::InstantaneousTrajectoryExecutor, and aikido::control::QueuedTrajectoryExecutor.
|
overridepure virtual |
Step to a point in time.
timepoint
can be a time in the future to enable faster than real-time execution.timepoint | Time to simulate to |
Reimplemented from aikido::control::Executor.
Implemented in aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::QueuedTrajectoryExecutor, and aikido::control::InstantaneousTrajectoryExecutor.
|
pure virtual |
Validate the traj in preparation for execution.
traj | Trajectory to be validated |
Implemented in aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::InstantaneousTrajectoryExecutor, and aikido::control::QueuedTrajectoryExecutor.
|
protected |
Time of previous call.
|
protected |
Set of trajectories validated by executor.