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

#include <cb_move_end_effector_relative.h>

Inheritance diagram for cl_move_group_interface::CbMoveEndEffectorRelative:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbMoveEndEffectorRelative:
Collaboration graph

Public Member Functions

 CbMoveEndEffectorRelative ()
 
 CbMoveEndEffectorRelative (geometry_msgs::Transform transform)
 
virtual void onEntry () override
 
virtual void onExit () 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 Attributes

geometry_msgs::Transform transform_
 
boost::optional< std::string > group_
 

Protected Member Functions

void moveRelative (moveit::planning_interface::MoveGroupInterface &moveGroupinterface, geometry_msgs::Transform &transformOffset)
 
- 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 ()
 

Protected Attributes

ClMoveGroupmovegroupClient_
 

Detailed Description

Definition at line 14 of file cb_move_end_effector_relative.h.

Constructor & Destructor Documentation

◆ CbMoveEndEffectorRelative() [1/2]

cl_move_group_interface::CbMoveEndEffectorRelative::CbMoveEndEffectorRelative ( )

Definition at line 14 of file cb_move_end_effector_relative.cpp.

15 {
16 transform_.rotation.w = 1;
17 }

References transform_.

◆ CbMoveEndEffectorRelative() [2/2]

cl_move_group_interface::CbMoveEndEffectorRelative::CbMoveEndEffectorRelative ( geometry_msgs::Transform  transform)

Definition at line 19 of file cb_move_end_effector_relative.cpp.

20 {
21 }

Member Function Documentation

◆ moveRelative()

void cl_move_group_interface::CbMoveEndEffectorRelative::moveRelative ( moveit::planning_interface::MoveGroupInterface &  moveGroupinterface,
geometry_msgs::Transform &  transformOffset 
)
protected

Definition at line 44 of file cb_move_end_effector_relative.cpp.

45 {
46 auto referenceStartPose = moveGroupInterface.getCurrentPose();
47 tf::Quaternion currentOrientation;
48 tf::quaternionMsgToTF(referenceStartPose.pose.orientation, currentOrientation);
49 tf::Quaternion desiredRelativeRotation;
50
51 tf::quaternionMsgToTF(transformOffset.rotation, desiredRelativeRotation);
52
53 auto targetOrientation = desiredRelativeRotation * currentOrientation;
54
55 geometry_msgs::PoseStamped targetObjectPose = referenceStartPose;
56
57 tf::quaternionTFToMsg(targetOrientation, targetObjectPose.pose.orientation);
58 targetObjectPose.pose.position.x += transformOffset.translation.x;
59 targetObjectPose.pose.position.y += transformOffset.translation.y;
60 targetObjectPose.pose.position.z += transformOffset.translation.z;
61
62 moveGroupInterface.setPlanningTime(1.0);
63
64 ROS_INFO_STREAM("[CbMoveEndEffectorRelative] Target End efector Pose: " << targetObjectPose);
65
66 moveGroupInterface.setPoseTarget(targetObjectPose);
67 moveGroupInterface.setPoseReferenceFrame("map");
68
69 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
70 bool success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
71 ROS_INFO_NAMED("CbMoveEndEffectorRelative", "Success Visualizing plan 1 (pose goal) %s", success ? "" : "FAILED");
72
73 if (success)
74 {
75 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
76
77 if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)
78 {
79 ROS_INFO("[CbMoveEndEffectorRelative] motion execution succeeded");
81 this->postSuccessEvent();
82 }
83 else
84 {
85 moveGroupInterface.setPoseTarget(referenceStartPose); // undo to avoid abort-repeat state issues with this relative motion
86 ROS_INFO("[CbMoveEndEffectorRelative] motion execution failed");
88 this->postFailureEvent();
89 }
90 }
91 else
92 {
93 moveGroupInterface.setPoseTarget(referenceStartPose); //undo since we did not executed the motion
94 ROS_INFO("[CbMoveEndEffectorRelative] motion execution failed");
96 this->postFailureEvent();
97 }
98 }

References movegroupClient_, cl_move_group_interface::ClMoveGroup::postEventMotionExecutionFailed(), cl_move_group_interface::ClMoveGroup::postEventMotionExecutionSucceded(), smacc::SmaccAsyncClientBehavior::postFailureEvent(), and smacc::SmaccAsyncClientBehavior::postSuccessEvent().

Referenced by onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onEntry()

void cl_move_group_interface::CbMoveEndEffectorRelative::onEntry ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 23 of file cb_move_end_effector_relative.cpp.

24 {
25 ROS_INFO_STREAM("[CbMoveEndEffectorRelative] Transform end effector pose relative: " << transform_);
26
28
29 if (this->group_)
30 {
31 moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));
32 this->moveRelative(move_group, this->transform_);
33 }
34 else
35 {
37 }
38 }
void moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupinterface, geometry_msgs::Transform &transformOffset)
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
Definition: cl_movegroup.h:74
void requiresClient(SmaccClientType *&storage)

References group_, movegroupClient_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, moveRelative(), smacc::ISmaccClientBehavior::requiresClient(), and transform_.

Here is the call graph for this function:

◆ onExit()

void cl_move_group_interface::CbMoveEndEffectorRelative::onExit ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 40 of file cb_move_end_effector_relative.cpp.

41 {
42 }

Member Data Documentation

◆ group_

boost::optional<std::string> cl_move_group_interface::CbMoveEndEffectorRelative::group_

Definition at line 19 of file cb_move_end_effector_relative.h.

Referenced by onEntry().

◆ movegroupClient_

ClMoveGroup* cl_move_group_interface::CbMoveEndEffectorRelative::movegroupClient_
protected

Definition at line 33 of file cb_move_end_effector_relative.h.

Referenced by moveRelative(), and onEntry().

◆ transform_

geometry_msgs::Transform cl_move_group_interface::CbMoveEndEffectorRelative::transform_

Definition at line 17 of file cb_move_end_effector_relative.h.

Referenced by CbMoveEndEffectorRelative(), and onEntry().


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