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

#include <cb_end_effector_rotate.h>

Inheritance diagram for cl_move_group_interface::CbEndEffectorRotate:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbEndEffectorRotate:
Collaboration graph

Public Member Functions

 CbEndEffectorRotate (double deltaRadians, std::string tipLink="")
 
virtual ~CbEndEffectorRotate ()
 
virtual void onEntry () override
 
- Public Member Functions inherited from cl_move_group_interface::CbCircularPivotMotion
 CbCircularPivotMotion (std::string tipLink="")
 
 CbCircularPivotMotion (const geometry_msgs::PoseStamped &planePivotPose, double deltaRadians, std::string tipLink="")
 
 CbCircularPivotMotion (const geometry_msgs::PoseStamped &planePivotPose, const geometry_msgs::Pose &relativeInitialPose, double deltaRadians, std::string tipLink="")
 
virtual void generateTrajectory () override
 
virtual void createMarkers () 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)
 

Additional Inherited Members

- Public Attributes inherited from cl_move_group_interface::CbCircularPivotMotion
boost::optional< double > angularSpeed_rad_s_
 
boost::optional< double > linearSpeed_m_s_
 
boost::optional< geometry_msgs::Pose > relativeInitialPose_
 
- 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::CbCircularPivotMotion
geometry_msgs::PoseStamped planePivotPose_
 
double deltaRadians_
 
- 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 11 of file cb_end_effector_rotate.h.

Constructor & Destructor Documentation

◆ CbEndEffectorRotate()

cl_move_group_interface::CbEndEffectorRotate::CbEndEffectorRotate ( double  deltaRadians,
std::string  tipLink = "" 
)

◆ ~CbEndEffectorRotate()

cl_move_group_interface::CbEndEffectorRotate::~CbEndEffectorRotate ( )
virtual

Definition at line 11 of file cb_end_effector_rotate.cpp.

12 {
13
14 }

Member Function Documentation

◆ onEntry()

void cl_move_group_interface::CbEndEffectorRotate::onEntry ( )
overridevirtual

Reimplemented from cl_move_group_interface::CbMoveEndEffectorTrajectory.

Definition at line 16 of file cb_end_effector_rotate.cpp.

17 {
18 // autocompute pivot pose
19
20 tf::TransformListener tfListener;
21 // tf::StampedTransform globalBaseLink;
22 tf::StampedTransform endEffectorInPivotFrame;
23
24 int attempts = 3;
25
26 while (attempts > 0)
27 {
28 try
29 {
31 if (!tipLink_ || *tipLink_ == "")
32 {
33 tipLink_ = this->movegroupClient_->moveGroupClientInterface.getEndEffectorLink();
34 }
35
36 auto pivotFrame = this->movegroupClient_->moveGroupClientInterface.getPlanningFrame();
37
38 tf::StampedTransform endEffectorInPivotFrame;
39
40 tfListener.waitForTransform(pivotFrame, *tipLink_, ros::Time(0), ros::Duration(10));
41 tfListener.lookupTransform(pivotFrame, *tipLink_, ros::Time(0), endEffectorInPivotFrame);
42
43 tf::poseTFToMsg(endEffectorInPivotFrame, this->planePivotPose_.pose);
44 this->planePivotPose_.header.frame_id = endEffectorInPivotFrame.frame_id_;
45 this->planePivotPose_.header.stamp = endEffectorInPivotFrame.stamp_;
46 break;
47 }
48 catch (const std::exception &e)
49 {
50 ROS_ERROR_STREAM(e.what() << ". Attempt countdown: " << attempts);
51 ros::Duration(0.5);
52 attempts--;
53 }
54 }
55
57 }
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
Definition: cl_movegroup.h:74
void requiresClient(SmaccClientType *&storage)

References cl_move_group_interface::CbMoveEndEffectorTrajectory::movegroupClient_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, smacc::ISmaccClientBehavior::onEntry(), cl_move_group_interface::CbCircularPivotMotion::planePivotPose_, smacc::ISmaccClientBehavior::requiresClient(), and cl_move_group_interface::CbMoveEndEffectorTrajectory::tipLink_.

Here is the call graph for this function:

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