SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
cl_moveit2z::CbEndEffectorRotate Class Reference

#include <cb_end_effector_rotate.hpp>

Inheritance diagram for cl_moveit2z::CbEndEffectorRotate:
Inheritance graph
Collaboration diagram for cl_moveit2z::CbEndEffectorRotate:
Collaboration graph

Public Member Functions

 CbEndEffectorRotate (double deltaRadians, std::optional< std::string > tipLink=std::nullopt)
 
virtual ~CbEndEffectorRotate ()
 
virtual void onEntry () override
 
- Public Member Functions inherited from cl_moveit2z::CbCircularPivotMotion
 CbCircularPivotMotion (std::optional< std::string > tipLink=std::nullopt)
 
 CbCircularPivotMotion (const geometry_msgs::msg::PoseStamped &planePivotPose, double deltaRadians, std::optional< std::string > tipLink=std::nullopt)
 
 CbCircularPivotMotion (const geometry_msgs::msg::PoseStamped &planePivotPose, const geometry_msgs::msg::Pose &relativeInitialPose, double deltaRadians, std::optional< std::string > tipLink=std::nullopt)
 
virtual void generateTrajectory () override
 
virtual void createMarkers () override
 
- Public Member Functions inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
 CbMoveEndEffectorTrajectory (std::optional< std::string > tipLink=std::nullopt)
 
 CbMoveEndEffectorTrajectory (const std::vector< geometry_msgs::msg::PoseStamped > &endEffectorTrajectory, std::optional< std::string > tipLink=std::nullopt)
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual void onExit () override
 
virtual void update () override
 
- Public Member Functions inherited from smacc2::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)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
 
- Public Member Functions inherited from smacc2::ISmaccUpdatable
 ISmaccUpdatable ()
 
 ISmaccUpdatable (rclcpp::Duration duration)
 
void executeUpdate (rclcpp::Node::SharedPtr node)
 
void setUpdatePeriod (rclcpp::Duration duration)
 

Public Attributes

std::optional< std::string > tipLink
 
- Public Attributes inherited from cl_moveit2z::CbCircularPivotMotion
std::optional< double > angularSpeed_rad_s_
 
std::optional< double > linearSpeed_m_s_
 
std::optional< geometry_msgs::msg::Pose > relativeInitialPose_
 
- Public Attributes inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
std::optional< std::string > group_
 
std::optional< std::string > tipLink_
 
std::optional< boolallowInitialTrajectoryStateJointDiscontinuity_
 

Additional Inherited Members

- Protected Member Functions inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory (moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
 
void executeJointSpaceTrajectory (const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory)
 
void getCurrentEndEffectorPose (std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
 
- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 
- Protected Attributes inherited from cl_moveit2z::CbCircularPivotMotion
geometry_msgs::msg::PoseStamped planePivotPose_
 
double deltaRadians_
 
- Protected Attributes inherited from cl_moveit2z::CbMoveEndEffectorTrajectory
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
 
ClMoveit2zmovegroupClient_ = nullptr
 
visualization_msgs::msg::MarkerArray beahiorMarkers_
 

Detailed Description

Definition at line 26 of file cb_end_effector_rotate.hpp.

Constructor & Destructor Documentation

◆ CbEndEffectorRotate()

cl_moveit2z::CbEndEffectorRotate::CbEndEffectorRotate ( double  deltaRadians,
std::optional< std::string >  tipLink = std::nullopt 
)

Definition at line 34 of file cb_end_effector_rotate.cpp.

36{
37 deltaRadians_ = deltaRadians;
38}
CbCircularPivotMotion(std::optional< std::string > tipLink=std::nullopt)
std::optional< std::string > tipLink

References cl_moveit2z::CbCircularPivotMotion::deltaRadians_.

◆ ~CbEndEffectorRotate()

cl_moveit2z::CbEndEffectorRotate::~CbEndEffectorRotate ( )
virtual

Definition at line 40 of file cb_end_effector_rotate.cpp.

40{}

Member Function Documentation

◆ onEntry()

void cl_moveit2z::CbEndEffectorRotate::onEntry ( )
overridevirtual

Reimplemented from cl_moveit2z::CbMoveEndEffectorTrajectory.

Definition at line 42 of file cb_end_effector_rotate.cpp.

43{
44 // autocompute pivot pose
45 tf2_ros::Buffer tfBuffer(getNode()->get_clock());
46 tf2_ros::TransformListener tfListener(tfBuffer);
47
48 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
49
50 int attempts = 3;
51
53 if (!tipLink_)
54 {
55 tipLink_ = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
56 RCLCPP_WARN_STREAM(
57 getLogger(),
58 "[" << getName() << "] tip unspecified, using default end effector: " << *tipLink_);
59 }
60
61 while (attempts > 0)
62 {
63 try
64 {
65 //auto pivotFrameName = this->movegroupClient_->moveGroupClientInterface->getPlanningFrame();
66 auto pivotFrameName = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
67
68 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
69
70 tf2::fromMsg(
71 tfBuffer.lookupTransform(pivotFrameName, *tipLink_, rclcpp::Time(), rclcpp::Duration(10s)),
72 endEffectorInPivotFrame);
73
74 tf2::toMsg(endEffectorInPivotFrame, this->planePivotPose_.pose);
75 this->planePivotPose_.header.frame_id = endEffectorInPivotFrame.frame_id_;
76 this->planePivotPose_.header.stamp =
77 rclcpp::Time(endEffectorInPivotFrame.stamp_.time_since_epoch().count());
78 break;
79 }
80 catch (const std::exception & e)
81 {
82 RCLCPP_ERROR_STREAM(getLogger(), e.what() << ". Attempt countdown: " << attempts);
83 rclcpp::Duration(500ms);
84 attempts--;
85 }
86 }
87
88 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] pivotPose: " << planePivotPose_);
89
90 RCLCPP_INFO_STREAM(
91 getLogger(), "[" << getName() << "] calling base CbCircularPivotMotion::onEntry");
93}
geometry_msgs::msg::PoseStamped planePivotPose_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)

References smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_moveit2z::CbMoveEndEffectorTrajectory::movegroupClient_, cl_moveit2z::ClMoveit2z::moveGroupClientInterface, smacc2::ISmaccClientBehavior::onEntry(), cl_moveit2z::CbCircularPivotMotion::planePivotPose_, smacc2::ISmaccClientBehavior::requiresClient(), and cl_moveit2z::CbMoveEndEffectorTrajectory::tipLink_.

Here is the call graph for this function:

Member Data Documentation

◆ tipLink

std::optional<std::string> cl_moveit2z::CbEndEffectorRotate::tipLink

Definition at line 35 of file cb_end_effector_rotate.hpp.


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