SMACC
Loading...
Searching...
No Matches
Public Member Functions | Private Attributes | List of all members
cl_move_group_interface::CbUndoLastTrajectory Class Reference

#include <cb_undo_last_trajectory.h>

Inheritance diagram for cl_move_group_interface::CbUndoLastTrajectory:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbUndoLastTrajectory:
Collaboration graph

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 ()
 
ISmaccStateMachinegetStateMachine ()
 
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< boolallowInitialTrajectoryStateJointDiscontinuity_
 
- 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 &currentEndEffectorTransform)
 
- 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 ()
 
ISmaccStategetCurrentState ()
 
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_
 
ClMoveGroupmovegroupClient_ = nullptr
 
visualization_msgs::MarkerArray beahiorMarkers_
 

Detailed Description

Definition at line 13 of file cb_undo_last_trajectory.h.

Constructor & Destructor Documentation

◆ CbUndoLastTrajectory() [1/2]

cl_move_group_interface::CbUndoLastTrajectory::CbUndoLastTrajectory ( )

Definition at line 12 of file cb_undo_last_trajectory.cpp.

13 {
14 }

◆ CbUndoLastTrajectory() [2/2]

cl_move_group_interface::CbUndoLastTrajectory::CbUndoLastTrajectory ( int  backIndex)

Definition at line 16 of file cb_undo_last_trajectory.cpp.

◆ ~CbUndoLastTrajectory()

cl_move_group_interface::CbUndoLastTrajectory::~CbUndoLastTrajectory ( )
virtual

Definition at line 21 of file cb_undo_last_trajectory.cpp.

22 {
23 }

Member Function Documentation

◆ onEntry()

void cl_move_group_interface::CbUndoLastTrajectory::onEntry ( )
overridevirtual

Reimplemented from cl_move_group_interface::CbMoveEndEffectorTrajectory.

Definition at line 25 of file cb_undo_last_trajectory.cpp.

26 {
27 CpTrajectoryHistory *trajectoryHistory;
28 this->requiresComponent(trajectoryHistory);
30
31 if (trajectoryHistory->getLastTrajectory(backIndex_, trajectory))
32 {
33 auto initialTime = trajectory.joint_trajectory.points.back().time_from_start;
34
36
37 std::reverse(reversed.joint_trajectory.points.begin(), reversed.joint_trajectory.points.end());
38
39 for (auto &jp : reversed.joint_trajectory.points)
40 {
41 jp.time_from_start = ros::Duration(fabs(jp.time_from_start.toSec() - initialTime.toSec())); //ros::Duration(t);
42 }
43
45 }
46 }
void executeJointSpaceTrajectory(const moveit_msgs::RobotTrajectory &computedJointTrajectory)
void requiresComponent(SmaccComponentType *&storage)
void requiresClient(SmaccClientType *&storage)

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.

Here is the call graph for this function:

Member Data Documentation

◆ backIndex_

int cl_move_group_interface::CbUndoLastTrajectory::backIndex_ = -1
private

Definition at line 24 of file cb_undo_last_trajectory.h.

Referenced by onEntry().

◆ reversed

moveit_msgs::RobotTrajectory cl_move_group_interface::CbUndoLastTrajectory::reversed
private

Definition at line 27 of file cb_undo_last_trajectory.h.

Referenced by onEntry().

◆ trajectory

moveit_msgs::RobotTrajectory cl_move_group_interface::CbUndoLastTrajectory::trajectory
private

Definition at line 26 of file cb_undo_last_trajectory.h.

Referenced by onEntry().


The documentation for this class was generated from the following files: