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

#include <cb_move_cartesian_relative.h>

Inheritance diagram for cl_move_group_interface::CbMoveCartesianRelative:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbMoveCartesianRelative:
Collaboration graph

Public Member Functions

 CbMoveCartesianRelative ()
 
 CbMoveCartesianRelative (geometry_msgs::Vector3 offset)
 
virtual void onEntry () override
 
virtual void onExit () override
 
void moveRelativeCartesian (moveit::planning_interface::MoveGroupInterface *movegroupClient, geometry_msgs::Vector3 &offset)
 
- 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::Vector3 offset_
 
boost::optional< double > scalingFactor_
 
boost::optional< std::string > group_
 
ClMoveGroupmoveGroupSmaccClient_
 

Additional Inherited Members

- 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 ()
 

Detailed Description

Definition at line 14 of file cb_move_cartesian_relative.h.

Constructor & Destructor Documentation

◆ CbMoveCartesianRelative() [1/2]

cl_move_group_interface::CbMoveCartesianRelative::CbMoveCartesianRelative ( )

Definition at line 11 of file cb_move_cartesian_relative.cpp.

12{
13}

◆ CbMoveCartesianRelative() [2/2]

cl_move_group_interface::CbMoveCartesianRelative::CbMoveCartesianRelative ( geometry_msgs::Vector3  offset)

Definition at line 15 of file cb_move_cartesian_relative.cpp.

15 : offset_(offset)
16{
17}

Member Function Documentation

◆ moveRelativeCartesian()

void cl_move_group_interface::CbMoveCartesianRelative::moveRelativeCartesian ( moveit::planning_interface::MoveGroupInterface *  movegroupClient,
geometry_msgs::Vector3 &  offset 
)

Definition at line 40 of file cb_move_cartesian_relative.cpp.

42{
43 std::vector<geometry_msgs::Pose> waypoints;
44
45 // this one was working fine but the issue is that for relative motions it grows up on ABORT-State-Loop pattern.
46 // But, we need current pose because maybe setCurrentPose was not set by previous behaviors. The only solution would be
47 // distinguishing between the execution error and the planning error with no state change
48 //auto referenceStartPose = movegroupClient->getPoseTarget();
49 auto referenceStartPose = movegroupClient->getCurrentPose();
50 movegroupClient->setPoseReferenceFrame(referenceStartPose.header.frame_id);
51
52 ROS_INFO_STREAM("[CbMoveCartesianRelative] RELATIVE MOTION, SOURCE POSE: " << referenceStartPose);
53 ROS_INFO_STREAM("[CbMoveCartesianRelative] Offset: " << offset);
54
55 waypoints.push_back(referenceStartPose.pose); // up and out
56
57 auto endPose = referenceStartPose.pose;
58
59 endPose.position.x += offset.x;
60 endPose.position.y += offset.y;
61 endPose.position.z += offset.z;
62
63 ROS_INFO_STREAM("[CbMoveCartesianRelative] DESTINY POSE: " << endPose);
64
65 // target_pose2.position.x -= 0.15;
66 waypoints.push_back(endPose); // left
67
68 movegroupClient->setPoseTarget(endPose);
69
70 float scalinf = 0.5;
72 scalinf = *scalingFactor_;
73
74 ROS_INFO_STREAM("[CbMoveCartesianRelative] Using scaling factor: " << scalinf);
75 movegroupClient->setMaxVelocityScalingFactor(scalinf);
76
77 moveit_msgs::RobotTrajectory trajectory;
78 double fraction = movegroupClient->computeCartesianPath(waypoints,
79 0.01, // eef_step
80 0.00, // jump_threshold
81 trajectory);
82
83 moveit::core::MoveItErrorCode behaviorResult;
84 if (fraction != 1.0 || fraction == -1)
85 {
86 ROS_WARN_STREAM("[CbMoveCartesianRelative] Cartesian plan joint-continuity percentaje. Execution skipped because not 100% of cartesian motion: " << fraction*100<<"%");
87 behaviorResult = moveit::core::MoveItErrorCode::PLANNING_FAILED;
88 }
89 else
90 {
91 ROS_INFO_STREAM("[CbMoveCartesianRelative] Cartesian plan joint-continuity percentaje: " << fraction);
92
93 moveit::planning_interface::MoveGroupInterface::Plan grasp_pose_plan;
94
95 // grasp_pose_plan.start_state_ = *(moveGroupInterface.getCurrentState());
96 grasp_pose_plan.trajectory_ = trajectory;
97 behaviorResult = movegroupClient->execute(grasp_pose_plan);
98 }
99
100 if (behaviorResult == moveit_msgs::MoveItErrorCodes::SUCCESS)
101 {
102 ROS_INFO("[CbMoveCartesianRelative] relative motion execution succeeded: fraction %lf.", fraction);
104 this->postSuccessEvent();
105 }
106 else
107 {
108 movegroupClient->setPoseTarget(referenceStartPose); // undo changes since we did not executed the motion
109 ROS_INFO("[CbMoveCartesianRelative] relative motion execution failed: fraction %lf.", fraction);
111 this->postFailureEvent();
112 }
113}

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

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

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 19 of file cb_move_cartesian_relative.cpp.

20{
22
23 if (this->group_)
24 {
25 moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));
26 this->moveRelativeCartesian(&move_group, offset_);
27 }
28 else
29 {
31 }
32}
void moveRelativeCartesian(moveit::planning_interface::MoveGroupInterface *movegroupClient, geometry_msgs::Vector3 &offset)
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
Definition: cl_movegroup.h:74
void requiresClient(SmaccClientType *&storage)

References group_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, moveGroupSmaccClient_, moveRelativeCartesian(), offset_, and smacc::ISmaccClientBehavior::requiresClient().

Here is the call graph for this function:

◆ onExit()

void cl_move_group_interface::CbMoveCartesianRelative::onExit ( )
overridevirtual

Reimplemented from smacc::ISmaccClientBehavior.

Definition at line 34 of file cb_move_cartesian_relative.cpp.

35{
36
37}

Member Data Documentation

◆ group_

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

Definition at line 21 of file cb_move_cartesian_relative.h.

Referenced by onEntry().

◆ moveGroupSmaccClient_

ClMoveGroup* cl_move_group_interface::CbMoveCartesianRelative::moveGroupSmaccClient_

Definition at line 35 of file cb_move_cartesian_relative.h.

Referenced by moveRelativeCartesian(), and onEntry().

◆ offset_

geometry_msgs::Vector3 cl_move_group_interface::CbMoveCartesianRelative::offset_

Definition at line 17 of file cb_move_cartesian_relative.h.

Referenced by onEntry().

◆ scalingFactor_

boost::optional<double> cl_move_group_interface::CbMoveCartesianRelative::scalingFactor_

Definition at line 19 of file cb_move_cartesian_relative.h.

Referenced by moveRelativeCartesian().


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