SMACC2
Loading...
Searching...
No Matches
cb_pouring_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
24
25namespace cl_moveit2z
26{
28 const geometry_msgs::msg::Point & relativePivotPoint, double deltaHeight, std::string tipLink,
29 std::string globalFrame)
31 relativePivotPoint_(relativePivotPoint),
32 deltaHeight_(deltaHeight),
33 globalFrame_(globalFrame)
34
35{
36}
37
39{
40 // at least 1 sample per centimeter (average)
41 const double METERS_PER_SAMPLE = 0.001;
42
43 float dist_meters = 0;
44 float totallineardist = fabs(this->deltaHeight_);
45
46 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
47 int steps = totallineardist / METERS_PER_SAMPLE;
48
49 float interpolation_factor_step = 1.0 / totalSamplesCount;
50
51 double secondsPerSample;
52
54 {
55 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
56 }
57 else
58 {
59 secondsPerSample = std::numeric_limits<double>::max();
60 }
61
62 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
63
64 this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);
65
66 tf2::Transform lidEndEffectorTransform;
67 tf2::fromMsg(this->pointerRelativePose_, lidEndEffectorTransform);
68
69 tf2::Vector3 v0, v1;
70 v0 = (currentEndEffectorTransform * lidEndEffectorTransform).getOrigin();
71
72 tf2::Vector3 pivotPoint;
73
74 tf2::fromMsg(this->relativePivotPoint_, pivotPoint);
75
76 tf2::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);
77
78 v0 = v0 - pivot;
79 v1 = v0;
80 v1.setZ(v1.z() + this->deltaHeight_);
81
82 tf2::Vector3 vp1(v1);
83 tf2::Vector3 vp0(v0);
84 tf2::Quaternion rotation = tf2::shortestArcQuatNormalize2(vp0, vp1);
85
86 tf2::Quaternion initialEndEffectorOrientation = currentEndEffectorTransform.getRotation();
87 auto finalEndEffectorOrientation = initialEndEffectorOrientation * rotation;
88
89 tf2::Quaternion initialPointerOrientation =
90 initialEndEffectorOrientation * lidEndEffectorTransform.getRotation();
91 tf2::Quaternion finalPointerOrientation =
92 finalEndEffectorOrientation * lidEndEffectorTransform.getRotation();
93
94 // auto shortestAngle =
95 // tf2::angleShortestPath(initialEndEffectorOrientation, finalEndEffectorOrientation);
96
97 v0 += pivot;
98 v1 += pivot;
99
100 float linc = deltaHeight_ / steps; // METERS_PER_SAMPLE with sign
101 float interpolation_factor = 0;
102 tf2::Vector3 vi = v0;
103
104 tf2::Transform invertedLidTransform = lidEndEffectorTransform.inverse();
105 rclcpp::Time startTime = getNode()->now();
106
107 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] trajectory steps: " << steps);
108 for (float i = 0; i < steps; i++)
109 {
110 // auto currentEndEffectorOrientation =
111 // tf2::slerp(initialEndEffectorOrientation, finalEndEffectorOrientation, interpolation_factor);
112 auto currentPointerOrientation =
113 tf2::slerp(initialPointerOrientation, finalPointerOrientation, interpolation_factor);
114
115 interpolation_factor += interpolation_factor_step;
116 dist_meters += linc;
117
118 vi = v0;
119 vi.setZ(vi.getZ() + dist_meters);
120
121 tf2::Transform pose;
122 pose.setOrigin(vi);
123 pose.setRotation(currentPointerOrientation);
124
125 geometry_msgs::msg::PoseStamped pointerPose;
126 tf2::toMsg(pose, pointerPose.pose);
127 pointerPose.header.frame_id = globalFrame_;
128 pointerPose.header.stamp = startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);
129 this->pointerTrajectory_.push_back(pointerPose);
130
131 tf2::Transform poseEndEffector = pose * invertedLidTransform;
132
133 geometry_msgs::msg::PoseStamped globalEndEffectorPose;
134 tf2::toMsg(poseEndEffector, globalEndEffectorPose.pose);
135 globalEndEffectorPose.header.frame_id = globalFrame_;
136 globalEndEffectorPose.header.stamp =
137 startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);
138
139 this->endEffectorTrajectory_.push_back(globalEndEffectorPose);
140 RCLCPP_INFO_STREAM(
141 getLogger(), "[" << getName() << "] " << i << " - " << globalEndEffectorPose);
142 }
143 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "]trajectory generated, size: " << steps);
144}
145
147{
149
150 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
151 this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);
152 tf2::Vector3 pivotPoint;
153
154 tf2::fromMsg(this->relativePivotPoint_, pivotPoint);
155
156 tf2::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);
157
158 visualization_msgs::msg::Marker marker;
159
160 marker.ns = "trajectory";
161 marker.id = beahiorMarkers_.markers.size();
162 marker.type = visualization_msgs::msg::Marker::SPHERE;
163 marker.action = visualization_msgs::msg::Marker::ADD;
164 marker.scale.x = 0.01;
165 marker.scale.y = 0.01;
166 marker.scale.z = 0.01;
167
168 marker.color.a = 1.0;
169 marker.color.r = 0.0;
170 marker.color.g = 0;
171 marker.color.b = 1.0;
172
173 tf2::toMsg(pivot, marker.pose.position);
174
175 marker.header.frame_id = globalFrame_;
176 marker.header.stamp = getNode()->now();
177
178 beahiorMarkers_.markers.push_back(marker);
179
180 tf2::Transform localdirection;
181 localdirection.setIdentity();
182 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
183 auto frameid = this->pointerTrajectory_.front().header.frame_id;
184
185 for (auto & pose : this->pointerTrajectory_)
186 {
187 visualization_msgs::msg::Marker marker;
188 marker.header.frame_id = frameid;
189 marker.header.stamp = getNode()->now();
190 marker.ns = "trajectory";
191 marker.id = this->beahiorMarkers_.markers.size();
192 marker.type = visualization_msgs::msg::Marker::ARROW;
193 marker.action = visualization_msgs::msg::Marker::ADD;
194 marker.scale.x = 0.005;
195 marker.scale.y = 0.01;
196 marker.scale.z = 0.01;
197 marker.color.a = 0.8;
198 marker.color.r = 0.0;
199 marker.color.g = 1;
200 marker.color.b = 0.0;
201
202 geometry_msgs::msg::Point start, end;
203 start.x = 0;
204 start.y = 0;
205 start.z = 0;
206
207 tf2::Transform basetransform;
208 tf2::fromMsg(pose.pose, basetransform);
209 // tf2::Transform endarrow = localdirection * basetransform;
210
211 end.x = localdirection.getOrigin().x();
212 end.y = localdirection.getOrigin().y();
213 end.z = localdirection.getOrigin().z();
214
215 marker.pose.position = pose.pose.position;
216 marker.pose.orientation = pose.pose.orientation;
217 marker.points.push_back(start);
218 marker.points.push_back(end);
219
220 beahiorMarkers_.markers.push_back(marker);
221 }
222}
223
224} // namespace cl_moveit2z
CbCircularPouringMotion(const geometry_msgs::msg::Point &pivotPoint, double deltaHeight, std::string tipLink, std::string globalFrame)
std::vector< geometry_msgs::msg::PoseStamped > pointerTrajectory_
geometry_msgs::msg::Pose pointerRelativePose_
geometry_msgs::msg::Point relativePivotPoint_
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const