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

#include <cb_move_end_effector.h>

Inheritance diagram for cl_move_group_interface::CbMoveEndEffector:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbMoveEndEffector:
Collaboration graph

Public Member Functions

 CbMoveEndEffector ()
 
 CbMoveEndEffector (geometry_msgs::PoseStamped target_pose, std::string tip_link="")
 
virtual void onEntry () 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::PoseStamped targetPose
 
std::string tip_link_
 
boost::optional< std::string > group_
 

Protected Member Functions

bool moveToAbsolutePose (moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::PoseStamped &targetObjectPose)
 
- 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.h.

Constructor & Destructor Documentation

◆ CbMoveEndEffector() [1/2]

cl_move_group_interface::CbMoveEndEffector::CbMoveEndEffector ( )

Definition at line 14 of file cb_move_end_effector.cpp.

15{
16}

◆ CbMoveEndEffector() [2/2]

cl_move_group_interface::CbMoveEndEffector::CbMoveEndEffector ( geometry_msgs::PoseStamped  target_pose,
std::string  tip_link = "" 
)

Definition at line 18 of file cb_move_end_effector.cpp.

19 : targetPose(target_pose)
20{
21 tip_link_ = tip_link;
22}

References tip_link_.

Member Function Documentation

◆ moveToAbsolutePose()

bool cl_move_group_interface::CbMoveEndEffector::moveToAbsolutePose ( moveit::planning_interface::MoveGroupInterface &  moveGroupInterface,
geometry_msgs::PoseStamped &  targetObjectPose 
)
protected

Definition at line 43 of file cb_move_end_effector.cpp.

45{
46 auto& planningSceneInterface = movegroupClient_->planningSceneInterface;
47 ROS_DEBUG("[CbMoveEndEffector] Synchronous sleep of 1 seconds");
48 ros::Duration(0.5).sleep();
49
50 moveGroupInterface.setPlanningTime(1.0);
51
52 ROS_INFO_STREAM("[CbMoveEndEffector] Target End efector Pose: " << targetObjectPose);
53
54 moveGroupInterface.setPoseTarget(targetObjectPose, tip_link_);
55 moveGroupInterface.setPoseReferenceFrame(targetObjectPose.header.frame_id);
56
57 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
58 bool success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
59 ROS_INFO_NAMED("CbMoveEndEffector", "Success Visualizing plan 1 (pose goal) %s", success ? "" : "FAILED");
60
61 if (success)
62 {
63 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
64
65 if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)
66 {
67 ROS_INFO("[CbMoveEndEffector] motion execution succeeded");
69 this->postSuccessEvent();
70
71 }
72 else
73 {
74 ROS_INFO("[CbMoveEndEffector] motion execution failed");
76 this->postFailureEvent();
77 }
78 }
79 else
80 {
81 ROS_INFO("[CbMoveEndEffector] motion execution failed");
83 this->postFailureEvent();
84 }
85
86 ROS_DEBUG("[CbMoveEndEffector] Synchronous sleep of 1 seconds");
87 ros::Duration(0.5).sleep();
88
89 return success;
90}
moveit::planning_interface::PlanningSceneInterface planningSceneInterface
Definition: cl_movegroup.h:76

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

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::CbMoveEndEffector::onEntry ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 24 of file cb_move_end_effector.cpp.

25{
27
28 if (this->group_)
29 {
30 ROS_DEBUG("[CbMoveEndEfector] new thread started to move absolute end effector");
31 moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));
32 this->moveToAbsolutePose(move_group, targetPose);
33 ROS_DEBUG("[CbMoveEndEfector] to move absolute end effector thread destroyed");
34 }
35 else
36 {
37 ROS_DEBUG("[CbMoveEndEfector] new thread started to move absolute end effector");
39 ROS_DEBUG("[CbMoveEndEfector] to move absolute end effector thread destroyed");
40 }
41}
bool moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::PoseStamped &targetObjectPose)
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
Definition: cl_movegroup.h:74
void requiresClient(SmaccClientType *&storage)

References group_, movegroupClient_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, moveToAbsolutePose(), smacc::ISmaccClientBehavior::requiresClient(), and targetPose.

Here is the call graph for this function:

Member Data Documentation

◆ group_

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

Definition at line 19 of file cb_move_end_effector.h.

Referenced by onEntry().

◆ movegroupClient_

ClMoveGroup* cl_move_group_interface::CbMoveEndEffector::movegroupClient_
protected

Definition at line 30 of file cb_move_end_effector.h.

Referenced by moveToAbsolutePose(), and onEntry().

◆ targetPose

geometry_msgs::PoseStamped cl_move_group_interface::CbMoveEndEffector::targetPose

Definition at line 17 of file cb_move_end_effector.h.

Referenced by onEntry().

◆ tip_link_

std::string cl_move_group_interface::CbMoveEndEffector::tip_link_

Definition at line 18 of file cb_move_end_effector.h.

Referenced by CbMoveEndEffector(), and moveToAbsolutePose().


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