SMACC2
Loading...
Searching...
No Matches
cb_move_cartesian_relative2.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 *****************************************************************************************************************/
20
23
24namespace cl_moveit2z
25{
26using namespace std::chrono_literals;
27
28CbMoveCartesianRelative2::CbMoveCartesianRelative2(std::string referenceFrame, std::string tipLink)
30{
31 globalFrame_ = referenceFrame;
32}
33
35 std::string referenceFrame, std::string tipLink, geometry_msgs::msg::Vector3 offset)
37{
38 globalFrame_ = referenceFrame;
39 offset_ = offset;
40}
41
43
45{
46 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] generating trajectory");
47 // at least 1 sample per centimeter (average)
48 const double METERS_PER_SAMPLE = 0.001;
49
50 float dist_meters = 0;
51 tf2::Vector3 voffset;
52 tf2::fromMsg(offset_, voffset);
53
54 float totallineardist = voffset.length();
55
56 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
57 int steps = totallineardist / METERS_PER_SAMPLE;
58
59 float interpolation_factor_step = 1.0 / totalSamplesCount;
60
61 double secondsPerSample;
62
64 {
65 linearSpeed_m_s_ = 0.1;
66 }
67
68 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
69
70 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
71 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] getting current end effector pose");
72 this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);
73
74 tf2::Transform finalEndEffectorTransform = currentEndEffectorTransform;
75 finalEndEffectorTransform.setOrigin(finalEndEffectorTransform.getOrigin() + voffset);
76
77 float linc = totallineardist / steps; // METERS_PER_SAMPLE with sign
78 float interpolation_factor = 0;
79
80 rclcpp::Time startTime = getNode()->now();
81 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] trajectory steps: " << steps);
82
83 for (float i = 0; i < steps; i++)
84 {
85 interpolation_factor += interpolation_factor_step;
86 dist_meters += linc;
87
88 tf2::Vector3 vi = currentEndEffectorTransform.getOrigin().lerp(
89 finalEndEffectorTransform.getOrigin(), interpolation_factor);
90
91 tf2::Transform pose;
92 pose.setOrigin(vi);
93 pose.setRotation(currentEndEffectorTransform.getRotation());
94
95 geometry_msgs::msg::PoseStamped pointerPose;
96 tf2::toMsg(pose, pointerPose.pose);
97 pointerPose.header.frame_id = globalFrame_;
98 pointerPose.header.stamp = startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);
99
100 this->endEffectorTrajectory_.push_back(pointerPose);
101 }
102
103 RCLCPP_INFO_STREAM(
104 getLogger(),
105 "[" << getName() << "] Target End efector Pose: " << this->endEffectorTrajectory_.back());
106}
107} // namespace cl_moveit2z
CbMoveCartesianRelative2(std::string referenceFrame, std::string tipLink)
std::vector< geometry_msgs::msg::PoseStamped > endEffectorTrajectory_
void getCurrentEndEffectorPose(std::string globalFrame, tf2::Stamped< tf2::Transform > &currentEndEffectorTransform)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const