21#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
22#include <tf2_ros/transform_listener.h>
25using namespace std::chrono_literals;
35 const geometry_msgs::msg::PoseStamped & planePivotPose,
double deltaRadians,
36 std::optional<std::string> tipLink)
43 const geometry_msgs::msg::PoseStamped & planePivotPose,
44 const geometry_msgs::msg::Pose & relativeInitialPose,
double deltaRadians,
45 std::optional<std::string> tipLink)
47 relativeInitialPose_(relativeInitialPose),
48 planePivotPose_(planePivotPose),
49 deltaRadians_(deltaRadians)
73 const double RADS_PER_SAMPLE = 0.02;
74 const double METERS_PER_SAMPLE = 0.01;
76 int totalSamplesCount =
77 std::max(totallineardist / METERS_PER_SAMPLE, totalangulardist / RADS_PER_SAMPLE);
79 double linearSecondsPerSample;
80 double angularSecondsPerSamples;
81 double secondsPerSample;
85 linearSecondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
89 linearSecondsPerSample = std::numeric_limits<double>::max();
94 angularSecondsPerSamples = RADS_PER_SAMPLE / (*angularSpeed_rad_s_);
98 angularSecondsPerSamples = std::numeric_limits<double>::max();
103 secondsPerSample = 0.5;
107 secondsPerSample = std::min(linearSecondsPerSample, angularSecondsPerSamples);
110 double currentAngle = initialAngle;
112 double angleStep =
deltaRadians_ / (double)totalSamplesCount;
114 tf2::Transform tfBasePose;
119 "[" <<
getName() <<
"] generated trajectory, total samples: " << totalSamplesCount);
120 for (
int i = 0; i < totalSamplesCount; i++)
123 double y = radius * cos(currentAngle);
124 double z = radius * sin(currentAngle);
126 geometry_msgs::msg::Pose relativeCurrentPose;
129 relativeCurrentPose.position.y = y;
130 relativeCurrentPose.position.z = z;
132 tf2::Quaternion localquat;
133 localquat.setEuler(currentAngle, 0, 0);
137 relativeCurrentPose.orientation.w = 1;
139 tf2::Transform tfRelativeCurrentPose;
140 tf2::fromMsg(relativeCurrentPose, tfRelativeCurrentPose);
142 tf2::Transform tfGlobalPose = tfRelativeCurrentPose * tfBasePose;
144 tfGlobalPose.setRotation(tfGlobalPose.getRotation() * localquat);
146 geometry_msgs::msg::PoseStamped globalPose;
147 tf2::toMsg(tfGlobalPose, globalPose.pose);
150 rclcpp::Duration::from_seconds(i * secondsPerSample);
152 getLogger(),
"[" <<
getName() <<
"]" << rclcpp::Time(globalPose.header.stamp).nanoseconds());
155 currentAngle += angleStep;
163 tf2_ros::Buffer tfBuffer(
getNode()->get_clock());
164 tf2_ros::TransformListener tfListener(tfBuffer);
167 tf2::Stamped<tf2::Transform> endEffectorInPivotFrame;
180 tfBuffer.lookupTransform(
182 endEffectorInPivotFrame);
190 catch (
const std::exception & e)
192 std::cerr << e.what() <<
'\n';
202 tf2::Transform pivotTransform;
204 tf2::Transform invertedNewReferenceFrame = pivotTransform.inverse();
206 tf2::Transform currentPoseRelativeToPivot = invertedNewReferenceFrame * endEffectorInPivotFrame;
208 geometry_msgs::msg::Pose finalEndEffectorRelativePose;
209 tf2::toMsg(currentPoseRelativeToPivot, finalEndEffectorRelativePose);
217 tf2::Transform localdirection;
218 localdirection.setIdentity();
219 localdirection.setOrigin(tf2::Vector3(0.12, 0, 0));
222 visualization_msgs::msg::Marker marker;
223 marker.header.frame_id = frameid;
224 marker.header.stamp =
getNode()->now();
225 marker.ns =
"trajectory";
227 marker.type = visualization_msgs::msg::Marker::ARROW;
228 marker.action = visualization_msgs::msg::Marker::ADD;
229 marker.scale.x = 0.01;
230 marker.scale.y = 0.02;
231 marker.scale.z = 0.02;
232 marker.color.a = 1.0;
233 marker.color.r = 0.0;
235 marker.color.b = 1.0;
237 geometry_msgs::msg::Point start, end;
242 tf2::Transform basetransform;
244 tf2::Transform endarrow = localdirection * basetransform;
246 end.x = endarrow.getOrigin().x();
247 end.y = endarrow.getOrigin().y();
248 end.z = endarrow.getOrigin().z();
250 marker.pose.orientation.w = 1;
251 marker.points.push_back(start);
252 marker.points.push_back(end);
geometry_msgs::msg::PoseStamped planePivotPose_
void computeCurrentEndEffectorPoseRelativeToPivot()
std::optional< double > angularSpeed_rad_s_
CbCircularPivotMotion(std::optional< std::string > tipLink=std::nullopt)
virtual void createMarkers() override
virtual void generateTrajectory() override
std::optional< geometry_msgs::msg::Pose > relativeInitialPose_
std::optional< double > linearSpeed_m_s_
std::optional< std::string > tipLink_
virtual void createMarkers()
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
visualization_msgs::msg::MarkerArray beahiorMarkers_
ClMoveGroup * movegroupClient_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const