41 const double METERS_PER_SAMPLE = 0.001;
43 float dist_meters = 0;
46 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
47 int steps = totallineardist / METERS_PER_SAMPLE;
49 float interpolation_factor_step = 1.0 / totalSamplesCount;
51 double secondsPerSample;
55 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
59 secondsPerSample = std::numeric_limits<double>::max();
62 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
66 tf2::Transform lidEndEffectorTransform;
70 v0 = (currentEndEffectorTransform * lidEndEffectorTransform).getOrigin();
72 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;
156 tf2::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);
158 visualization_msgs::msg::Marker marker;
160 marker.ns =
"trajectory";
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;
168 marker.color.a = 1.0;
169 marker.color.r = 0.0;
171 marker.color.b = 1.0;
173 tf2::toMsg(pivot, marker.pose.position);
176 marker.header.stamp =
getNode()->now();
180 tf2::Transform localdirection;
181 localdirection.setIdentity();
182 localdirection.setOrigin(tf2::Vector3(0.05, 0, 0));
187 visualization_msgs::msg::Marker marker;
188 marker.header.frame_id = frameid;
189 marker.header.stamp =
getNode()->now();
190 marker.ns =
"trajectory";
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;
200 marker.color.b = 0.0;
202 geometry_msgs::msg::Point start, end;
207 tf2::Transform basetransform;
208 tf2::fromMsg(pose.pose, basetransform);
211 end.x = localdirection.getOrigin().x();
212 end.y = localdirection.getOrigin().y();
213 end.z = localdirection.getOrigin().z();
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);