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

Executes end-effector SE3 command. More...

#include <aikido/control/JacobianExecutor.hpp>

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

Public Member Functions

 JacobianExecutor (::dart::dynamics::BodyNode *eeNode, std::shared_ptr< JointCommandExecutor< T >> executor=nullptr, double lambda=DEFAULT_LAMBDA)
 Constructor. More...
 
virtual ~JacobianExecutor ()
 
virtual std::future< int > execute (const Eigen::Vector6d command, const std::chrono::duration< double > &timeout=std::chrono::duration< double >(1))
 Execute an SE3 Command, setting future upon completion. More...
 
virtual std::future< int > execute (const Eigen::Vector6d command, const std::chrono::duration< double > &timeout, const std::chrono::system_clock::time_point &timepoint)
 
virtual std::future< int > execute (const std::vector< double > &command, const std::chrono::duration< double > &timeout=std::chrono::duration< double >(1))
 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, const std::chrono::system_clock::time_point &timepoint)
 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 ()
 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...
 

Static Public Attributes

static constexpr size_t SE3_SIZE = 6
 
static constexpr double DEFAULT_LAMBDA = 1E-8
 

Private Member Functions

std::vector< double > SE3ToJoint (const Eigen::Vector6d command)
 Convert SE3 command to joint command. More...
 

Private Attributes

::dart::dynamics::BodyNode * mEENode
 End Effector Body Node Name. More...
 
std::shared_ptr< JointCommandExecutor< T > > mExecutor
 Underlying Joint Command Executor. More...
 
Eigen::Vector6d mCommand
 Command being executed (6d) More...
 
double mLambda
 Jacobian damping factor. 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 command start. More...
 
std::chrono::duration< double > mTimeout
 Velocity timeout. More...
 
std::future< int > mFuture
 Future for underlying executor call. 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::JacobianExecutor< T >

Executes end-effector SE3 command.

Uses local Jacobian to translate to joint command.

Constructor & Destructor Documentation

◆ JacobianExecutor()

template<ExecutorType T>
aikido::control::JacobianExecutor< T >::JacobianExecutor ( ::dart::dynamics::BodyNode *  eeNode,
std::shared_ptr< JointCommandExecutor< T >>  executor = nullptr,
double  lambda = DEFAULT_LAMBDA 
)
explicit

Constructor.

Parameters
eeNodeEnd effector body node.
lambdaDamped Jacobian pseudo-inverse calculation: (JtJ + lambda^2 I)^{-1}
executorBase joint executor for converted joint commands. Default: KinematicSimulationJointCommandExecutor

◆ ~JacobianExecutor()

template<ExecutorType T>
aikido::control::JacobianExecutor< T >::~JacobianExecutor
virtual

Member Function Documentation

◆ cancel()

template<ExecutorType T>
void aikido::control::JacobianExecutor< T >::cancel
virtual

Cancels the current command.

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

◆ execute() [1/4]

template<ExecutorType T>
std::future< int > aikido::control::JacobianExecutor< T >::execute ( const Eigen::Vector6d  command,
const std::chrono::duration< double > &  timeout,
const std::chrono::system_clock::time_point &  timepoint 
)
virtual

◆ execute() [2/4]

template<ExecutorType T>
virtual std::future<int> aikido::control::JacobianExecutor< T >::execute ( const Eigen::Vector6d  command,
const std::chrono::duration< double > &  timeout = std::chrono::duration<double>(1) 
)
inlinevirtual

Execute an SE3 Command, setting future upon completion.

Note
Future should return 0 on success or timeout.
Parameters
commandSE3 Command Vector (6d)
timeoutHow long until command expires

◆ execute() [3/4]

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

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() [4/4]

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

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

Cancels all SE3 Commands Calls the underlying JointCommandExecutor.

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

◆ SE3ToJoint()

template<ExecutorType T>
std::vector< double > aikido::control::JacobianExecutor< T >::SE3ToJoint ( const Eigen::Vector6d  command)
private

Convert SE3 command to joint command.

◆ step()

template<ExecutorType T>
void aikido::control::JacobianExecutor< 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

◆ DEFAULT_LAMBDA

template<ExecutorType T>
constexpr double aikido::control::JacobianExecutor< T >::DEFAULT_LAMBDA = 1E-8
staticconstexpr

◆ mCommand

template<ExecutorType T>
Eigen::Vector6d aikido::control::JacobianExecutor< T >::mCommand
private

Command being executed (6d)

◆ mEENode

template<ExecutorType T>
::dart::dynamics::BodyNode* aikido::control::JacobianExecutor< T >::mEENode
private

End Effector Body Node Name.

◆ mExecutionStartTime

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

Time of command start.

◆ mExecutor

template<ExecutorType T>
std::shared_ptr<JointCommandExecutor<T> > aikido::control::JacobianExecutor< T >::mExecutor
private

Underlying Joint Command Executor.

◆ mFuture

template<ExecutorType T>
std::future<int> aikido::control::JacobianExecutor< T >::mFuture
private

Future for underlying executor call.

◆ mInProgress

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

Whether a command is being executed.

◆ mLambda

template<ExecutorType T>
double aikido::control::JacobianExecutor< T >::mLambda
private

Jacobian damping factor.

◆ mMutex

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

Manages access to mCommand, mInProgress, mPromise.

◆ mPromise

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

Promise whose future is returned by execute()

◆ mTimeout

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

Velocity timeout.

◆ SE3_SIZE

template<ExecutorType T>
constexpr size_t aikido::control::JacobianExecutor< T >::SE3_SIZE = 6
staticconstexpr