|
SMACC2
|
#include <cb_pouring_motion.hpp>


Public Member Functions | |
| CbCircularPouringMotion (const geometry_msgs::msg::Point &pivotPoint, double deltaHeight, std::string tipLink, std::string globalFrame) | |
| 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 | onEntry () override |
| virtual void | onExit () override |
| 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 | onEntry () override |
| virtual void | onExit () override |
| virtual void | update () override |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| 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 () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
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< double > | angularSpeed_rad_s_ |
| std::optional< double > | linearSpeed_m_s_ |
| geometry_msgs::msg::Vector3 | directionVector_ |
| geometry_msgs::msg::Pose | pointerRelativePose_ |
Public Attributes inherited from cl_moveit2z::CbMoveEndEffectorTrajectory | |
| std::optional< std::string > | group_ |
| std::optional< std::string > | tipLink_ |
| std::optional< bool > | allowInitialTrajectoryStateJointDiscontinuity_ |
Protected Attributes | |
| geometry_msgs::msg::Point | relativePivotPoint_ |
| double | deltaHeight_ |
| std::vector< geometry_msgs::msg::PoseStamped > | pointerTrajectory_ |
Protected Attributes inherited from cl_moveit2z::CbMoveEndEffectorTrajectory | |
| std::vector< geometry_msgs::msg::PoseStamped > | endEffectorTrajectory_ |
| ClMoveit2z * | movegroupClient_ = nullptr |
| visualization_msgs::msg::MarkerArray | beahiorMarkers_ |
Private Member Functions | |
| void | computeCurrentEndEffectorPoseRelativeToPivot () |
Private Attributes | |
| std::string | globalFrame_ |
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 > ¤tEndEffectorTransform) |
| ComputeJointTrajectoryErrorCode | computeJointSpaceTrajectory (moveit_msgs::msg::RobotTrajectory &computedJointTrajectory) |
| void | executeJointSpaceTrajectory (const moveit_msgs::msg::RobotTrajectory &computedJointTrajectory) |
| void | getCurrentEndEffectorPose (std::string globalFrame, tf2::Stamped< tf2::Transform > ¤tEndEffectorTransform) |
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 () |
| ISmaccState * | getCurrentState () |
| virtual rclcpp::Node::SharedPtr | getNode () const |
| virtual rclcpp::Logger | getLogger () const |
Protected Member Functions inherited from smacc2::ISmaccUpdatable | |
Definition at line 27 of file cb_pouring_motion.hpp.
| cl_moveit2z::CbCircularPouringMotion::CbCircularPouringMotion | ( | const geometry_msgs::msg::Point & | pivotPoint, |
| double | deltaHeight, | ||
| std::string | tipLink, | ||
| std::string | globalFrame ) |
Definition at line 27 of file cb_pouring_motion.cpp.
|
private |
|
overridevirtual |
Reimplemented from cl_moveit2z::CbMoveEndEffectorTrajectory.
Definition at line 146 of file cb_pouring_motion.cpp.
References cl_moveit2z::CbMoveEndEffectorTrajectory::beahiorMarkers_, cl_moveit2z::CbMoveEndEffectorTrajectory::createMarkers(), cl_moveit2z::CbMoveEndEffectorTrajectory::getCurrentEndEffectorPose(), smacc2::ISmaccClientBehavior::getNode(), globalFrame_, pointerTrajectory_, and relativePivotPoint_.

|
overridevirtual |
Reimplemented from cl_moveit2z::CbMoveEndEffectorTrajectory.
Definition at line 38 of file cb_pouring_motion.cpp.
References deltaHeight_, cl_moveit2z::CbMoveEndEffectorTrajectory::endEffectorTrajectory_, cl_moveit2z::CbMoveEndEffectorTrajectory::getCurrentEndEffectorPose(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), globalFrame_, linearSpeed_m_s_, pointerRelativePose_, pointerTrajectory_, and relativePivotPoint_.

| std::optional<double> cl_moveit2z::CbCircularPouringMotion::angularSpeed_rad_s_ |
Definition at line 30 of file cb_pouring_motion.hpp.
|
protected |
Definition at line 52 of file cb_pouring_motion.hpp.
Referenced by generateTrajectory().
| geometry_msgs::msg::Vector3 cl_moveit2z::CbCircularPouringMotion::directionVector_ |
Definition at line 42 of file cb_pouring_motion.hpp.
|
private |
Definition at line 59 of file cb_pouring_motion.hpp.
Referenced by createMarkers(), and generateTrajectory().
| std::optional<double> cl_moveit2z::CbCircularPouringMotion::linearSpeed_m_s_ |
Definition at line 32 of file cb_pouring_motion.hpp.
Referenced by generateTrajectory().
| geometry_msgs::msg::Pose cl_moveit2z::CbCircularPouringMotion::pointerRelativePose_ |
Definition at line 46 of file cb_pouring_motion.hpp.
Referenced by generateTrajectory().
|
protected |
Definition at line 54 of file cb_pouring_motion.hpp.
Referenced by createMarkers(), and generateTrajectory().
|
protected |
Definition at line 49 of file cb_pouring_motion.hpp.
Referenced by createMarkers(), and generateTrajectory().