|
Aikido
|
This class sends trajectory commands to ROS server. More...
#include <aikido/control/ros/RosTrajectoryExecutor.hpp>
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< 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 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< ExecutorType > | mTypes |
| Vector of executor types. More... | |
| std::vector< dart::dynamics::DegreeOfFreedom * > | mDofs |
| Vector of dof names. More... | |
This class sends trajectory commands to ROS server.
|
private |
|
private |
| 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.
| [in] | node | ROS node handle for action client. |
| [in] | serverName | Name of the server to send trajectory to. |
| [in] | waypointTimestep | Step size for interpolating trajectories. |
| [in] | goalTimeTolerance | Wait time for robot to settle at goal |
| [in] | dofs | The Degrees of Freedom this executor acts upon |
| [in] | connectionTimeout | Timeout for server connection. |
| [in] | connectionPollingPeriod | Polling period for server connection. |
|
virtual |
|
overridevirtual |
Cancel the current trajectory.
Implements aikido::control::TrajectoryExecutor.
|
overridevirtual |
Sends trajectory to ROS server for execution.
| [in] | traj | Trajectory to be executed. |
Implements aikido::control::TrajectoryExecutor.
| std::future<void> aikido::control::ros::RosTrajectoryExecutor::execute | ( | const trajectory::ConstTrajectoryPtr & | traj, |
| const ::ros::Time & | startTime | ||
| ) |
Sends trajectory to ROS server for execution.
| [in] | traj | Trajectory to be executed. |
| [in] | startTime | Start time for the trajectory. |
|
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 |
To be executed on a separate thread. Regularly checks for the completion of a sent trajectory.
Implements aikido::control::TrajectoryExecutor.
|
private |
|
overridevirtual |
Validate the traj in preparation for execution.
| traj | Trajectory to be validated |
Implements aikido::control::TrajectoryExecutor.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
MetaSkeleton to execute trajectories on For trajectory-validation purposes only.
|
mutableprivate |
Manages access to mInProgress, mPromise.
|
private |
|
private |
|
private |