08_RMLVelocitySampleApplication.cpp
Go to the documentation of this file.
1 // ---------------------- Doxygen info ----------------------
35 // ----------------------------------------------------------
36 // For a convenient reading of this file's source code,
37 // please use a tab width of four characters.
38 // ----------------------------------------------------------
39 
40 
41 #include <stdio.h>
42 #include <stdlib.h>
43 
44 #include <ReflexxesAPI.h>
45 #include <RMLVelocityFlags.h>
48 
49 
50 //*************************************************************************
51 // defines
52 
53 #define CYCLE_TIME_IN_SECONDS 0.001
54 #define NUMBER_OF_DOFS 3
55 
56 
57 //*************************************************************************
58 // Main function to run the process that contains the test application
59 //
60 // This function contains source code to get started with the Type II
61 // Reflexxes Motion Library. Based on the program
62 // 04_RMLVelocitySampleApplication.cpp, this sample code becomes extended by
63 // using (and describing) all available output values of the velocity-based
64 // algorithm. As in the former example, we compute a trajectory for a
65 // system with three degrees of freedom starting from an arbitrary state of
66 // motion. This code snippet again directly corresponds to the example
67 // trajectories shown in the documentation.
68 //*************************************************************************
69 int main()
70 {
71  // ********************************************************************
72  // Variable declarations and definitions
73 
74  bool FirstCycleCompleted = false ;
75 
76  int ResultValue = 0
77  , i = 0
78  , j = 0 ;
79 
80  ReflexxesAPI *RML = NULL ;
81 
82  RMLVelocityInputParameters *IP = NULL ;
83 
84  RMLVelocityOutputParameters *OP = NULL ;
85 
86  RMLVelocityFlags Flags ;
87 
88  // ********************************************************************
89  // Creating all relevant objects of the Type II Reflexxes Motion Library
90 
91  RML = new ReflexxesAPI( NUMBER_OF_DOFS
93 
95 
97 
98  // ********************************************************************
99  // Set-up a timer with a period of one millisecond
100  // (not implemented in this example in order to keep it simple)
101  // ********************************************************************
102 
103  printf("-------------------------------------------------------\n" );
104  printf("Reflexxes Motion Libraries \n" );
105  printf("Example: 08_RMLVelocitySampleApplication \n\n");
106  printf("This example demonstrates the use of the entire output \n" );
107  printf("values of the velocity-based Online Trajectory \n" );
108  printf("Generation algorithm of the Type II Reflexxes Motion \n" );
109  printf("Library. \n\n");
110  printf("Copyright (C) 2014 Google, Inc. \n" );
111  printf("-------------------------------------------------------\n" );
112 
113  // ********************************************************************
114  // Set-up the input parameters
115 
116  // In this test program, arbitrary values are chosen. If executed on a
117  // real robot or mechanical system, the position is read and stored in
118  // an RMLVelocityInputParameters::CurrentPositionVector vector object.
119  // For the very first motion after starting the controller, velocities
120  // and acceleration are commonly set to zero. The desired target state
121  // of motion and the motion constraints depend on the robot and the
122  // current task/application.
123  // The internal data structures make use of native C data types
124  // (e.g., IP->CurrentPositionVector->VecData is a pointer to
125  // an array of NUMBER_OF_DOFS double values), such that the Reflexxes
126  // Library can be used in a universal way.
127 
128  IP->CurrentPositionVector->VecData [0] = -200.0 ;
129  IP->CurrentPositionVector->VecData [1] = 100.0 ;
130  IP->CurrentPositionVector->VecData [2] = -300.0 ;
131 
132  IP->CurrentVelocityVector->VecData [0] = -150.0 ;
133  IP->CurrentVelocityVector->VecData [1] = 100.0 ;
134  IP->CurrentVelocityVector->VecData [2] = 50.0 ;
135 
136  IP->CurrentAccelerationVector->VecData [0] = 350.0 ;
137  IP->CurrentAccelerationVector->VecData [1] = -500.0 ;
138  IP->CurrentAccelerationVector->VecData [2] = 0.0 ;
139 
140  IP->MaxAccelerationVector->VecData [0] = 500.0 ;
141  IP->MaxAccelerationVector->VecData [1] = 500.0 ;
142  IP->MaxAccelerationVector->VecData [2] = 1000.0 ;
143 
144  IP->MaxJerkVector->VecData [0] = 1000.0 ;
145  IP->MaxJerkVector->VecData [1] = 700.0 ;
146  IP->MaxJerkVector->VecData [2] = 500.0 ;
147 
148  IP->TargetVelocityVector->VecData [0] = 150.0 ;
149  IP->TargetVelocityVector->VecData [1] = 75.0 ;
150  IP->TargetVelocityVector->VecData [2] = 100.0 ;
151 
152  IP->SelectionVector->VecData [0] = true ;
153  IP->SelectionVector->VecData [1] = true ;
154  IP->SelectionVector->VecData [2] = true ;
155 
156  // ********************************************************************
157  // Specifying the minimum synchronization time
158 
159  IP->MinimumSynchronizationTime = 2.5 ;
160 
161  // ********************************************************************
162  // Checking the input parameters (optional)
163 
164  if (IP->CheckForValidity())
165  {
166  printf("Input values are valid!\n");
167  }
168  else
169  {
170  printf("Input values are INVALID!\n");
171  }
172 
174 
175  // ********************************************************************
176  // Starting the control loop
177 
178  while (ResultValue != ReflexxesAPI::RML_FINAL_STATE_REACHED)
179  {
180 
181  // ****************************************************************
182  // Wait for the next timer tick
183  // (not implemented in this example in order to keep it simple)
184  // ****************************************************************
185 
186  // Calling the Reflexxes OTG algorithm
187  ResultValue = RML->RMLVelocity( *IP
188  , OP
189  , Flags );
190 
191  if (ResultValue < 0)
192  {
193  printf("An error occurred (%d).\n", ResultValue );
194  break;
195  }
196 
197  // ****************************************************************
198  // The following part completely describes all output values
199  // of the Reflexxes Type II Online Trajectory Generation
200  // algorithm.
201 
202  if (!FirstCycleCompleted)
203  {
204  FirstCycleCompleted = true;
205 
206  printf("-------------------------------------------------------\n");
207  printf("General information:\n\n");
208 
210  {
211  printf("The current trajectory is phase-synchronized.\n");
212  }
213  else
214  {
215  printf("The current trajectory is time-synchronized.\n");
216  }
218  {
219  printf("The trajectory was computed during the last computation cycle.\n");
220  }
221  else
222  {
223  printf("The input values did not change, and a new computation of the trajectory parameters was not required.\n");
224  }
225 
226  for ( j = 0; j < NUMBER_OF_DOFS; j++)
227  {
228  printf("The degree of freedom with the index %d will reach its target velocity at position %.3lf after %.3lf seconds.\n"
229  , j
231  , OP->ExecutionTimes->VecData[j] );
232  }
233 
234  printf("The degree of freedom with the index %d will require the greatest execution time.\n", OP->GetDOFWithTheGreatestExecutionTime());
235 
236  printf("-------------------------------------------------------\n");
237  printf("New state of motion:\n\n");
238 
239  printf("New position/pose vector : ");
240  for ( j = 0; j < NUMBER_OF_DOFS; j++)
241  {
242  printf("%10.3lf ", OP->NewPositionVector->VecData[j]);
243  }
244  printf("\n");
245  printf("New velocity vector : ");
246  for ( j = 0; j < NUMBER_OF_DOFS; j++)
247  {
248  printf("%10.3lf ", OP->NewVelocityVector->VecData[j]);
249  }
250  printf("\n");
251  printf("New acceleration vector : ");
252  for ( j = 0; j < NUMBER_OF_DOFS; j++)
253  {
254  printf("%10.3lf ", OP->NewAccelerationVector->VecData[j]);
255  }
256  printf("\n");
257  printf("-------------------------------------------------------\n");
258  printf("Extremes of the current trajectory:\n");
259 
260  for ( i = 0; i < NUMBER_OF_DOFS; i++)
261  {
262  printf("\n");
263  printf("Degree of freedom : %d\n", i);
264  printf("Minimum position : %10.3lf\n", OP->MinPosExtremaPositionVectorOnly->VecData[i]);
265  printf("Time, at which the minimum will be reached: %10.3lf\n", OP->MinExtremaTimesVector->VecData[i]);
266  printf("Position/pose vector at this time : ");
267  for ( j = 0; j < NUMBER_OF_DOFS; j++)
268  {
269  printf("%10.3lf ", OP->MinPosExtremaPositionVectorArray[i]->VecData[j]);
270  }
271  printf("\n");
272  printf("Velocity vector at this time : ");
273  for ( j = 0; j < NUMBER_OF_DOFS; j++)
274  {
275  printf("%10.3lf ", OP->MinPosExtremaVelocityVectorArray[i]->VecData[j]);
276  }
277  printf("\n");
278  printf("Acceleration vector at this time : ");
279  for ( j = 0; j < NUMBER_OF_DOFS; j++)
280  {
281  printf("%10.3lf ", OP->MinPosExtremaAccelerationVectorArray[i]->VecData[j]);
282  }
283  printf("\n");
284  printf("Maximum position : %10.3lf\n", OP->MaxPosExtremaPositionVectorOnly->VecData[i]);
285  printf("Time, at which the maximum will be reached: %10.3lf\n", OP->MaxExtremaTimesVector->VecData[i]);
286  printf("Position/pose vector at this time : ");
287  for ( j = 0; j < NUMBER_OF_DOFS; j++)
288  {
289  printf("%10.3lf ", OP->MaxPosExtremaPositionVectorArray[i]->VecData[j]);
290  }
291  printf("\n");
292  printf("Velocity vector at this time : ");
293  for ( j = 0; j < NUMBER_OF_DOFS; j++)
294  {
295  printf("%10.3lf ", OP->MaxPosExtremaVelocityVectorArray[i]->VecData[j]);
296  }
297  printf("\n");
298  printf("Acceleration vector at this time : ");
299  for ( j = 0; j < NUMBER_OF_DOFS; j++)
300  {
301  printf("%10.3lf ", OP->MaxPosExtremaAccelerationVectorArray[i]->VecData[j]);
302  }
303  printf("\n");
304  }
305  printf("-------------------------------------------------------\n");
306  }
307  // ****************************************************************
308 
309  // ****************************************************************
310  // Feed the output values of the current control cycle back to
311  // input values of the next control cycle
312 
316  }
317 
318  // ********************************************************************
319  // Deleting the objects of the Reflexxes Motion Library end terminating
320  // the process
321 
322  delete RML ;
323  delete IP ;
324  delete OP ;
325 
326  exit(EXIT_SUCCESS) ;
327 }
Header file for the class ReflexxesAPI (API of the Reflexxes Motion Libraries)
unsigned int GetDOFWithTheGreatestExecutionTime(void) const
Returns the index of the degree of freedom with the greatest trajectory execution time...
RMLDoubleVector * NewAccelerationVector
A pointer to the new acceleration vector .
Data structure containing flags to parameterize the execution of the velocity-based On-Line Trajector...
RMLDoubleVector * CurrentVelocityVector
A pointer to the current velocity vector .
RMLDoubleVector ** MaxPosExtremaAccelerationVectorArray
A pointer to an array of pointers to RMLDoubleVector objects. The number of array elements equals the...
RMLDoubleVector * MaxAccelerationVector
A pointer to the maximum acceleration vector .
RMLDoubleVector * ExecutionTimes
A pointer to an RMLDoubleVector object that contains the execution times of all selected degrees of f...
T * VecData
Pointer to the actual vector data, that is, an array of type T objects.
Definition: RMLVector.h:524
#define CYCLE_TIME_IN_SECONDS
RMLDoubleVector * NewPositionVector
A pointer to the new position vector .
RMLDoubleVector ** MaxPosExtremaVelocityVectorArray
A pointer to an array of pointers to RMLDoubleVector objects. The number of array elements equals the...
double MinimumSynchronizationTime
Minimum trajectory execution time in seconds specified by the user (optional input parameter) ...
RMLDoubleVector ** MinPosExtremaVelocityVectorArray
A pointer to an array of pointers to RMLDoubleVector objects. The number of array elements equals the...
RMLDoubleVector * MaxExtremaTimesVector
A pointer to an RMLDoubleVector object that contains the times at which each degree of freedom reache...
Header file for the class RMLVelocityInputParameters.
Header file for the class RMLVelocityFlags.
RMLDoubleVector * MinExtremaTimesVector
A pointer to an RMLDoubleVector object that contains the times at which each degree of freedom reache...
bool IsTrajectoryPhaseSynchronized(void) const
Indicates whether the currently calculated trajectory is phase- synchronized or only time-synchronize...
unsigned char SynchronizationBehavior
This value specifies the desired synchronization behavior.
Definition: RMLFlags.h:192
RMLBoolVector * SelectionVector
A pointer to the selection vector .
Header file for the class RMLVelocityOutputParameters.
Class for the output parameters of the velocity-based On-Line Trajectory Generation algorithm...
int RMLVelocity(const RMLVelocityInputParameters &InputValues, RMLVelocityOutputParameters *OutputValues, const RMLVelocityFlags &Flags)
This is the method for velocity-based On-Line Trajectory Generation.
Even if it is possible to calculate a phase-synchronized trajectory, only a time-synchronized traject...
Definition: RMLFlags.h:152
bool WasACompleteComputationPerformedDuringTheLastCycle(void) const
Indicates, whether a new computation was performed in the last cycle.
bool CheckForValidity(void) const
Checks the input parameters for validity.
This class constitutes the API of the Reflexxes Motion Libraries
Definition: ReflexxesAPI.h:123
RMLDoubleVector * TargetVelocityVector
A pointer to the target velocity vector .
RMLDoubleVector * MaxJerkVector
A pointer to the maximum jerk vector .
RMLDoubleVector * NewVelocityVector
A pointer to the new velocity vector .
RMLDoubleVector * MinPosExtremaPositionVectorOnly
A pointer to an RMLDoubleVector object that contains the maximum positions for all degrees of freedom...
Class for the input parameters of the velocity-based On-Line Trajectory Generation algorithm...
RMLDoubleVector * MaxPosExtremaPositionVectorOnly
A pointer to an RMLDoubleVector object that contains the maximum positions for all degrees of freedom...
RMLDoubleVector * PositionValuesAtTargetVelocity
A pointer to an RMLDoubleVector object that contains the position values at the instants the desired ...
RMLDoubleVector ** MinPosExtremaAccelerationVectorArray
A pointer to an array of pointers to RMLDoubleVector objects. The number of array elements equals the...
RMLDoubleVector * CurrentAccelerationVector
A pointer to the current acceleration vector .
RMLDoubleVector * CurrentPositionVector
A pointer to the current position vector .
RMLDoubleVector ** MinPosExtremaPositionVectorArray
A pointer to an array of pointers to RMLDoubleVector objects. The number of array elements equals the...
RMLDoubleVector ** MaxPosExtremaPositionVectorArray
A pointer to an array of pointers to RMLDoubleVector objects. The number of array elements equals the...


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