cartesian_controller_data_types.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_DATA_TYPES_H
00019 #define COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_DATA_TYPES_H
00020 
00021 #include <vector>
00022 #include <std_msgs/Float64.h>
00023 #include <geometry_msgs/Pose.h>
00024 
00025 namespace cob_cartesian_controller
00026 {
00027 
00028 struct ProfileStruct
00029 {
00030     double t_ipo;
00031     unsigned int profile_type;
00032     double vel, accl;
00033     double Se_max;
00034 };
00035 
00036 struct ProfileTimings
00037 {
00038     double tb, te, tv;
00039     unsigned int steps_tb, steps_te, steps_tv;
00040     double vel;
00041 };
00042 
00043 struct MoveLinStruct
00044 {
00045     geometry_msgs::Pose start, end;
00046 };
00047 
00048 struct MoveCircStruct
00049 {
00050     geometry_msgs::Pose pose_center;
00051     double start_angle, end_angle;
00052     double radius;
00053 };
00054 
00055 struct CartesianActionStruct
00056 {
00057     unsigned int move_type;
00058     MoveLinStruct move_lin;
00059     MoveCircStruct move_circ;
00060     ProfileStruct profile;
00061 };
00062 
00063 class PathArray
00064 {
00065     public:
00066         PathArray(const double Se, const std::vector<double> array)
00067         :    Se_(Se),
00068              array_(array)
00069         {}
00070 
00071         ~PathArray()
00072         {
00073             array_.clear();
00074         }
00075 
00076         double Se_;
00077         std::vector<double> array_;
00078 };
00079 
00080 class PathMatrix
00081 {
00082     public:
00083         PathMatrix(const PathArray pa1,
00084                    const PathArray pa2)
00085         {
00086             pm_.push_back(pa1);
00087             pm_.push_back(pa2);
00088         }
00089 
00090         ~PathMatrix()
00091         {
00092             pm_.clear();
00093         }
00094 
00095         double getMaxSe()
00096         {
00097             double se_max = 0;
00098 
00099             for (unsigned int i = 0; i < pm_.size(); i++)
00100             {
00101                 if (se_max < fabs(pm_[i].Se_))
00102                 {
00103                     se_max = fabs(pm_[i].Se_);
00104                 }
00105             }
00106             return se_max;
00107         }
00108 
00109         std::vector<PathArray> pm_;
00110 };
00111 
00112 }  // namespace cob_cartesian_controller
00113 
00114 #endif  // COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_DATA_TYPES_H


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Jun 6 2019 21:19:40