Aikido
|
Executes end-effector SE3 command. More...
#include <aikido/control/JacobianExecutor.hpp>
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... | |
![]() | |
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 () |
![]() | |
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... | |
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 | |
![]() | |
std::set< ExecutorType > | mTypes |
Vector of executor types. More... | |
std::vector< dart::dynamics::DegreeOfFreedom * > | mDofs |
Vector of dof names. More... | |
Executes end-effector SE3 command.
Uses local Jacobian to translate to joint command.
|
explicit |
Constructor.
eeNode | End effector body node. |
lambda | Damped Jacobian pseudo-inverse calculation: (JtJ + lambda^2 I)^{-1} |
executor | Base joint executor for converted joint commands. Default: KinematicSimulationJointCommandExecutor |
|
virtual |
|
virtual |
Cancels the current command.
Implements aikido::control::JointCommandExecutor< T >.
|
virtual |
|
inlinevirtual |
Execute an SE3 Command, setting future upon completion.
command | SE3 Command Vector (6d) |
timeout | How long until command expires |
|
virtual |
Execute a Joint Command, setting future upon completion.
command | Vector of joint commands, parallel with joints vector |
timeout | How long until command expires |
timepoint | If supplied, time to simulate to |
Implements aikido::control::JointCommandExecutor< T >.
|
inlinevirtual |
Execute a Joint Command, setting future upon completion.
command | Vector of joint commands, parallel with joints vector |
timeout | How long until command expires |
timepoint | If supplied, time to simulate to |
Cancels all SE3 Commands Calls the underlying JointCommandExecutor.
Reimplemented from aikido::control::JointCommandExecutor< T >.
|
private |
Convert SE3 command to joint command.
|
overridevirtual |
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 |
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 >.
|
staticconstexpr |
|
private |
Command being executed (6d)
|
private |
End Effector Body Node Name.
|
private |
Time of command start.
|
private |
Underlying Joint Command Executor.
|
private |
Future for underlying executor call.
|
private |
Whether a command is being executed.
|
private |
Jacobian damping factor.
|
mutableprivate |
Manages access to mCommand, mInProgress, mPromise.
|
private |
Promise whose future is returned by execute()
|
private |
Velocity timeout.
|
staticconstexpr |