|
Aikido
|
Executes end-effector R3 linear velocity command towards a perceived target Uses underlying JacobianVelocityExecutor on its own thread. More...
#include <aikido/control/VisualServoingVelocityExecutor.hpp>
Classes | |
| struct | Properties |
| Paramters for Vector Field Planner. More... | |
Public Member Functions | |
| VisualServoingVelocityExecutor (::dart::dynamics::BodyNode *eeNode, std::shared_ptr< JacobianVelocityExecutor > executor=nullptr, Properties properties=Properties()) | |
| Constructor. More... | |
| virtual | ~VisualServoingVelocityExecutor () |
| void | resetProperties (Properties properties=Properties()) |
| Cancel current command and update properties. More... | |
| Properties | getProperties () const |
| Get current properties. More... | |
| virtual std::future< int > | execute (std::function< std::shared_ptr< Eigen::Isometry3d >(void)> perception) |
| Execute a Visual Servoing Command, setting future upon completion. More... | |
| virtual std::future< int > | execute (std::function< std::shared_ptr< Eigen::Isometry3d >(void)> perception, const std::chrono::system_clock::time_point &timepoint) |
| 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::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< 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... | |
Private Attributes | |
| ::dart::dynamics::BodyNode * | mEENode |
| End Effector Body Node Name. More... | |
| std::shared_ptr< JacobianVelocityExecutor > | mExecutor |
| Underlying JacobianVelocityExecutor. More... | |
| std::function< std::shared_ptr< Eigen::Isometry3d >void)> | mPerception |
| Perception Function (if empty, then executor not in progress) More... | |
| std::unique_ptr< std::promise< int > > | mPromise |
| Promise whose future is returned by execute() More... | |
| std::mutex | mMutex |
| Manages access to mPerception, mPromise. More... | |
| Properties | mProperties |
| Properties (see documentation above) More... | |
| std::future< int > | mFuture |
| Future for underlying executor call. More... | |
| std::chrono::system_clock::time_point | mLastPerceivedTime |
| Time of command start. More... | |
Additional Inherited Members | |
Protected Attributes inherited from aikido::control::Executor | |
| std::set< ExecutorType > | mTypes |
| Vector of executor types. More... | |
| std::vector< dart::dynamics::DegreeOfFreedom * > | mDofs |
| Vector of dof names. More... | |
Executes end-effector R3 linear velocity command towards a perceived target Uses underlying JacobianVelocityExecutor on its own thread.
|
explicit |
Constructor.
| eeNode | End effector body node (current position = getWorldTransform()) |
| executor | Base jacobian velocity executor. Default: kinematic, constructed from BodyNode |
| properties | See ::Properties for more info. |
|
virtual |
|
virtual |
Cancels the current command.
Reimplemented from aikido::control::Executor.
|
inlinevirtual |
Execute a Visual Servoing Command, setting future upon completion.
| perception | goal position in DART World Frame |
|
virtual |
| Properties aikido::control::VisualServoingVelocityExecutor::getProperties | ( | ) | const |
Get current properties.
| void aikido::control::VisualServoingVelocityExecutor::resetProperties | ( | Properties | properties = Properties() | ) |
Cancel current command and update properties.
|
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.
Reimplemented from aikido::control::Executor.
|
private |
End Effector Body Node Name.
|
private |
Underlying JacobianVelocityExecutor.
|
private |
Future for underlying executor call.
|
private |
Time of command start.
|
mutableprivate |
Manages access to mPerception, mPromise.
|
private |
Perception Function (if empty, then executor not in progress)
|
private |
Promise whose future is returned by execute()
|
private |
Properties (see documentation above)