SMACC
Loading...
Searching...
No Matches
cb_move_end_effector_relative.cpp
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018-2020
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6
8#include <tf/tf.h>
9#include <tf/transform_datatypes.h>
10#include <future>
11
13{
15 {
16 transform_.rotation.w = 1;
17 }
18
19 CbMoveEndEffectorRelative::CbMoveEndEffectorRelative(geometry_msgs::Transform transform)
20 {
21 }
22
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 }
39
41 {
42 }
43
44 void CbMoveEndEffectorRelative::moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::Transform &transformOffset)
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 }
99} // namespace cl_move_group_interface
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)