cartesian_controller_data_types.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_DATA_TYPES_H
19 #define COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_DATA_TYPES_H
20 
21 #include <vector>
22 #include <std_msgs/Float64.h>
23 #include <geometry_msgs/Pose.h>
24 
26 {
27 
29 {
30  double t_ipo;
31  unsigned int profile_type;
32  double vel, accl;
33  double Se_max;
34 };
35 
37 {
38  double tb, te, tv;
39  unsigned int steps_tb, steps_te, steps_tv;
40  double vel;
41 };
42 
44 {
45  geometry_msgs::Pose start, end;
46 };
47 
49 {
50  geometry_msgs::Pose pose_center;
52  double radius;
53 };
54 
56 {
57  unsigned int move_type;
61 };
62 
63 class PathArray
64 {
65  public:
66  PathArray(const double Se, const std::vector<double> array)
67  : Se_(Se),
68  array_(array)
69  {}
70 
72  {
73  array_.clear();
74  }
75 
76  double Se_;
77  std::vector<double> array_;
78 };
79 
81 {
82  public:
83  PathMatrix(const PathArray pa1,
84  const PathArray pa2)
85  {
86  pm_.push_back(pa1);
87  pm_.push_back(pa2);
88  }
89 
91  {
92  pm_.clear();
93  }
94 
95  double getMaxSe()
96  {
97  double se_max = 0;
98 
99  for (unsigned int i = 0; i < pm_.size(); i++)
100  {
101  if (se_max < fabs(pm_[i].Se_))
102  {
103  se_max = fabs(pm_[i].Se_);
104  }
105  }
106  return se_max;
107  }
108 
109  std::vector<PathArray> pm_;
110 };
111 
112 } // namespace cob_cartesian_controller
113 
114 #endif // COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_DATA_TYPES_H
PathArray(const double Se, const std::vector< double > array)
PathMatrix(const PathArray pa1, const PathArray pa2)


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Apr 8 2021 02:40:13