TypeIIRMLVelocity.h
Go to the documentation of this file.
1 // ---------------------- Doxygen info ----------------------
43 // ----------------------------------------------------------
44 // For a convenient reading of this file's source code,
45 // please use a tab width of four characters.
46 // ----------------------------------------------------------
47 
48 
49 #ifndef __TypeIIRMLVelocity__
50 #define __TypeIIRMLVelocity__
51 
52 
55 #include "RMLVector.h"
56 #include "TypeIIRMLPolynomial.h"
57 #include "RMLVelocityFlags.h"
58 
59 
60 
61 using namespace TypeIIRMLMath;
62 
63 
64 // ---------------------- Doxygen info ----------------------
102 // ----------------------------------------------------------
104 {
105 public:
106 
107 
108 // ---------------------- Doxygen info ----------------------
126 // ----------------------------------------------------------
127  TypeIIRMLVelocity( const unsigned int &DegreesOfFreedom
128  , const double &CycleTimeInSeconds);
129 
130 
131 // ---------------------- Doxygen info ----------------------
145 // ----------------------------------------------------------
146  TypeIIRMLVelocity(const TypeIIRMLVelocity &TypeIIRMLObject);
147 
148 
149 // ---------------------- Doxygen info ----------------------
154 // ----------------------------------------------------------
155  ~TypeIIRMLVelocity(void);
156 
157 
158 // ---------------------- Doxygen info ----------------------
166 // ----------------------------------------------------------
167  TypeIIRMLVelocity &operator = (const TypeIIRMLVelocity &TypeIIRMLObject);
168 
169 
170 // ---------------------- Doxygen info ----------------------
246 // ----------------------------------------------------------
247  int GetNextStateOfMotion( const RMLVelocityInputParameters &InputValues
248  , RMLVelocityOutputParameters *OutputValues
249  , const RMLVelocityFlags &Flags);
250 
251 
252 // ---------------------- Doxygen info ----------------------
307 // ----------------------------------------------------------
308  int GetNextStateOfMotionAtTime( const double &TimeValueInSeconds
309  , RMLVelocityOutputParameters *OutputValues ) const;
310 
311 
312 protected:
313 
314 
315 // ---------------------- Doxygen info ----------------------
320 // ----------------------------------------------------------
322  {
324  FUNC_SUCCESS = false,
326  FUNC_ERROR_OCCURRED = true
327  };
328 
329 
330 // ---------------------- Doxygen info ----------------------
382 // ----------------------------------------------------------
383  void FallBackStrategy( const RMLVelocityInputParameters &InputValues
384  , RMLVelocityOutputParameters *OutputValues );
385 
386 
387 // ---------------------- Doxygen info ----------------------
408 // ----------------------------------------------------------
409  void CalculateExecutionTimes(void);
410 
411 
412 // ---------------------- Doxygen info ----------------------
432 // ----------------------------------------------------------
433  void ComputeTrajectoryParameters(void);
434 
435 
436 // ---------------------- Doxygen info ----------------------
456 // ----------------------------------------------------------
457  void ComputePhaseSynchronizationParameters(void);
458 
459 
460 // ---------------------- Doxygen info ----------------------
474 // ----------------------------------------------------------
475  void ComputeTimeSynchronizedTrajectoryParameters(void);
476 
477 
478 // ---------------------- Doxygen info ----------------------
514 // ----------------------------------------------------------
515  int ComputeAndSetOutputParameters( const double &TimeValueInSeconds
516  , RMLVelocityOutputParameters *OP ) const;
517 
518 // ---------------------- Doxygen info ----------------------
563 // ----------------------------------------------------------
564  bool IsPhaseSynchronizationPossible(void);
565 
566 
567 // ---------------------- Doxygen info ----------------------
616 // ----------------------------------------------------------
617  void CalculatePositionalExtrems( const double &TimeValueInSeconds
618  , RMLVelocityOutputParameters *OP ) const;
619 
620 
621 // ---------------------- Doxygen info ----------------------
659 // ----------------------------------------------------------
660  void SetPositionalExtremsToZero(RMLVelocityOutputParameters *OP) const;
661 
662 
663 // ---------------------- Doxygen info ----------------------
689 // ----------------------------------------------------------
690  void SetupPhaseSyncSelectionVector(void);
691 
692 
693 // ---------------------- Doxygen info ----------------------
703 // ----------------------------------------------------------
705 
706 
707 // ---------------------- Doxygen info ----------------------
716 // ----------------------------------------------------------
718 
719 
720 // ---------------------- Doxygen info ----------------------
727 // ----------------------------------------------------------
729 
730 
731 // ---------------------- Doxygen info ----------------------
739 // ----------------------------------------------------------
741 
742 
743 // ---------------------- Doxygen info ----------------------
750 // ----------------------------------------------------------
751  unsigned int NumberOfDOFs;
752 
753 
754 // ---------------------- Doxygen info ----------------------
761 // ----------------------------------------------------------
763 
764 
765 // ---------------------- Doxygen info ----------------------
772 // ----------------------------------------------------------
773  double CycleTime;
774 
775 
776 // ---------------------- Doxygen info ----------------------
784 // ----------------------------------------------------------
786 
787 
788 // ---------------------- Doxygen info ----------------------
797 // ----------------------------------------------------------
799 
800 
801 // ---------------------- Doxygen info ----------------------
815 // ----------------------------------------------------------
817 
818 
819 // ---------------------- Doxygen info ----------------------
831 // ----------------------------------------------------------
833 
834 
835 // ---------------------- Doxygen info ----------------------
843 // ----------------------------------------------------------
845 
846 
847 // ---------------------- Doxygen info ----------------------
856 // ----------------------------------------------------------
858 
859 
860 // ---------------------- Doxygen info ----------------------
869 // ----------------------------------------------------------
871 
872 
873 // ---------------------- Doxygen info ----------------------
882 // ----------------------------------------------------------
884 
885 
886 // ---------------------- Doxygen info ----------------------
896 // ----------------------------------------------------------
898 
899 
900 // ---------------------- Doxygen info ----------------------
915 // ----------------------------------------------------------
917 
918 
919 // ---------------------- Doxygen info ----------------------
928 // ----------------------------------------------------------
930 
931 
932 // ---------------------- Doxygen info ----------------------
945 // ----------------------------------------------------------
947 
948 
949 
950 // ---------------------- Doxygen info ----------------------
961 // ----------------------------------------------------------
963 
964 
965 }; // class TypeIIRMLVelocity
966 
967 
968 #endif
969 
970 
Header file for the dynamic vector class used for the Reflexxes Motion Libraries. ...
double InternalClockInSeconds
In order to prevent from recalculating the trajectory within every control cycle and to safe CPU time...
RMLDoubleVector * PhaseSynchronizationTargetVelocityVector
Target velocity vector used for the calculation of phase-synchronized motion trajectories.
Data structure containing flags to parameterize the execution of the velocity-based On-Line Trajector...
double SynchronizationTime
If the trajectory is time- or phase-synchronized, this attribute will contain the synchronization tim...
RMLVelocityFlags OldFlags
In order to check, whether a new calculation has to be started, the input values have to be compared ...
Three arrays of TypeIIRMLMath::TypeIIRMLPolynomial.
bool CalculatePositionalExtremsFlag
Indicates, whether the positional extremes are to be calculated.
RMLDoubleVector * ExecutionTimes
Vector of double values, each of which represents an execution time that is used internally.
Header file for the class RMLVelocityInputParameters.
Header file for the class RMLVelocityFlags.
RMLBoolVector * PhaseSyncSelectionVector
Boolean vector, which contains the modified selection vector that is based on the original selection ...
Header file for the class TypeIIRMLMath::TypeIIRMLPolynomial and the struct TypeIIRMLMath::MotionPoly...
RMLVelocityInputParameters * CurrentInputParameters
Pointer to an RMLVelocityInputParameters object. This object contains a complete set of input values ...
double CycleTime
Contains the cycle time in seconds.
bool CurrentTrajectoryIsPhaseSynchronized
Indicates, whether the current trajectory is phase-synchronized.
Header file for the class RMLVelocityOutputParameters.
Class for the output parameters of the velocity-based On-Line Trajectory Generation algorithm...
RMLDoubleVector * PhaseSynchronizationMaxAccelerationVector
Contains the adapted maximum acceleration vector for phase-synchronized trajectories.
RMLVelocityOutputParameters * OutputParameters
Pointer to an RMLVelocityOutputParameters object. This object contains the output parameters of the m...
RMLDoubleVector * PhaseSynchronizationCurrentVelocityVector
Current velocity vector used for the calculation of phase-synchronized motion trajectories.
RMLDoubleVector * PhaseSynchronizationReferenceVector
Reference vector for phase-synchronized trajectories, with .
FunctionResults
For class-internal use only: return values of boolean methods.
unsigned int NumberOfDOFs
The number of degrees of freedom .
unsigned int DOFWithGreatestExecutionTime
Index of the degree of freedom that requires the greatest execution time.
int ReturnValue
Contains the return value of the method TypeIIRMLVelocity::GetNextStateOfMotion() ...
Class for the input parameters of the velocity-based On-Line Trajectory Generation algorithm...
bool CurrentTrajectoryIsNotSynchronized
Indicates, that the current trajectory is not synchronized.
MotionPolynomials * Polynomials
Pointer to an array of MotionPolynomials objects, which contains the actual trajectory ...
This is a minimalistic dynamic vector class implementation used for the Reflexxes Motion Libraries...
Definition: RMLVector.h:77
RMLVelocityInputParameters * OldInputParameters
Pointer to an RMLVelocityInputParameters object. In order to check, whether a new calculation has to ...
This class constitutes the user interface of velocity-based the Type II On-Line Trajectory Generation...


libreflexxestype2
Author(s):
autogenerated on Sat Nov 21 2020 03:17:34