07_RMLPositionSampleApplication.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 <RMLPositionFlags.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 // 01_RMLPositionSampleApplication.cpp, this sample code becomes extended by
63 // using (and describing) all available output values of the algorithm.
64 // As in the former example, we compute a trajectory for a system with
65 // three degrees of freedom starting from an arbitrary state of motion.
66 // This code snippet again directly corresponds to the example trajectories
67 // 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  RMLPositionInputParameters *IP = NULL ;
83 
84  RMLPositionOutputParameters *OP = NULL ;
85 
86  RMLPositionFlags 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: 07_RMLPositionSampleApplication.cpp \n\n");
106  printf("This example demonstrates the use of the entire output \n" );
107  printf("values of the position-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 RMLPositionInputParameters::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] = 100.0 ;
129  IP->CurrentPositionVector->VecData [1] = 0.0 ;
130  IP->CurrentPositionVector->VecData [2] = 50.0 ;
131 
132  IP->CurrentVelocityVector->VecData [0] = 100.0 ;
133  IP->CurrentVelocityVector->VecData [1] = -220.0 ;
134  IP->CurrentVelocityVector->VecData [2] = -50.0 ;
135 
136  IP->CurrentAccelerationVector->VecData [0] = -150.0 ;
137  IP->CurrentAccelerationVector->VecData [1] = 250.0 ;
138  IP->CurrentAccelerationVector->VecData [2] = -50.0 ;
139 
140  IP->MaxVelocityVector->VecData [0] = 300.0 ;
141  IP->MaxVelocityVector->VecData [1] = 100.0 ;
142  IP->MaxVelocityVector->VecData [2] = 300.0 ;
143 
144  IP->MaxAccelerationVector->VecData [0] = 300.0 ;
145  IP->MaxAccelerationVector->VecData [1] = 200.0 ;
146  IP->MaxAccelerationVector->VecData [2] = 100.0 ;
147 
148  IP->MaxJerkVector->VecData [0] = 400.0 ;
149  IP->MaxJerkVector->VecData [1] = 300.0 ;
150  IP->MaxJerkVector->VecData [2] = 200.0 ;
151 
152  IP->TargetPositionVector->VecData [0] = -600.0 ;
153  IP->TargetPositionVector->VecData [1] = -200.0 ;
154  IP->TargetPositionVector->VecData [2] = -350.0 ;
155 
156  IP->TargetVelocityVector->VecData [0] = 50.0 ;
157  IP->TargetVelocityVector->VecData [1] = -50.0 ;
158  IP->TargetVelocityVector->VecData [2] = -200.0 ;
159 
160  IP->SelectionVector->VecData [0] = true ;
161  IP->SelectionVector->VecData [1] = true ;
162  IP->SelectionVector->VecData [2] = true ;
163 
164  // ********************************************************************
165  // Specifying the minimum synchronization time
166 
167  IP->MinimumSynchronizationTime = 6.5 ;
168 
169  // ********************************************************************
170  // Checking the input parameters (optional)
171 
172  if (IP->CheckForValidity())
173  {
174  printf("Input values are valid!\n");
175  }
176  else
177  {
178  printf("Input values are INVALID!\n");
179  }
180 
181  // ********************************************************************
182  // Starting the control loop
183 
184  while (ResultValue != ReflexxesAPI::RML_FINAL_STATE_REACHED)
185  {
186 
187  // ****************************************************************
188  // Wait for the next timer tick
189  // (not implemented in this example in order to keep it simple)
190  // ****************************************************************
191 
192  // Calling the Reflexxes OTG algorithm
193  ResultValue = RML->RMLPosition( *IP
194  , OP
195  , Flags );
196 
197  if (ResultValue < 0)
198  {
199  printf("An error occurred (%d).\n", ResultValue );
200  break;
201  }
202 
203  // ****************************************************************
204  // The following part completely describes all output values
205  // of the Reflexxes Type II Online Trajectory Generation
206  // algorithm.
207 
208  if (!FirstCycleCompleted)
209  {
210  FirstCycleCompleted = true;
211 
212  printf("-------------------------------------------------------\n");
213  printf("General information:\n\n");
214 
215  printf("The execution time of the current trajectory is %.3lf seconds.\n", OP->GetSynchronizationTime());
216 
218  {
219  printf("The current trajectory is phase-synchronized.\n");
220  }
221  else
222  {
223  printf("The current trajectory is time-synchronized.\n");
224  }
226  {
227  printf("The trajectory was computed during the last computation cycle.\n");
228  }
229  else
230  {
231  printf("The input values did not change, and a new computation of the trajectory parameters was not required.\n");
232  }
233 
234  printf("-------------------------------------------------------\n");
235  printf("New state of motion:\n\n");
236 
237  printf("New position/pose vector : ");
238  for ( j = 0; j < NUMBER_OF_DOFS; j++)
239  {
240  printf("%10.3lf ", OP->NewPositionVector->VecData[j]);
241  }
242  printf("\n");
243  printf("New velocity vector : ");
244  for ( j = 0; j < NUMBER_OF_DOFS; j++)
245  {
246  printf("%10.3lf ", OP->NewVelocityVector->VecData[j]);
247  }
248  printf("\n");
249  printf("New acceleration vector : ");
250  for ( j = 0; j < NUMBER_OF_DOFS; j++)
251  {
252  printf("%10.3lf ", OP->NewAccelerationVector->VecData[j]);
253  }
254  printf("\n");
255  printf("-------------------------------------------------------\n");
256  printf("Extremes of the current trajectory:\n");
257 
258  for ( i = 0; i < NUMBER_OF_DOFS; i++)
259  {
260  printf("\n");
261  printf("Degree of freedom : %d\n", i);
262  printf("Minimum position : %10.3lf\n", OP->MinPosExtremaPositionVectorOnly->VecData[i]);
263  printf("Time, at which the minimum will be reached: %10.3lf\n", OP->MinExtremaTimesVector->VecData[i]);
264  printf("Position/pose vector at this time : ");
265  for ( j = 0; j < NUMBER_OF_DOFS; j++)
266  {
267  printf("%10.3lf ", OP->MinPosExtremaPositionVectorArray[i]->VecData[j]);
268  }
269  printf("\n");
270  printf("Velocity vector at this time : ");
271  for ( j = 0; j < NUMBER_OF_DOFS; j++)
272  {
273  printf("%10.3lf ", OP->MinPosExtremaVelocityVectorArray[i]->VecData[j]);
274  }
275  printf("\n");
276  printf("Acceleration vector at this time : ");
277  for ( j = 0; j < NUMBER_OF_DOFS; j++)
278  {
279  printf("%10.3lf ", OP->MinPosExtremaAccelerationVectorArray[i]->VecData[j]);
280  }
281  printf("\n");
282  printf("Maximum position : %10.3lf\n", OP->MaxPosExtremaPositionVectorOnly->VecData[i]);
283  printf("Time, at which the maximum will be reached: %10.3lf\n", OP->MaxExtremaTimesVector->VecData[i]);
284  printf("Position/pose vector at this time : ");
285  for ( j = 0; j < NUMBER_OF_DOFS; j++)
286  {
287  printf("%10.3lf ", OP->MaxPosExtremaPositionVectorArray[i]->VecData[j]);
288  }
289  printf("\n");
290  printf("Velocity vector at this time : ");
291  for ( j = 0; j < NUMBER_OF_DOFS; j++)
292  {
293  printf("%10.3lf ", OP->MaxPosExtremaVelocityVectorArray[i]->VecData[j]);
294  }
295  printf("\n");
296  printf("Acceleration vector at this time : ");
297  for ( j = 0; j < NUMBER_OF_DOFS; j++)
298  {
299  printf("%10.3lf ", OP->MaxPosExtremaAccelerationVectorArray[i]->VecData[j]);
300  }
301  printf("\n");
302  }
303  printf("-------------------------------------------------------\n");
304  }
305  // ****************************************************************
306 
307  // ****************************************************************
308  // Feed the output values of the current control cycle back to
309  // input values of the next control cycle
310 
314  }
315 
316  // ********************************************************************
317  // Deleting the objects of the Reflexxes Motion Library end terminating
318  // the process
319 
320  delete RML ;
321  delete IP ;
322  delete OP ;
323 
324  exit(EXIT_SUCCESS) ;
325 }
Header file for the class RMLPositionOutputParameters.
Header file for the class ReflexxesAPI (API of the Reflexxes Motion Libraries)
Header file for the class RMLPositionFlags.
RMLDoubleVector * NewAccelerationVector
A pointer to the new acceleration vector .
Data structure containing flags to parameterize the execution of the position-based On-Line Trajector...
RMLDoubleVector * CurrentVelocityVector
A pointer to the current velocity vector .
double GetSynchronizationTime(void) const
Returns the synchronization time.
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 .
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...
Header file for the class RMLPositionInputParameters.
RMLDoubleVector * MaxExtremaTimesVector
A pointer to an RMLDoubleVector object that contains the times at which each degree of freedom reache...
RMLDoubleVector * MaxVelocityVector
A pointer to the maximum velocity vector .
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...
int RMLPosition(const RMLPositionInputParameters &InputValues, RMLPositionOutputParameters *OutputValues, const RMLPositionFlags &Flags)
This is the central method of each Reflexxes Type Motion Library.
RMLBoolVector * SelectionVector
A pointer to the selection vector .
RMLDoubleVector * TargetPositionVector
A pointer to the target position vector .
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 .
Class for the output parameters of the position-based On-Line Trajectory Generation algorithm...
RMLDoubleVector * NewVelocityVector
A pointer to the new velocity vector .
Class for the input parameters of the position-based On-Line Trajectory Generation algorithm...
RMLDoubleVector * MinPosExtremaPositionVectorOnly
A pointer to an RMLDoubleVector object that contains the maximum positions for all degrees of freedom...
RMLDoubleVector * MaxPosExtremaPositionVectorOnly
A pointer to an RMLDoubleVector object that contains the maximum positions for all degrees of freedom...
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