Aikido
aikido::control::KinematicSimulationJointCommandExecutor< T > Class Template Reference

Executes joint command in DART. More...

#include <aikido/control/KinematicSimulationJointCommandExecutor.hpp>

Inheritance diagram for aikido::control::KinematicSimulationJointCommandExecutor< T >:
aikido::control::JointCommandExecutor< T > aikido::control::Executor

Public Member Functions

 KinematicSimulationJointCommandExecutor (::dart::dynamics::MetaSkeletonPtr metaskeleton)
 Constructor. More...
 
 KinematicSimulationJointCommandExecutor (std::vector<::dart::dynamics::DegreeOfFreedom * > dofs)
 DoF-only Constructor. More...
 
virtual ~KinematicSimulationJointCommandExecutor ()
 
virtual std::future< int > execute (const std::vector< double > &command, const std::chrono::duration< double > &timeout, const std::chrono::system_clock::time_point &timepoint) override
 Execute a Joint Command, setting future upon completion. More...
 
virtual std::future< int > execute (const std::vector< double > &command, const std::chrono::duration< double > &timeout=std::chrono::duration< double >(1.0)) override
 Execute a Joint Command, setting future upon completion. More...
 
void step (const std::chrono::system_clock::time_point &timepoint) override
 Step to a point in time. More...
 
void cancel () override
 Cancels the current command. More...
 
- Public Member Functions inherited from aikido::control::JointCommandExecutor< T >
 JointCommandExecutor (const std::vector< dart::dynamics::DegreeOfFreedom * > dofs, const std::set< ExecutorType > otherTypes=std::set< ExecutorType >(), const std::chrono::milliseconds threadRate=defaultThreadRate)
 Constructor. More...
 
virtual ~JointCommandExecutor ()
 
- 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

std::vector< double > mCommand
 Command being executed. More...
 
::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
 The controlled subset of mSkeleton for the currently executing command. More...
 
bool mInProgress
 Whether a command is being executed. More...
 
std::unique_ptr< std::promise< int > > mPromise
 Promise whose future is returned by execute() More...
 
std::mutex mMutex
 Manages access to mCommand, mInProgress, mPromise. More...
 
std::chrono::system_clock::time_point mExecutionStartTime
 Time of position command start (for interpolation) More...
 
std::vector< double > mStartPosition
 Position at start of command (for interpolation) More...
 
std::chrono::duration< double > mTimeout
 Velocity timeout. More...
 

Additional Inherited Members

- 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

template<ExecutorType T>
class aikido::control::KinematicSimulationJointCommandExecutor< T >

Executes joint command in DART.

This simulates by setting interpolated DOF positions, without running dynamic simulation.

Constructor & Destructor Documentation

◆ KinematicSimulationJointCommandExecutor() [1/2]

template<ExecutorType T>
aikido::control::KinematicSimulationJointCommandExecutor< T >::KinematicSimulationJointCommandExecutor ( ::dart::dynamics::MetaSkeletonPtr  metaskeleton)
explicit

Constructor.

Parameters
metaskeletonMetaSkeleton to execute commands on.

◆ KinematicSimulationJointCommandExecutor() [2/2]

template<ExecutorType T>
aikido::control::KinematicSimulationJointCommandExecutor< T >::KinematicSimulationJointCommandExecutor ( std::vector<::dart::dynamics::DegreeOfFreedom * >  dofs)
explicit

DoF-only Constructor.

Parameters
dofsDoFs to execute commands on.

◆ ~KinematicSimulationJointCommandExecutor()

Member Function Documentation

◆ cancel()

template<ExecutorType T>
void aikido::control::KinematicSimulationJointCommandExecutor< T >::cancel
overridevirtual

Cancels the current command.

Implements aikido::control::JointCommandExecutor< T >.

◆ execute() [1/2]

template<ExecutorType T>
std::future< int > aikido::control::KinematicSimulationJointCommandExecutor< T >::execute ( const std::vector< double > &  command,
const std::chrono::duration< double > &  timeout,
const std::chrono::system_clock::time_point &  timepoint 
)
overridevirtual

Execute a Joint Command, setting future upon completion.

Note
Future should return 0 on success or timeout.
Parameters
commandVector of joint commands, parallel with joints vector
timeoutHow long until command expires
timepointIf supplied, time to simulate to

Implements aikido::control::JointCommandExecutor< T >.

◆ execute() [2/2]

template<ExecutorType T>
virtual std::future<int> aikido::control::KinematicSimulationJointCommandExecutor< T >::execute ( const std::vector< double > &  command,
const std::chrono::duration< double > &  timeout = std::chrono::duration<double>(1.0) 
)
inlineoverridevirtual

Execute a Joint Command, setting future upon completion.

If applicable, simulate to the current time.

Note
Future should return 0 on success or timeout.
Parameters
commandVector of joint commands, parallel with joints vector
timeoutHow long until command expires

Reimplemented from aikido::control::JointCommandExecutor< T >.

◆ step()

template<ExecutorType T>
void aikido::control::KinematicSimulationJointCommandExecutor< T >::step ( const std::chrono::system_clock::time_point &  timepoint)
overridevirtual

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

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.

Implements aikido::control::JointCommandExecutor< T >.

Member Data Documentation

◆ mCommand

template<ExecutorType T>
std::vector<double> aikido::control::KinematicSimulationJointCommandExecutor< T >::mCommand
private

Command being executed.

◆ mExecutionStartTime

template<ExecutorType T>
std::chrono::system_clock::time_point aikido::control::KinematicSimulationJointCommandExecutor< T >::mExecutionStartTime
private

Time of position command start (for interpolation)

◆ mInProgress

template<ExecutorType T>
bool aikido::control::KinematicSimulationJointCommandExecutor< T >::mInProgress
private

Whether a command is being executed.

◆ mMetaSkeleton

template<ExecutorType T>
::dart::dynamics::MetaSkeletonPtr aikido::control::KinematicSimulationJointCommandExecutor< T >::mMetaSkeleton
private

The controlled subset of mSkeleton for the currently executing command.

◆ mMutex

template<ExecutorType T>
std::mutex aikido::control::KinematicSimulationJointCommandExecutor< T >::mMutex
mutableprivate

Manages access to mCommand, mInProgress, mPromise.

◆ mPromise

template<ExecutorType T>
std::unique_ptr<std::promise<int> > aikido::control::KinematicSimulationJointCommandExecutor< T >::mPromise
private

Promise whose future is returned by execute()

◆ mStartPosition

template<ExecutorType T>
std::vector<double> aikido::control::KinematicSimulationJointCommandExecutor< T >::mStartPosition
private

Position at start of command (for interpolation)

◆ mTimeout

template<ExecutorType T>
std::chrono::duration<double> aikido::control::KinematicSimulationJointCommandExecutor< T >::mTimeout
private

Velocity timeout.