SMACC2
Loading...
Searching...
No Matches
cb_circular_pivot_motion.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
22#include <tf2_ros/transform_listener.h>
24
25using namespace std::chrono_literals;
26
28{
29CbCircularPivotMotion::CbCircularPivotMotion(std::optional<std::string> tipLink)
31{
32}
33
35 const geometry_msgs::msg::PoseStamped & planePivotPose, double deltaRadians,
36 std::optional<std::string> tipLink)
37: CbMoveEndEffectorTrajectory(tipLink), planePivotPose_(planePivotPose), deltaRadians_(deltaRadians)
38{
39 if (tipLink_) planePivotPose_.header.frame_id = *tipLink;
40}
41
43 const geometry_msgs::msg::PoseStamped & planePivotPose,
44 const geometry_msgs::msg::Pose & relativeInitialPose, double deltaRadians,
45 std::optional<std::string> tipLink)
47 relativeInitialPose_(relativeInitialPose),
48 planePivotPose_(planePivotPose),
49 deltaRadians_(deltaRadians)
50{
51}
52
54{
56 {
58 }
59
60 // project offset into the xy-plane
61 // get the radius
62 double radius = sqrt(
63 relativeInitialPose_->position.z * relativeInitialPose_->position.z +
64 relativeInitialPose_->position.y * relativeInitialPose_->position.y);
65 double initialAngle = atan2(relativeInitialPose_->position.z, relativeInitialPose_->position.y);
66
67 double totallineardist = fabs(radius * deltaRadians_);
68 double totalangulardist = fabs(deltaRadians_);
69
70 // at least 1 sample per centimeter (average)
71 // at least 1 sample per ~1.1 degrees (average)
72
73 const double RADS_PER_SAMPLE = 0.02;
74 const double METERS_PER_SAMPLE = 0.01;
75
76 int totalSamplesCount =
77 std::max(totallineardist / METERS_PER_SAMPLE, totalangulardist / RADS_PER_SAMPLE);
78
79 double linearSecondsPerSample;
80 double angularSecondsPerSamples;
81 double secondsPerSample;
82
84 {
85 linearSecondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
86 }
87 else
88 {
89 linearSecondsPerSample = std::numeric_limits<double>::max();
90 }
91
93 {
94 angularSecondsPerSamples = RADS_PER_SAMPLE / (*angularSpeed_rad_s_);
95 }
96 else
97 {
98 angularSecondsPerSamples = std::numeric_limits<double>::max();
99 }
100
102 {
103 secondsPerSample = 0.5;
104 }
105 else
106 {
107 secondsPerSample = std::min(linearSecondsPerSample, angularSecondsPerSamples);
108 }
109
110 double currentAngle = initialAngle;
111
112 double angleStep = deltaRadians_ / (double)totalSamplesCount;
113
114 tf2::Transform tfBasePose;
115 tf2::fromMsg(planePivotPose_.pose, tfBasePose);
116
117 RCLCPP_INFO_STREAM(
118 getLogger(),
119 "[" << getName() << "] generated trajectory, total samples: " << totalSamplesCount);
120 for (int i = 0; i < totalSamplesCount; i++)
121 {
122 // relativePose i
123 double y = radius * cos(currentAngle);
124 double z = radius * sin(currentAngle);
125
126 geometry_msgs::msg::Pose relativeCurrentPose;
127
128 relativeCurrentPose.position.x = relativeInitialPose_->position.x;
129 relativeCurrentPose.position.y = y;
130 relativeCurrentPose.position.z = z;
131
132 tf2::Quaternion localquat;
133 localquat.setEuler(currentAngle, 0, 0);
134
135 //relativeCurrentPose.orientation = relativeInitialPose_.orientation;
136 //tf2::toMsg(localquat, relativeCurrentPose.orientation);
137 relativeCurrentPose.orientation.w = 1;
138
139 tf2::Transform tfRelativeCurrentPose;
140 tf2::fromMsg(relativeCurrentPose, tfRelativeCurrentPose);
141
142 tf2::Transform tfGlobalPose = tfRelativeCurrentPose * tfBasePose;
143
144 tfGlobalPose.setRotation(tfGlobalPose.getRotation() * localquat);
145
146 geometry_msgs::msg::PoseStamped globalPose;
147 tf2::toMsg(tfGlobalPose, globalPose.pose);
148 globalPose.header.frame_id = planePivotPose_.header.frame_id;
149 globalPose.header.stamp = rclcpp::Time(planePivotPose_.header.stamp) +
150 rclcpp::Duration::from_seconds(i * secondsPerSample);
151 RCLCPP_INFO_STREAM(
152 getLogger(), "[" << getName() << "]" << rclcpp::Time(globalPose.header.stamp).nanoseconds());
153
154 this->endEffectorTrajectory_.push_back(globalPose);
155 currentAngle += angleStep;
156 }
157}
158
160{
161 //auto currentRobotEndEffectorPose = this->movegroupClient_->moveGroupClientInterface.getCurrentPose();
162
163 tf2_ros::Buffer tfBuffer(getNode()->get_clock());
164 tf2_ros::TransformListener tfListener(tfBuffer);
165
166 // tf2::Stamped<tf2::Transform> globalBaseLink;
167 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
168
169 try
170 {
171 if (!tipLink_ || *tipLink_ == "")
172 {
173 tipLink_ = this->movegroupClient_->moveGroupClientInterface->getEndEffectorLink();
174 }
175
176 RCLCPP_INFO_STREAM(
177 getLogger(), "[" << getName() << "] waiting transform, pivot: '"
178 << planePivotPose_.header.frame_id << "' tipLink: '" << *tipLink_ << "'");
179 tf2::fromMsg(
180 tfBuffer.lookupTransform(
181 planePivotPose_.header.frame_id, *tipLink_, rclcpp::Time(), rclcpp::Duration(10s)),
182 endEffectorInPivotFrame);
183
184 //endEffectorInPivotFrame = tfBuffer.lookupTransform(planePivotPose_.header.frame_id, *tipLink_, rclcpp::Time(0));
185
186 // we define here the global frame as the pivot frame id
187 // tfListener.waitForTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, rclcpp::Time(0), rclcpp::Duration(10));
188 // tfListener.lookupTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, rclcpp::Time(0), globalBaseLink);
189 }
190 catch (const std::exception & e)
191 {
192 std::cerr << e.what() << '\n';
193 }
194
195 // tf2::Transform endEffectorInBaseLinkFrame;
196 // tf2::fromMsg(currentRobotEndEffectorPose.pose, endEffectorInBaseLinkFrame);
197
198 // tf2::Transform endEffectorInPivotFrame = globalBaseLink * endEffectorInBaseLinkFrame; // pose composition
199
200 // now pivot and EndEffector share a common reference frame (let say map)
201 // now get the current pose from the pivot reference frame with inverse composition
202 tf2::Transform pivotTransform;
203 tf2::fromMsg(planePivotPose_.pose, pivotTransform);
204 tf2::Transform invertedNewReferenceFrame = pivotTransform.inverse();
205
206 tf2::Transform currentPoseRelativeToPivot = invertedNewReferenceFrame * endEffectorInPivotFrame;
207
208 geometry_msgs::msg::Pose finalEndEffectorRelativePose;
209 tf2::toMsg(currentPoseRelativeToPivot, finalEndEffectorRelativePose);
210 relativeInitialPose_ = finalEndEffectorRelativePose;
211}
212
214{
216
217 tf2::Transform localdirection;
218 localdirection.setIdentity();
219 localdirection.setOrigin(tf2::Vector3(0.12, 0, 0));
220 auto frameid = planePivotPose_.header.frame_id;
221
222 visualization_msgs::msg::Marker marker;
223 marker.header.frame_id = frameid;
224 marker.header.stamp = getNode()->now();
225 marker.ns = "trajectory";
226 marker.id = beahiorMarkers_.markers.size();
227 marker.type = visualization_msgs::msg::Marker::ARROW;
228 marker.action = visualization_msgs::msg::Marker::ADD;
229 marker.scale.x = 0.01;
230 marker.scale.y = 0.02;
231 marker.scale.z = 0.02;
232 marker.color.a = 1.0;
233 marker.color.r = 0.0;
234 marker.color.g = 0;
235 marker.color.b = 1.0;
236
237 geometry_msgs::msg::Point start, end;
238 start.x = planePivotPose_.pose.position.x;
239 start.y = planePivotPose_.pose.position.y;
240 start.z = planePivotPose_.pose.position.z;
241
242 tf2::Transform basetransform;
243 tf2::fromMsg(planePivotPose_.pose, basetransform);
244 tf2::Transform endarrow = localdirection * basetransform;
245
246 end.x = endarrow.getOrigin().x();
247 end.y = endarrow.getOrigin().y();
248 end.z = endarrow.getOrigin().z();
249
250 marker.pose.orientation.w = 1;
251 marker.points.push_back(start);
252 marker.points.push_back(end);
253
254 beahiorMarkers_.markers.push_back(marker);
255}
256
257} // namespace cl_move_group_interface
CbCircularPivotMotion(std::optional< std::string > tipLink=std::nullopt)
std::optional< geometry_msgs::msg::Pose > relativeInitialPose_
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const