SMACC2
cb_pouring_motion.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#pragma once
21
22#include <tf2/transform_datatypes.h>
24
26{
28{
29public:
30 std::optional<double> angularSpeed_rad_s_;
31
32 std::optional<double> linearSpeed_m_s_;
33
35 const geometry_msgs::msg::Point & pivotPoint, double deltaHeight, std::string tipLink,
36 std::string globalFrame);
37
38 virtual void generateTrajectory() override;
39
40 virtual void createMarkers() override;
41
42 geometry_msgs::msg::Vector3 directionVector_;
43
44 // relative position of the "lid" of the bottle in the end effector reference frame.
45 // that point is the one that must do the linear motion
46 geometry_msgs::msg::Pose pointerRelativePose_;
47
48protected:
49 geometry_msgs::msg::Point relativePivotPoint_;
50
51 // distance in meters from the initial pose to the bottom/top direction in z axe
53
54 std::vector<geometry_msgs::msg::PoseStamped> pointerTrajectory_;
55
56private:
58
59 std::string globalFrame_;
60};
61
62} // namespace cl_move_group_interface
CbCircularPouringMotion(const geometry_msgs::msg::Point &pivotPoint, double deltaHeight, std::string tipLink, std::string globalFrame)
std::vector< geometry_msgs::msg::PoseStamped > pointerTrajectory_