SMACC2
Loading...
Searching...
No Matches
cb_move_cartesian_relative2.hpp
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
21#pragma once
22
23#include <tf2/transform_datatypes.h>
27#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
29
30using namespace std::chrono_literals;
31
32namespace cl_moveit2z
33{
35{
36public:
37 geometry_msgs::msg::Vector3 offset_;
38
39 std::optional<double> linearSpeed_m_s_;
40
41 CbMoveCartesianRelative2(std::string referenceFrame, std::string tipLink)
43 {
44 globalFrame_ = referenceFrame;
45 }
46
48 std::string referenceFrame, std::string tipLink, geometry_msgs::msg::Vector3 offset)
50 {
51 globalFrame_ = referenceFrame;
52 offset_ = offset;
53 }
54
56
57 void generateTrajectory() override
58 {
59 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] generating trajectory");
60 // at least 1 sample per centimeter (average)
61 const double METERS_PER_SAMPLE = 0.001;
62
63 float dist_meters = 0;
64 tf2::Vector3 voffset;
65 tf2::fromMsg(offset_, voffset);
66
67 float totallineardist = voffset.length();
68
69 int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;
70 int steps = totallineardist / METERS_PER_SAMPLE;
71
72 float interpolation_factor_step = 1.0 / totalSamplesCount;
73
74 double secondsPerSample;
75
77 {
78 linearSpeed_m_s_ = 0.1;
79 }
80
81 secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);
82
83 tf2::Stamped<tf2::Transform> currentEndEffectorTransform;
84 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] getting current end effector pose");
85 this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);
86
87 tf2::Transform finalEndEffectorTransform = currentEndEffectorTransform;
88 finalEndEffectorTransform.setOrigin(finalEndEffectorTransform.getOrigin() + voffset);
89
90 float linc = totallineardist / steps; // METERS_PER_SAMPLE with sign
91 float interpolation_factor = 0;
92
93 rclcpp::Time startTime = getNode()->now();
94 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] trajectory steps: " << steps);
95
96 for (float i = 0; i < steps; i++)
97 {
98 interpolation_factor += interpolation_factor_step;
99 dist_meters += linc;
100
101 tf2::Vector3 vi = currentEndEffectorTransform.getOrigin().lerp(
102 finalEndEffectorTransform.getOrigin(), interpolation_factor);
103
104 tf2::Transform pose;
105 pose.setOrigin(vi);
106 pose.setRotation(currentEndEffectorTransform.getRotation());
107
108 geometry_msgs::msg::PoseStamped pointerPose;
109 tf2::toMsg(pose, pointerPose.pose);
110 pointerPose.header.frame_id = globalFrame_;
111 pointerPose.header.stamp = startTime + rclcpp::Duration::from_seconds(i * secondsPerSample);
112
113 this->endEffectorTrajectory_.push_back(pointerPose);
114 }
115
116 RCLCPP_INFO_STREAM(
117 getLogger(),
118 "[" << getName() << "] Target End efector Pose: " << this->endEffectorTrajectory_.back());
119 }
120
121private:
122 std::string globalFrame_;
123};
124} // namespace cl_moveit2z
CbMoveCartesianRelative2(std::string referenceFrame, std::string tipLink, geometry_msgs::msg::Vector3 offset)
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