59 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] generating trajectory");
61 const double METERS_PER_SAMPLE = 0.001;
63 float dist_meters = 0;
67 float totallineardist = voffset.length();
69 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
70 int steps = totallineardist / METERS_PER_SAMPLE;
72 float interpolation_factor_step = 1.0 / totalSamplesCount;
74 double secondsPerSample;
81 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
83 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
84 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] getting current end effector pose");
87 tf2::Transform finalEndEffectorTransform = currentEndEffectorTransform;
88 finalEndEffectorTransform.setOrigin(finalEndEffectorTransform.getOrigin() + voffset);
90 float linc = totallineardist / steps;
91 float interpolation_factor = 0;
93 rclcpp::Time startTime =
getNode()->now();
94 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] trajectory steps: " << steps);
96 for (
float i = 0; i < steps; i++)
98 interpolation_factor += interpolation_factor_step;
101 tf2::Vector3 vi = currentEndEffectorTransform.getOrigin().lerp(
102 finalEndEffectorTransform.getOrigin(), interpolation_factor);
106 pose.setRotation(currentEndEffectorTransform.getRotation());
108 geometry_msgs::msg::PoseStamped pointerPose;
109 tf2::toMsg(pose, pointerPose.pose);
111 pointerPose.header.stamp = startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);