RefValJS_PTP_Trajectory.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 _REFVALJS_PTP_TRAJECTORY_H_
00019 #define _REFVALJS_PTP_TRAJECTORY_H_
00020 #include <ros/console.h>
00021 #include <cob_trajectory_controller/RefVal_JS.h>
00022 #include <vector>
00023 #include <cob_trajectory_controller/BSplineND.h>
00024 #include <trajectory_msgs/JointTrajectory.h>
00025 
00026 
00027 class RefValJS_PTP_Trajectory : public RefVal_JS
00028 {
00029         public:
00030                 /* smooth = false:
00031                         additional knots between the trajectory points will be generated to make the spline follow straight lines
00032                         and just have the corners rounded (default)
00033                    smooth = true:
00034                         no additional points will be generated, path will be lot smoother, but will have significant differences
00035                         between a path were the trajectory points are connected by straight lines. Do not use in conjunction with
00036                         a path planner!
00037                 */
00038                 RefValJS_PTP_Trajectory(const trajectory_msgs::JointTrajectory& trajectory, double v_rad_s, double a_rad_s2, bool smooth=false);
00039                 //RefValJS_PTP_Trajectory(const std::vector<Jointd>& trajectory, Jointd start, Jointd startvel, double v_rad_s, double a_rad_s2, bool smooth=false);
00040 
00041                 std::vector<double> r(double s) const;
00042                 double s(double t) const;
00043 
00044                 std::vector<double> dr_ds(double s) const;
00045                 double ds_dt(double t) const;
00046 
00047                 double getTotalTime() const { return m_T1 + m_T2 + m_T3; }
00048 
00049                 std::vector<double> getLengthParts() const { return m_length_parts; }
00050 
00051         protected:
00052                 double norm(const std::vector<double>& j);
00053                 double norm_max(const std::vector<double>& j);
00054                 double norm_sqr(const std::vector<double>& j);
00055                 double norm_weighted(const std::vector<double>& j);
00056                 trajectory_msgs::JointTrajectory m_trajectory;
00057 
00058                 typedef std::vector<double> vecd;
00059                 typedef std::vector<double>::const_iterator vecd_it;
00060                 vecd m_length_parts;
00061                 vecd m_length_cumulated;
00062                 vecd m_s_parts;
00063 
00064                 BSplineND< std::vector<double> > m_TrajectorySpline;
00065                 std::vector< std::vector<double> > m_SplinePoints;
00066 
00067 
00068                 double m_stepSize;
00069                 double m_length;
00070                 double m_param_length;
00071 
00072                 double m_v_rad_s;
00073                 double m_a_rad_s2;
00074 
00075                 double m_T1;    // Dauer der Phase konst. Beschl.
00076                 double m_T2;    // Dauer der Phase konst. Geschw.
00077                 double m_T3;    // Dauer der Phase konst. Verzög.
00078 
00079                 double m_sa1;   // "Beschl." des Wegparameters s in Phase 1
00080                 double m_sv2;   // "Geschw." des Wegparameters s in Phase 2
00081                 double m_sa3;   // "Verzög." des Wegparameters s in Phase 3
00082 
00083                 static const double weigths[];
00084 };
00085 
00086 
00087 inline double RefValJS_PTP_Trajectory::norm(const std::vector<double>& j)
00088 {
00089         // which norm should be used?
00090         return norm_weighted(j);
00091 }
00092 
00093 inline double RefValJS_PTP_Trajectory::norm_max(const std::vector<double>& j)
00094 {
00095         double max = j.at(0);
00096         for     (unsigned int i = 0; i<j.size(); i++)
00097         {
00098                 if(j.at(i) < max)
00099                         max = j.at(i);
00100         }
00101         return max;
00102 }
00103 
00104 inline double RefValJS_PTP_Trajectory::norm_sqr(const std::vector<double>& j)
00105 {
00106         double l = 0;
00107         for (unsigned int i = 0; i < j.size(); i++)
00108         {
00109                 l += j[i] * j[i];
00110         }
00111         return sqrt(l);
00112 }
00113 
00114 inline double RefValJS_PTP_Trajectory::norm_weighted(const std::vector<double>& j)
00115 {
00116         double l = 0;
00117         if ( j.size() == 7 )
00118         {
00119                 for (unsigned int i = 0; i < j.size(); i++)
00120                 {
00121                         l += j[i]* weigths[i] * j[i] * weigths[i];
00122                 }
00123         }
00124         else
00125         {
00126                 for (unsigned int i = 0; i < j.size(); i++)
00127                 {
00128                         l += j[i] * j[i];
00129                 }
00130         }
00131         return sqrt(l);
00132 }
00133 
00134 
00135 
00136 #endif
00137 


cob_trajectory_controller
Author(s): Alexander Bubeck
autogenerated on Thu Jun 6 2019 21:19:22