46 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] generating trajectory");
48 const double METERS_PER_SAMPLE = 0.001;
50 float dist_meters = 0;
54 float totallineardist = voffset.length();
56 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
57 int steps = totallineardist / METERS_PER_SAMPLE;
59 float interpolation_factor_step = 1.0 / totalSamplesCount;
61 double secondsPerSample;
68 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
70 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
71 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] getting current end effector pose");
74 tf2::Transform finalEndEffectorTransform = currentEndEffectorTransform;
75 finalEndEffectorTransform.setOrigin(finalEndEffectorTransform.getOrigin() + voffset);
77 float linc = totallineardist / steps;
78 float interpolation_factor = 0;
80 rclcpp::Time startTime =
getNode()->now();
81 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] trajectory steps: " << steps);
83 for (
float i = 0; i < steps; i++)
85 interpolation_factor += interpolation_factor_step;
88 tf2::Vector3 vi = currentEndEffectorTransform.getOrigin().lerp(
89 finalEndEffectorTransform.getOrigin(), interpolation_factor);
93 pose.setRotation(currentEndEffectorTransform.getRotation());
95 geometry_msgs::msg::PoseStamped pointerPose;
96 tf2::toMsg(pose, pointerPose.pose);
98 pointerPose.header.stamp = startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);