Aikido
aikido::control::ros::RosTrajectoryExecutor Class Reference

This class sends trajectory commands to ROS server. More...

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

Inheritance diagram for aikido::control::ros::RosTrajectoryExecutor:
aikido::control::TrajectoryExecutor aikido::control::Executor

Public Member Functions

 RosTrajectoryExecutor (const ::ros::NodeHandle &node, const std::string &serverName, double waypointTimestep, double goalTimeTolerance, const ::dart::dynamics::MetaSkeletonPtr metaskeleton, const std::chrono::milliseconds &connectionTimeout=std::chrono::milliseconds{1000}, const std::chrono::milliseconds &connectionPollingPeriod=std::chrono::milliseconds{20})
 Constructor. More...
 
virtual ~RosTrajectoryExecutor ()
 
void validate (const trajectory::Trajectory *traj) override
 Validate the traj in preparation for execution. More...
 
std::future< void > execute (const trajectory::ConstTrajectoryPtr &traj) override
 Sends trajectory to ROS server for execution. More...
 
std::future< void > execute (const trajectory::ConstTrajectoryPtr &traj, const ::ros::Time &startTime)
 Sends trajectory to ROS server for execution. More...
 
void step (const std::chrono::system_clock::time_point &timepoint) override
 Step to a point in time. More...
 
void cancel () override
 Cancel the current trajectory. More...
 
- Public Member Functions inherited from aikido::control::TrajectoryExecutor
 TrajectoryExecutor (const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, const std::set< ExecutorType > otherTypes=std::set< ExecutorType >(), const std::chrono::milliseconds threadRate=defaultThreadRate)
 Constructor Documentation Inherited. More...
 
virtual ~TrajectoryExecutor ()=default
 
- 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 Types

using TrajectoryActionClient = actionlib::ActionClient< control_msgs::FollowJointTrajectoryAction >
 
using GoalHandle = TrajectoryActionClient::GoalHandle
 

Private Member Functions

void transitionCallback (GoalHandle handle)
 

Private Attributes

const ::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
 MetaSkeleton to execute trajectories on For trajectory-validation purposes only. More...
 
::ros::NodeHandle mNode
 
::ros::CallbackQueue mCallbackQueue
 
TrajectoryActionClient mClient
 
TrajectoryActionClient::GoalHandle mGoalHandle
 
double mWaypointTimestep
 
double mGoalTimeTolerance
 
std::chrono::milliseconds mConnectionTimeout
 
std::chrono::milliseconds mConnectionPollingPeriod
 
bool mInProgress
 
std::unique_ptr< std::promise< void > > mPromise
 
std::mutex mMutex
 Manages access to mInProgress, mPromise. More...
 

Additional Inherited Members

- Protected Attributes inherited from aikido::control::TrajectoryExecutor
std::set< const trajectory::Trajectory * > mValidatedTrajectories
 Set of trajectories validated by executor. More...
 
std::chrono::system_clock::time_point mExecutionStartTime
 Time of previous call. More...
 
- 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

This class sends trajectory commands to ROS server.

Member Typedef Documentation

◆ GoalHandle

using aikido::control::ros::RosTrajectoryExecutor::GoalHandle = TrajectoryActionClient::GoalHandle
private

◆ TrajectoryActionClient

using aikido::control::ros::RosTrajectoryExecutor::TrajectoryActionClient = actionlib::ActionClient<control_msgs::FollowJointTrajectoryAction>
private

Constructor & Destructor Documentation

◆ RosTrajectoryExecutor()

aikido::control::ros::RosTrajectoryExecutor::RosTrajectoryExecutor ( const ::ros::NodeHandle &  node,
const std::string &  serverName,
double  waypointTimestep,
double  goalTimeTolerance,
const ::dart::dynamics::MetaSkeletonPtr  metaskeleton,
const std::chrono::milliseconds &  connectionTimeout = std::chrono::milliseconds{1000},
const std::chrono::milliseconds &  connectionPollingPeriod = std::chrono::milliseconds{20} 
)

Constructor.

Parameters
[in]nodeROS node handle for action client.
[in]serverNameName of the server to send trajectory to.
[in]waypointTimestepStep size for interpolating trajectories.
[in]goalTimeToleranceWait time for robot to settle at goal
[in]dofsThe Degrees of Freedom this executor acts upon
[in]connectionTimeoutTimeout for server connection.
[in]connectionPollingPeriodPolling period for server connection.

◆ ~RosTrajectoryExecutor()

virtual aikido::control::ros::RosTrajectoryExecutor::~RosTrajectoryExecutor ( )
virtual

Member Function Documentation

◆ cancel()

void aikido::control::ros::RosTrajectoryExecutor::cancel ( )
overridevirtual

Cancel the current trajectory.

Implements aikido::control::TrajectoryExecutor.

◆ execute() [1/2]

std::future<void> aikido::control::ros::RosTrajectoryExecutor::execute ( const trajectory::ConstTrajectoryPtr traj)
overridevirtual

Sends trajectory to ROS server for execution.

Parameters
[in]trajTrajectory to be executed.

Implements aikido::control::TrajectoryExecutor.

◆ execute() [2/2]

std::future<void> aikido::control::ros::RosTrajectoryExecutor::execute ( const trajectory::ConstTrajectoryPtr traj,
const ::ros::Time &  startTime 
)

Sends trajectory to ROS server for execution.

Parameters
[in]trajTrajectory to be executed.
[in]startTimeStart time for the trajectory.

◆ step()

void aikido::control::ros::RosTrajectoryExecutor::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

To be executed on a separate thread. Regularly checks for the completion of a sent trajectory.

Implements aikido::control::TrajectoryExecutor.

◆ transitionCallback()

void aikido::control::ros::RosTrajectoryExecutor::transitionCallback ( GoalHandle  handle)
private

◆ validate()

void aikido::control::ros::RosTrajectoryExecutor::validate ( const trajectory::Trajectory traj)
overridevirtual

Validate the traj in preparation for execution.

Parameters
trajTrajectory to be validated

Implements aikido::control::TrajectoryExecutor.

Member Data Documentation

◆ mCallbackQueue

::ros::CallbackQueue aikido::control::ros::RosTrajectoryExecutor::mCallbackQueue
private

◆ mClient

TrajectoryActionClient aikido::control::ros::RosTrajectoryExecutor::mClient
private

◆ mConnectionPollingPeriod

std::chrono::milliseconds aikido::control::ros::RosTrajectoryExecutor::mConnectionPollingPeriod
private

◆ mConnectionTimeout

std::chrono::milliseconds aikido::control::ros::RosTrajectoryExecutor::mConnectionTimeout
private

◆ mGoalHandle

TrajectoryActionClient::GoalHandle aikido::control::ros::RosTrajectoryExecutor::mGoalHandle
private

◆ mGoalTimeTolerance

double aikido::control::ros::RosTrajectoryExecutor::mGoalTimeTolerance
private

◆ mInProgress

bool aikido::control::ros::RosTrajectoryExecutor::mInProgress
private

◆ mMetaSkeleton

const ::dart::dynamics::MetaSkeletonPtr aikido::control::ros::RosTrajectoryExecutor::mMetaSkeleton
private

MetaSkeleton to execute trajectories on For trajectory-validation purposes only.

◆ mMutex

std::mutex aikido::control::ros::RosTrajectoryExecutor::mMutex
mutableprivate

Manages access to mInProgress, mPromise.

◆ mNode

::ros::NodeHandle aikido::control::ros::RosTrajectoryExecutor::mNode
private

◆ mPromise

std::unique_ptr<std::promise<void> > aikido::control::ros::RosTrajectoryExecutor::mPromise
private

◆ mWaypointTimestep

double aikido::control::ros::RosTrajectoryExecutor::mWaypointTimestep
private