05_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 
78  unsigned int i = 0
79  , j = 0 ;
80 
81  ReflexxesAPI *RML = NULL ;
82 
83  RMLVelocityInputParameters *IP = NULL ;
84 
85  RMLVelocityOutputParameters *OP = NULL ;
86 
87  RMLVelocityFlags Flags ;
88 
89  // ********************************************************************
90  // Creating all relevant objects of the Type II Reflexxes Motion Library
91 
92  RML = new ReflexxesAPI( NUMBER_OF_DOFS
94 
96 
98 
99  // ********************************************************************
100  // Set-up a timer with a period of one millisecond
101  // (not implemented in this example in order to keep it simple)
102  // ********************************************************************
103 
104  printf("-------------------------------------------------------\n" );
105  printf("Reflexxes Motion Libraries \n" );
106  printf("Example: 05_RMLVelocitySampleApplication \n\n");
107  printf("This example demonstrates the use of the entire output \n" );
108  printf("values of the velocity-based Online Trajectory \n" );
109  printf("Generation algorithm of the Type II Reflexxes Motion \n" );
110  printf("Library. \n\n");
111  printf("Copyright (C) 2014 Google, Inc. \n" );
112  printf("-------------------------------------------------------\n" );
113 
114  // ********************************************************************
115  // Set-up the input parameters
116 
117  // In this test program, arbitrary values are chosen. If executed on a
118  // real robot or mechanical system, the position is read and stored in
119  // an RMLVelocityInputParameters::CurrentPositionVector vector object.
120  // For the very first motion after starting the controller, velocities
121  // and acceleration are commonly set to zero. The desired target state
122  // of motion and the motion constraints depend on the robot and the
123  // current task/application.
124  // The internal data structures make use of native C data types
125  // (e.g., IP->CurrentPositionVector->VecData is a pointer to
126  // an array of NUMBER_OF_DOFS double values), such that the Reflexxes
127  // Library can be used in a universal way.
128 
129  IP->CurrentPositionVector->VecData [0] = -200.0 ;
130  IP->CurrentPositionVector->VecData [1] = 100.0 ;
131  IP->CurrentPositionVector->VecData [2] = -300.0 ;
132 
133  IP->CurrentVelocityVector->VecData [0] = -150.0 ;
134  IP->CurrentVelocityVector->VecData [1] = 100.0 ;
135  IP->CurrentVelocityVector->VecData [2] = 50.0 ;
136 
137  IP->CurrentAccelerationVector->VecData [0] = 350.0 ;
138  IP->CurrentAccelerationVector->VecData [1] = -500.0 ;
139  IP->CurrentAccelerationVector->VecData [2] = 0.0 ;
140 
141  IP->MaxAccelerationVector->VecData [0] = 500.0 ;
142  IP->MaxAccelerationVector->VecData [1] = 500.0 ;
143  IP->MaxAccelerationVector->VecData [2] = 1000.0 ;
144 
145  IP->MaxJerkVector->VecData [0] = 1000.0 ;
146  IP->MaxJerkVector->VecData [1] = 700.0 ;
147  IP->MaxJerkVector->VecData [2] = 500.0 ;
148 
149  IP->TargetVelocityVector->VecData [0] = 150.0 ;
150  IP->TargetVelocityVector->VecData [1] = 75.0 ;
151  IP->TargetVelocityVector->VecData [2] = 100.0 ;
152 
153  IP->SelectionVector->VecData [0] = true ;
154  IP->SelectionVector->VecData [1] = true ;
155  IP->SelectionVector->VecData [2] = true ;
156 
157  // ********************************************************************
158  // Checking the input parameters (optional)
159 
160  if (IP->CheckForValidity())
161  {
162  printf("Input values are valid!\n");
163  }
164  else
165  {
166  printf("Input values are INVALID!\n");
167  }
168 
169  // ********************************************************************
170  // Starting the control loop
171 
172  while (ResultValue != ReflexxesAPI::RML_FINAL_STATE_REACHED)
173  {
174 
175  // ****************************************************************
176  // Wait for the next timer tick
177  // (not implemented in this example in order to keep it simple)
178  // ****************************************************************
179 
180  // Calling the Reflexxes OTG algorithm
181  ResultValue = RML->RMLVelocity( *IP
182  , OP
183  , Flags );
184 
185  if (ResultValue < 0)
186  {
187  printf("An error occurred (%d).\n", ResultValue );
188  break;
189  }
190 
191  // ****************************************************************
192  // The following part completely describes all output values
193  // of the Reflexxes Type II Online Trajectory Generation
194  // algorithm.
195 
196  if (!FirstCycleCompleted)
197  {
198  FirstCycleCompleted = true;
199 
200  printf("-------------------------------------------------------\n");
201  printf("General information:\n\n");
202 
204  {
205  printf("The current trajectory is phase-synchronized.\n");
206  }
207  else
208  {
209  printf("The current trajectory is time-synchronized.\n");
210  }
212  {
213  printf("The trajectory was computed during the last computation cycle.\n");
214  }
215  else
216  {
217  printf("The input values did not change, and a new computation of the trajectory parameters was not required.\n");
218  }
219 
220  for ( j = 0; j < NUMBER_OF_DOFS; j++)
221  {
222  printf("The degree of freedom with the index %d will reach its target velocity at position %.3lf after %.3lf seconds.\n"
223  , j
225  , OP->ExecutionTimes->VecData[j] );
226  }
227 
228  printf("The degree of freedom with the index %d will require the greatest execution time.\n", OP->GetDOFWithTheGreatestExecutionTime());
229 
230  printf("-------------------------------------------------------\n");
231  printf("New state of motion:\n\n");
232 
233  printf("New position/pose vector : ");
234  for ( j = 0; j < NUMBER_OF_DOFS; j++)
235  {
236  printf("%10.3lf ", OP->NewPositionVector->VecData[j]);
237  }
238  printf("\n");
239  printf("New velocity vector : ");
240  for ( j = 0; j < NUMBER_OF_DOFS; j++)
241  {
242  printf("%10.3lf ", OP->NewVelocityVector->VecData[j]);
243  }
244  printf("\n");
245  printf("New acceleration vector : ");
246  for ( j = 0; j < NUMBER_OF_DOFS; j++)
247  {
248  printf("%10.3lf ", OP->NewAccelerationVector->VecData[j]);
249  }
250  printf("\n");
251  printf("-------------------------------------------------------\n");
252  printf("Extremes of the current trajectory:\n");
253 
254  for ( i = 0; i < NUMBER_OF_DOFS; i++)
255  {
256  printf("\n");
257  printf("Degree of freedom : %d\n", i);
258  printf("Minimum position : %10.3lf\n", OP->MinPosExtremaPositionVectorOnly->VecData[i]);
259  printf("Time, at which the minimum will be reached: %10.3lf\n", OP->MinExtremaTimesVector->VecData[i]);
260  printf("Position/pose vector at this time : ");
261  for ( j = 0; j < NUMBER_OF_DOFS; j++)
262  {
263  printf("%10.3lf ", OP->MinPosExtremaPositionVectorArray[i]->VecData[j]);
264  }
265  printf("\n");
266  printf("Velocity vector at this time : ");
267  for ( j = 0; j < NUMBER_OF_DOFS; j++)
268  {
269  printf("%10.3lf ", OP->MinPosExtremaVelocityVectorArray[i]->VecData[j]);
270  }
271  printf("\n");
272  printf("Acceleration vector at this time : ");
273  for ( j = 0; j < NUMBER_OF_DOFS; j++)
274  {
275  printf("%10.3lf ", OP->MinPosExtremaAccelerationVectorArray[i]->VecData[j]);
276  }
277  printf("\n");
278  printf("Maximum position : %10.3lf\n", OP->MaxPosExtremaPositionVectorOnly->VecData[i]);
279  printf("Time, at which the maximum will be reached: %10.3lf\n", OP->MaxExtremaTimesVector->VecData[i]);
280  printf("Position/pose vector at this time : ");
281  for ( j = 0; j < NUMBER_OF_DOFS; j++)
282  {
283  printf("%10.3lf ", OP->MaxPosExtremaPositionVectorArray[i]->VecData[j]);
284  }
285  printf("\n");
286  printf("Velocity vector at this time : ");
287  for ( j = 0; j < NUMBER_OF_DOFS; j++)
288  {
289  printf("%10.3lf ", OP->MaxPosExtremaVelocityVectorArray[i]->VecData[j]);
290  }
291  printf("\n");
292  printf("Acceleration vector at this time : ");
293  for ( j = 0; j < NUMBER_OF_DOFS; j++)
294  {
295  printf("%10.3lf ", OP->MaxPosExtremaAccelerationVectorArray[i]->VecData[j]);
296  }
297  printf("\n");
298  }
299  printf("-------------------------------------------------------\n");
300 
301  }
302  // ****************************************************************
303 
304  // ****************************************************************
305  // Feed the output values of the current control cycle back to
306  // input values of the next control cycle
307 
311  }
312 
313  // ********************************************************************
314  // Deleting the objects of the Reflexxes Motion Library end terminating
315  // the process
316 
317  delete RML ;
318  delete IP ;
319  delete OP ;
320 
321  exit(EXIT_SUCCESS) ;
322 }
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
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...
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...
#define CYCLE_TIME_IN_SECONDS
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.
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