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

#include <cb_circular_pivot_motion.h>

Inheritance diagram for cl_move_group_interface::CbCircularPivotMotion:
Inheritance graph
Collaboration diagram for cl_move_group_interface::CbCircularPivotMotion:
Collaboration graph

Public Member Functions

 CbCircularPivotMotion (std::string tipLink="")
 
 CbCircularPivotMotion (const geometry_msgs::PoseStamped &planePivotPose, double deltaRadians, std::string tipLink="")
 
 CbCircularPivotMotion (const geometry_msgs::PoseStamped &planePivotPose, const geometry_msgs::Pose &relativeInitialPose, double deltaRadians, std::string tipLink="")
 
virtual void generateTrajectory () override
 
virtual void createMarkers () override
 
- Public Member Functions inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory
 CbMoveEndEffectorTrajectory (std::string tipLink="")
 
 CbMoveEndEffectorTrajectory (const std::vector< geometry_msgs::PoseStamped > &endEffectorTrajectory, std::string tipLink="")
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual void onEntry () override
 
virtual void onExit () override
 
virtual void update () 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 Member Functions inherited from smacc::ISmaccUpdatable
 ISmaccUpdatable ()
 
 ISmaccUpdatable (ros::Duration duration)
 
void executeUpdate ()
 
void setUpdatePeriod (ros::Duration duration)
 

Public Attributes

boost::optional< double > angularSpeed_rad_s_
 
boost::optional< double > linearSpeed_m_s_
 
boost::optional< geometry_msgs::Pose > relativeInitialPose_
 
- Public Attributes inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory
boost::optional< std::string > group_
 
boost::optional< std::string > tipLink_
 
boost::optional< boolallowInitialTrajectoryStateJointDiscontinuity_
 

Protected Attributes

geometry_msgs::PoseStamped planePivotPose_
 
double deltaRadians_
 
- Protected Attributes inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory
std::vector< geometry_msgs::PoseStamped > endEffectorTrajectory_
 
ClMoveGroupmovegroupClient_ = nullptr
 
visualization_msgs::MarkerArray beahiorMarkers_
 

Private Member Functions

void computeCurrentEndEffectorPoseRelativeToPivot ()
 

Additional Inherited Members

- Protected Member Functions inherited from cl_move_group_interface::CbMoveEndEffectorTrajectory
ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory (moveit_msgs::RobotTrajectory &computedJointTrajectory)
 
void executeJointSpaceTrajectory (const moveit_msgs::RobotTrajectory &computedJointTrajectory)
 
virtual void generateTrajectory ()
 
virtual void createMarkers ()
 
void getCurrentEndEffectorPose (std::string globalFrame, tf::StampedTransform &currentEndEffectorTransform)
 
- 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 ()
 
virtual void update ()=0
 

Detailed Description

Definition at line 14 of file cb_circular_pivot_motion.h.

Constructor & Destructor Documentation

◆ CbCircularPivotMotion() [1/3]

cl_move_group_interface::CbCircularPivotMotion::CbCircularPivotMotion ( std::string  tipLink = "")

Definition at line 11 of file cb_circular_pivot_motion.cpp.

◆ CbCircularPivotMotion() [2/3]

cl_move_group_interface::CbCircularPivotMotion::CbCircularPivotMotion ( const geometry_msgs::PoseStamped &  planePivotPose,
double  deltaRadians,
std::string  tipLink = "" 
)

Definition at line 16 of file cb_circular_pivot_motion.cpp.

◆ CbCircularPivotMotion() [3/3]

cl_move_group_interface::CbCircularPivotMotion::CbCircularPivotMotion ( const geometry_msgs::PoseStamped &  planePivotPose,
const geometry_msgs::Pose &  relativeInitialPose,
double  deltaRadians,
std::string  tipLink = "" 
)

Definition at line 21 of file cb_circular_pivot_motion.cpp.

22 : planePivotPose_(planePivotPose), relativeInitialPose_(relativeInitialPose), deltaRadians_(deltaRadians), CbMoveEndEffectorTrajectory(tipLink)
23 {
24 }
boost::optional< geometry_msgs::Pose > relativeInitialPose_

Member Function Documentation

◆ computeCurrentEndEffectorPoseRelativeToPivot()

void cl_move_group_interface::CbCircularPivotMotion::computeCurrentEndEffectorPoseRelativeToPivot ( )
private

Definition at line 121 of file cb_circular_pivot_motion.cpp.

122 {
123 //auto currentRobotEndEffectorPose = this->movegroupClient_->moveGroupClientInterface.getCurrentPose();
124
125 tf::TransformListener tfListener;
126 // tf::StampedTransform globalBaseLink;
127 tf::StampedTransform endEffectorInPivotFrame;
128
129 try
130 {
131 if (!tipLink_ || *tipLink_ == "")
132 {
133 tipLink_ = this->movegroupClient_->moveGroupClientInterface.getEndEffectorLink();
134 }
135
136 tfListener.waitForTransform(planePivotPose_.header.frame_id, *tipLink_, ros::Time(0), ros::Duration(10));
137 tfListener.lookupTransform(planePivotPose_.header.frame_id, *tipLink_, ros::Time(0), endEffectorInPivotFrame);
138
139 // we define here the global frame as the pivot frame id
140 // tfListener.waitForTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, ros::Time(0), ros::Duration(10));
141 // tfListener.lookupTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, ros::Time(0), globalBaseLink);
142 }
143 catch (const std::exception &e)
144 {
145 std::cerr << e.what() << '\n';
146 }
147
148 // tf::Transform endEffectorInBaseLinkFrame;
149 // tf::poseMsgToTF(currentRobotEndEffectorPose.pose, endEffectorInBaseLinkFrame);
150
151 // tf::Transform endEffectorInPivotFrame = globalBaseLink * endEffectorInBaseLinkFrame; // pose composition
152
153 // now pivot and EndEffector share a common reference frame (let say map)
154 // now get the current pose from the pivot reference frame with inverse composition
155 tf::Transform pivotTransform;
156 tf::poseMsgToTF(planePivotPose_.pose, pivotTransform);
157 tf::Transform invertedNewReferenceFrame = pivotTransform.inverse();
158
159 tf::Transform currentPoseRelativeToPivot = invertedNewReferenceFrame * endEffectorInPivotFrame;
160
161 geometry_msgs::Pose finalEndEffectorRelativePose;
162 tf::poseTFToMsg(currentPoseRelativeToPivot, finalEndEffectorRelativePose);
163 relativeInitialPose_ = finalEndEffectorRelativePose;
164 }
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
Definition: cl_movegroup.h:74

References cl_move_group_interface::CbMoveEndEffectorTrajectory::movegroupClient_, cl_move_group_interface::ClMoveGroup::moveGroupClientInterface, planePivotPose_, relativeInitialPose_, and cl_move_group_interface::CbMoveEndEffectorTrajectory::tipLink_.

Referenced by generateTrajectory().

Here is the caller graph for this function:

◆ createMarkers()

void cl_move_group_interface::CbCircularPivotMotion::createMarkers ( )
overridevirtual

Reimplemented from cl_move_group_interface::CbMoveEndEffectorTrajectory.

Definition at line 166 of file cb_circular_pivot_motion.cpp.

167 {
169
170 tf::Transform localdirection;
171 localdirection.setIdentity();
172 localdirection.setOrigin(tf::Vector3(0.12, 0, 0));
173 auto frameid = planePivotPose_.header.frame_id;
174
175 visualization_msgs::Marker marker;
176 marker.header.frame_id = frameid;
177 marker.header.stamp = ros::Time::now();
178 marker.ns = "trajectory";
179 marker.id = beahiorMarkers_.markers.size();
180 marker.type = visualization_msgs::Marker::ARROW;
181 marker.action = visualization_msgs::Marker::ADD;
182 marker.scale.x = 0.01;
183 marker.scale.y = 0.02;
184 marker.scale.z = 0.02;
185 marker.color.a = 1.0;
186 marker.color.r = 0.0;
187 marker.color.g = 0;
188 marker.color.b = 1.0;
189
190 geometry_msgs::Point start, end;
191 start.x = planePivotPose_.pose.position.x;
192 start.y = planePivotPose_.pose.position.y;
193 start.z = planePivotPose_.pose.position.z;
194
195 tf::Transform basetransform;
196 tf::poseMsgToTF(planePivotPose_.pose, basetransform);
197 tf::Transform endarrow = localdirection * basetransform;
198
199 end.x = endarrow.getOrigin().x();
200 end.y = endarrow.getOrigin().y();
201 end.z = endarrow.getOrigin().z();
202
203 marker.pose.orientation.w = 1;
204 marker.points.push_back(start);
205 marker.points.push_back(end);
206
207 beahiorMarkers_.markers.push_back(marker);
208 }

References cl_move_group_interface::CbMoveEndEffectorTrajectory::beahiorMarkers_, cl_move_group_interface::CbMoveEndEffectorTrajectory::createMarkers(), and planePivotPose_.

Here is the call graph for this function:

◆ generateTrajectory()

void cl_move_group_interface::CbCircularPivotMotion::generateTrajectory ( )
overridevirtual

Reimplemented from cl_move_group_interface::CbMoveEndEffectorTrajectory.

Definition at line 26 of file cb_circular_pivot_motion.cpp.

27 {
29 {
31 }
32
33 // project offset into the xy-plane
34 // get the radius
35 double radius = sqrt(relativeInitialPose_->position.z * relativeInitialPose_->position.z + relativeInitialPose_->position.y * relativeInitialPose_->position.y);
36 double initialAngle = atan2(relativeInitialPose_->position.z, relativeInitialPose_->position.y);
37
38 double totallineardist = fabs(radius * deltaRadians_);
39 double totalangulardist = fabs(deltaRadians_);
40
41 // at least 1 sample per centimeter (average)
42 // at least 1 sample per ~1.1 degrees (average)
43
44 const double RADS_PER_SAMPLE = 0.02;
45 const double METERS_PER_SAMPLE = 0.01;
46
47 int totalSamplesCount = std::max(totallineardist / METERS_PER_SAMPLE, totalangulardist / RADS_PER_SAMPLE);
48
49 double linearSecondsPerSample;
50 double angularSecondsPerSamples;
51 double secondsPerSample;
52
54 {
55 linearSecondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
56 }
57 else
58 {
59 linearSecondsPerSample = std::numeric_limits<double>::max();
60 }
61
63 {
64 angularSecondsPerSamples = RADS_PER_SAMPLE / (*angularSpeed_rad_s_);
65 }
66 else
67 {
68 angularSecondsPerSamples = std::numeric_limits<double>::max();
69 }
70
72 {
73 secondsPerSample = 0.5;
74 }
75 else
76 {
77 secondsPerSample = std::min(linearSecondsPerSample, angularSecondsPerSamples);
78 }
79
80 double currentAngle = initialAngle;
81
82 double angleStep = deltaRadians_ / (double)totalSamplesCount;
83
84 tf::Transform tfBasePose;
85 tf::poseMsgToTF(planePivotPose_.pose, tfBasePose);
86
87 for (int i = 0; i < totalSamplesCount; i++)
88 {
89 // relativePose i
90 currentAngle += angleStep;
91 double y = radius * cos(currentAngle);
92 double z = radius * sin(currentAngle);
93
94 geometry_msgs::Pose relativeCurrentPose;
95
96 relativeCurrentPose.position.x = relativeInitialPose_->position.x;
97 relativeCurrentPose.position.y = y;
98 relativeCurrentPose.position.z = z;
99
100 auto localquat = tf::createQuaternionFromRPY(currentAngle, 0, 0);
101 //relativeCurrentPose.orientation = relativeInitialPose_.orientation;
102 //tf::quaternionTFToMsg(localquat, relativeCurrentPose.orientation);
103 relativeCurrentPose.orientation.w = 1;
104
105 tf::Transform tfRelativeCurrentPose;
106 tf::poseMsgToTF(relativeCurrentPose, tfRelativeCurrentPose);
107
108 tf::Transform tfGlobalPose = tfRelativeCurrentPose * tfBasePose;
109
110 tfGlobalPose.setRotation(tfGlobalPose.getRotation() * localquat);
111
112 geometry_msgs::PoseStamped globalPose;
113 tf::poseTFToMsg(tfGlobalPose, globalPose.pose);
114 globalPose.header.frame_id = planePivotPose_.header.frame_id;
115 globalPose.header.stamp = planePivotPose_.header.stamp + ros::Duration(i * secondsPerSample);
116
117 this->endEffectorTrajectory_.push_back(globalPose);
118 }
119 }
std::vector< geometry_msgs::PoseStamped > endEffectorTrajectory_

References angularSpeed_rad_s_, computeCurrentEndEffectorPoseRelativeToPivot(), deltaRadians_, cl_move_group_interface::CbMoveEndEffectorTrajectory::endEffectorTrajectory_, linearSpeed_m_s_, planePivotPose_, and relativeInitialPose_.

Here is the call graph for this function:

Member Data Documentation

◆ angularSpeed_rad_s_

boost::optional<double> cl_move_group_interface::CbCircularPivotMotion::angularSpeed_rad_s_

Definition at line 17 of file cb_circular_pivot_motion.h.

Referenced by generateTrajectory().

◆ deltaRadians_

double cl_move_group_interface::CbCircularPivotMotion::deltaRadians_
protected

◆ linearSpeed_m_s_

boost::optional<double> cl_move_group_interface::CbCircularPivotMotion::linearSpeed_m_s_

Definition at line 18 of file cb_circular_pivot_motion.h.

Referenced by generateTrajectory().

◆ planePivotPose_

geometry_msgs::PoseStamped cl_move_group_interface::CbCircularPivotMotion::planePivotPose_
protected

◆ relativeInitialPose_

boost::optional<geometry_msgs::Pose> cl_move_group_interface::CbCircularPivotMotion::relativeInitialPose_

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