24#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
29 const geometry_msgs::msg::Point & relativePivotPoint,
double deltaHeight, std::string tipLink,
30 std::string globalFrame)
32 relativePivotPoint_(relativePivotPoint),
33 deltaHeight_(deltaHeight),
34 globalFrame_(globalFrame)
42 const double METERS_PER_SAMPLE = 0.001;
44 float dist_meters = 0;
47 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
48 int steps = totallineardist / METERS_PER_SAMPLE;
50 float interpolation_factor_step = 1.0 / totalSamplesCount;
52 double secondsPerSample;
56 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
60 secondsPerSample = std::numeric_limits<double>::max();
63 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
67 tf2::Transform lidEndEffectorTransform;
71 v0 = (currentEndEffectorTransform * lidEndEffectorTransform).getOrigin();
73 tf2::Vector3 pivotPoint;
76 tf2::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);
84 tf2::Quaternion rotation = tf2::shortestArcQuatNormalize2(vp0, vp1);
86 tf2::Quaternion initialEndEffectorOrientation = currentEndEffectorTransform.getRotation();
87 auto finalEndEffectorOrientation = initialEndEffectorOrientation * rotation;
89 tf2::Quaternion initialPointerOrientation =
90 initialEndEffectorOrientation * lidEndEffectorTransform.getRotation();
91 tf2::Quaternion finalPointerOrientation =
92 finalEndEffectorOrientation * lidEndEffectorTransform.getRotation();
101 float interpolation_factor = 0;
102 tf2::Vector3 vi = v0;
104 tf2::Transform invertedLidTransform = lidEndEffectorTransform.inverse();
105 rclcpp::Time startTime =
getNode()->now();
107 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] trajectory steps: " << steps);
108 for (
float i = 0; i < steps; i++)
112 auto currentPointerOrientation =
113 tf2::slerp(initialPointerOrientation, finalPointerOrientation, interpolation_factor);
115 interpolation_factor += interpolation_factor_step;
119 vi.setZ(vi.getZ() + dist_meters);
123 pose.setRotation(currentPointerOrientation);
125 geometry_msgs::msg::PoseStamped pointerPose;
126 tf2::toMsg(pose, pointerPose.pose);
128 pointerPose.header.stamp = startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);
131 tf2::Transform poseEndEffector = pose * invertedLidTransform;
133 geometry_msgs::msg::PoseStamped globalEndEffectorPose;
134 tf2::toMsg(poseEndEffector, globalEndEffectorPose.pose);
136 globalEndEffectorPose.header.stamp =
137 startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);
141 getLogger(),
"[" <<
getName() <<
"] " << i <<
" - " << globalEndEffectorPose);
143 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"]trajectory generated, size: " << steps);
150 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
152 tf2::Vector3 pivotPoint;
154 tf2::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);
156 visualization_msgs::msg::Marker marker;
158 marker.ns =
"trajectory";
160 marker.type = visualization_msgs::msg::Marker::SPHERE;
161 marker.action = visualization_msgs::msg::Marker::ADD;
162 marker.scale.x = 0.01;
163 marker.scale.y = 0.01;
164 marker.scale.z = 0.01;
166 marker.color.a = 1.0;
167 marker.color.r = 0.0;
169 marker.color.b = 1.0;
171 tf2::toMsg(pivot, marker.pose.position);
173 marker.header.stamp =
getNode()->now();
177 tf2::Transform localdirection;
178 localdirection.setIdentity();
179 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
184 visualization_msgs::msg::Marker marker;
185 marker.header.frame_id = frameid;
186 marker.header.stamp =
getNode()->now();
187 marker.ns =
"trajectory";
189 marker.type = visualization_msgs::msg::Marker::ARROW;
190 marker.action = visualization_msgs::msg::Marker::ADD;
191 marker.scale.x = 0.005;
192 marker.scale.y = 0.01;
193 marker.scale.z = 0.01;
194 marker.color.a = 0.8;
195 marker.color.r = 0.0;
197 marker.color.b = 0.0;
199 geometry_msgs::msg::Point start, end;
204 tf2::Transform basetransform;
205 tf2::fromMsg(pose.pose, basetransform);
208 end.x = localdirection.getOrigin().x();
209 end.y = localdirection.getOrigin().y();
210 end.z = localdirection.getOrigin().z();
212 marker.pose.position = pose.pose.position;
213 marker.pose.orientation = pose.pose.orientation;
214 marker.points.push_back(start);
215 marker.points.push_back(end);
virtual void createMarkers() override
geometry_msgs::msg::Point relativePivotPoint_
virtual void generateTrajectory() override
CbCircularPouringMotion(const geometry_msgs::msg::Point &pivotPoint, double deltaHeight, std::string tipLink, std::string globalFrame)
std::optional< double > linearSpeed_m_s_
geometry_msgs::msg::Pose pointerRelativePose_
std::vector< geometry_msgs::msg::PoseStamped > pointerTrajectory_
virtual void createMarkers()
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > ¤tEndEffectorTransform)
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
visualization_msgs::msg::MarkerArray beahiorMarkers_
std::string getName() const
virtual rclcpp::Logger getLogger()
virtual rclcpp::Node::SharedPtr getNode()