Aikido
aikido::control::ros::RosJointCommandExecutor< T > Class Template Reference

This Executor uses pr_control_msgs/JointGroupCommandAction to execute joint-wise commands. More...

#include <aikido/control/ros/RosJointCommandExecutor.hpp>

Inheritance diagram for aikido::control::ros::RosJointCommandExecutor< T >:
aikido::control::JointCommandExecutor< T > aikido::control::Executor

Public Member Functions

 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...
 
- 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

RosJointGroupCommandClient mClient
 

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::ros::RosJointCommandExecutor< T >

This Executor uses pr_control_msgs/JointGroupCommandAction to execute joint-wise commands.

See also
RosJointGroupCommandClient

Constructor & Destructor Documentation

◆ RosJointCommandExecutor()

template<ExecutorType T>
aikido::control::ros::RosJointCommandExecutor< T >::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.

Parameters
[in]nodeROS node handle for action client.
[in]controllerNameName of the controller to send command to.
[in]dofsThe Degrees of Freedom to set goal targets for
[in]connectionTimeoutTimeout for server connection.
[in]connectionPollingPeriodPolling period for server connection.

◆ ~RosJointCommandExecutor()

Member Function Documentation

◆ cancel()

template<ExecutorType T>
void aikido::control::ros::RosJointCommandExecutor< T >::cancel ( )
overridevirtual

Cancels the current command.

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

◆ execute()

template<ExecutorType T>
std::future< int > aikido::control::ros::RosJointCommandExecutor< 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 >.

◆ step()

template<ExecutorType T>
void aikido::control::ros::RosJointCommandExecutor< T >::step ( const std::chrono::system_clock::time_point &  )
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

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

Member Data Documentation

◆ mClient

template<ExecutorType T>
RosJointGroupCommandClient aikido::control::ros::RosJointCommandExecutor< T >::mClient
private