Aikido
|
Abstract class for executing commands on degrees of freedom. More...
#include <aikido/control/Executor.hpp>
Public Member Functions | |
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... | |
virtual void | step (const std::chrono::system_clock::time_point &) |
Step to a point in time. 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... | |
virtual void | cancel () |
Cancel the current command. More... | |
Protected Attributes | |
std::set< ExecutorType > | mTypes |
Vector of executor types. More... | |
std::vector< dart::dynamics::DegreeOfFreedom * > | mDofs |
Vector of dof names. More... | |
Private Member Functions | |
void | spin () |
Call to spin first to pass current time to step Necessary for real-time execution via mThread. More... | |
Private Attributes | |
std::chrono::milliseconds | mThreadRate |
How often to run spin() on internal thread. More... | |
bool | mDofsRegistered {false} |
Whether this executor has a lock on its DoF resources. More... | |
std::unique_ptr< aikido::common::ExecutorThread > | mThread |
Executor thread calling step function. More... | |
Static Private Attributes | |
static std::unordered_map< ExecutorType, std::set< dart::dynamics::DegreeOfFreedom * > > | mDofManager |
Manager for locking resources for degrees of freedom. More... | |
static std::mutex | mMutex |
Mutex to protects the DofManager. More... | |
Abstract class for executing commands on degrees of freedom.
aikido::control::Executor::Executor | ( | const std::set< ExecutorType > & | types, |
const std::vector< dart::dynamics::DegreeOfFreedom * > & | dofs, | ||
const std::chrono::milliseconds | threadRate = defaultThreadRate |
||
) |
aikido::control::Executor::Executor | ( | const ExecutorType | type, |
const std::vector< dart::dynamics::DegreeOfFreedom * > & | dofs, | ||
std::chrono::milliseconds | threadRate = defaultThreadRate |
||
) |
|
virtual |
|
inlinevirtual |
Cancel the current command.
Reimplemented in aikido::control::JointCommandExecutor< T >, aikido::control::TrajectoryExecutor, aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationJointCommandExecutor< T >, aikido::control::ros::RosJointCommandExecutor< T >, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::InstantaneousTrajectoryExecutor, aikido::control::QueuedTrajectoryExecutor, aikido::control::VisualServoingVelocityExecutor, and aikido::control::JacobianExecutor< T >.
const std::vector<dart::dynamics::DegreeOfFreedom*> aikido::control::Executor::getDofs | ( | ) | const |
Get list of dofs needed by this Executor.
std::set<ExecutorType> aikido::control::Executor::getTypes | ( | ) | const |
Get all of this Executor's ExecutorTypes.
bool aikido::control::Executor::registerDofs | ( | ) |
Lock the resources required by the DoFs.
void aikido::control::Executor::releaseDofs | ( | ) |
Unlock any resources required by the DoFs.
|
inlineprivate |
Call to spin first to pass current time to step Necessary for real-time execution via mThread.
void aikido::control::Executor::start | ( | ) |
Start the underlying ExecutorThread.
|
inlinevirtual |
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 in aikido::control::JointCommandExecutor< T >, aikido::control::TrajectoryExecutor, aikido::control::VisualServoingVelocityExecutor, aikido::control::JacobianExecutor< T >, aikido::control::ros::RosTrajectoryExecutor, aikido::control::KinematicSimulationJointCommandExecutor< T >, aikido::control::ros::RosJointCommandExecutor< T >, aikido::control::KinematicSimulationTrajectoryExecutor, aikido::control::QueuedTrajectoryExecutor, and aikido::control::InstantaneousTrajectoryExecutor.
void aikido::control::Executor::stop | ( | ) |
Stops the underlying ExecutorThread.
|
staticprivate |
Manager for locking resources for degrees of freedom.
|
protected |
Vector of dof names.
|
private |
Whether this executor has a lock on its DoF resources.
|
staticprivate |
Mutex to protects the DofManager.
|
private |
Executor thread calling step function.
|
private |
How often to run spin() on internal thread.
|
protected |
Vector of executor types.