|
SMACC
|
#include <cb_undo_last_trajectory.h>


Public Member Functions | |
| CbUndoLastTrajectory () | |
| CbUndoLastTrajectory (int backIndex) | |
| virtual | ~CbUndoLastTrajectory () |
| virtual void | onEntry () override |
Public Member Functions inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory | |
| CbMoveEndEffectorTrajectory (std::string tipLink="") | |
| CbMoveEndEffectorTrajectory (const std::vector< geometry_msgs::PoseStamped > &endEffectorTrajectory, std::string tipLink="") | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| virtual void | onEntry () override |
| virtual void | onExit () override |
| virtual void | update () override |
Public Member Functions inherited from smacc::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| virtual | ~SmaccAsyncClientBehavior () |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onSuccess (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFinished (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFailure (TCallback callback, T *object) |
Public Member Functions inherited from smacc::ISmaccClientBehavior | |
| ISmaccClientBehavior () | |
| virtual | ~ISmaccClientBehavior () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage) |
| ros::NodeHandle | getNode () |
Public Member Functions inherited from smacc::ISmaccUpdatable | |
| ISmaccUpdatable () | |
| ISmaccUpdatable (ros::Duration duration) | |
| void | executeUpdate () |
| void | setUpdatePeriod (ros::Duration duration) |
Private Attributes | |
| int | backIndex_ = -1 |
| moveit_msgs::RobotTrajectory | trajectory |
| moveit_msgs::RobotTrajectory | reversed |
Additional Inherited Members | |
Public Attributes inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory | |
| boost::optional< std::string > | group_ |
| boost::optional< std::string > | tipLink_ |
| boost::optional< bool > | allowInitialTrajectoryStateJointDiscontinuity_ |
Protected Member Functions inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory | |
| ComputeJointTrajectoryErrorCode | computeJointSpaceTrajectory (moveit_msgs::RobotTrajectory &computedJointTrajectory) |
| void | executeJointSpaceTrajectory (const moveit_msgs::RobotTrajectory &computedJointTrajectory) |
| virtual void | generateTrajectory () |
| virtual void | createMarkers () |
| void | getCurrentEndEffectorPose (std::string globalFrame, tf::StampedTransform ¤tEndEffectorTransform) |
Protected Member Functions inherited from smacc::SmaccAsyncClientBehavior | |
| virtual void | executeOnEntry () override |
| virtual void | executeOnExit () override |
| void | postSuccessEvent () |
| void | postFailureEvent () |
| virtual void | dispose () override |
Protected Member Functions inherited from smacc::ISmaccClientBehavior | |
| virtual void | runtimeConfigure () |
| virtual void | onEntry () |
| virtual void | onExit () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| ISmaccState * | getCurrentState () |
| virtual void | executeOnEntry () |
| virtual void | executeOnExit () |
| virtual void | dispose () |
| virtual void | update ()=0 |
Protected Attributes inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory | |
| std::vector< geometry_msgs::PoseStamped > | endEffectorTrajectory_ |
| ClMoveGroup * | movegroupClient_ = nullptr |
| visualization_msgs::MarkerArray | beahiorMarkers_ |
Definition at line 13 of file cb_undo_last_trajectory.h.
| cl_move_group_interface::CbUndoLastTrajectory::CbUndoLastTrajectory | ( | ) |
Definition at line 12 of file cb_undo_last_trajectory.cpp.
| cl_move_group_interface::CbUndoLastTrajectory::CbUndoLastTrajectory | ( | int | backIndex | ) |
Definition at line 16 of file cb_undo_last_trajectory.cpp.
|
virtual |
Definition at line 21 of file cb_undo_last_trajectory.cpp.
|
overridevirtual |
Reimplemented from cl_move_group_interface::CbMoveEndEffectorTrajectory.
Definition at line 25 of file cb_undo_last_trajectory.cpp.
References backIndex_, cl_move_group_interface::CbMoveEndEffectorTrajectory::executeJointSpaceTrajectory(), cl_move_group_interface::CpTrajectoryHistory::getLastTrajectory(), cl_move_group_interface::CbMoveEndEffectorTrajectory::movegroupClient_, smacc::ISmaccClientBehavior::requiresClient(), smacc::ISmaccClientBehavior::requiresComponent(), reversed, and trajectory.

|
private |
Definition at line 24 of file cb_undo_last_trajectory.h.
Referenced by onEntry().
|
private |
Definition at line 27 of file cb_undo_last_trajectory.h.
Referenced by onEntry().
|
private |
Definition at line 26 of file cb_undo_last_trajectory.h.
Referenced by onEntry().