|
| | RosJointCommandExecutor (const ::ros::NodeHandle &node, const std::string &controllerName, const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, std::chrono::milliseconds connectionTimeout=std::chrono::milliseconds{DEFAULT_CON_TIMEOUT_MS}, std::chrono::milliseconds connectionPollingPeriod=std::chrono::milliseconds{DEFAULT_POLL_PERIOD_MS}) |
| | Constructor. More...
|
| |
| virtual | ~RosJointCommandExecutor () |
| |
| 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...
|
| |
| 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 () |
| |
| virtual std::future< int > | execute (const std::vector< double > &command, const std::chrono::duration< double > &timeout) |
| | Execute a Joint Command, setting future upon completion. More...
|
| |
| | 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...
|
| |
template<ExecutorType T>
class aikido::control::ros::RosJointCommandExecutor< T >
This Executor uses pr_control_msgs/JointGroupCommandAction to execute joint-wise commands.
- See also
- RosJointGroupCommandClient