02_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 #include <iostream>
44 
45 #include <ReflexxesAPI.h>
46 #include <RMLPositionFlags.h>
49 
50 
51 //*************************************************************************
52 // defines
53 
54 #define CYCLE_TIME_IN_SECONDS 0.001
55 #define NUMBER_OF_DOFS 3
56 
57 
58 //*************************************************************************
59 // Main function to run the process that contains the test application
60 //
61 // This function contains source code to get started with the Type II
62 // Reflexxes Motion Library. Based on the program
63 // 01_RMLPositionSampleApplication.cpp, this sample code becomes extended by
64 // using (and describing) all available output values of the algorithm.
65 // As in the former example, we compute a trajectory for a system with
66 // three degrees of freedom starting from an arbitrary state of motion.
67 // This code snippet again directly corresponds to the example trajectories
68 // shown in the documentation.
69 //*************************************************************************
70 int main()
71 {
72  // ********************************************************************
73  // Variable declarations and definitions
74 
75  bool FirstCycleCompleted = false ;
76 
77  int ResultValue = 0 ;
78 
79  unsigned int i = 0
80  , j = 0 ;
81 
82  ReflexxesAPI *RML = NULL ;
83 
84  RMLPositionInputParameters *IP = NULL ;
85 
86  RMLPositionOutputParameters *OP = NULL ;
87 
88  RMLPositionFlags Flags ;
89 
90  // ********************************************************************
91  // Creating all relevant objects of the Type II Reflexxes Motion Library
92 
93  RML = new ReflexxesAPI( NUMBER_OF_DOFS
95 
97 
99 
100  // ********************************************************************
101  // Set-up a timer with a period of one millisecond
102  // (not implemented in this example in order to keep it simple)
103  // ********************************************************************
104 
105  printf("-------------------------------------------------------\n" );
106  printf("Reflexxes Motion Libraries \n" );
107  printf("Example: 02_RMLPositionSampleApplication \n\n");
108  printf("This example demonstrates the use of the entire output \n" );
109  printf("values of the position-based Online Trajectory \n" );
110  printf("Generation algorithm of the Type II Reflexxes Motion \n" );
111  printf("Library. \n\n");
112  printf("Copyright (C) 2014 Google, Inc. \n" );
113  printf("-------------------------------------------------------\n" );
114 
115  // ********************************************************************
116  // Set-up the input parameters
117 
118  // In this test program, arbitrary values are chosen. If executed on a
119  // real robot or mechanical system, the position is read and stored in
120  // an RMLPositionInputParameters::CurrentPositionVector vector object.
121  // For the very first motion after starting the controller, velocities
122  // and acceleration are commonly set to zero. The desired target state
123  // of motion and the motion constraints depend on the robot and the
124  // current task/application.
125  // The internal data structures make use of native C data types
126  // (e.g., IP->CurrentPositionVector->VecData is a pointer to
127  // an array of NUMBER_OF_DOFS double values), such that the Reflexxes
128  // Library can be used in a universal way.
129 
130  IP->CurrentPositionVector->VecData [0] = 100.0 ;
131  IP->CurrentPositionVector->VecData [1] = 0.0 ;
132  IP->CurrentPositionVector->VecData [2] = 50.0 ;
133 
134  IP->CurrentVelocityVector->VecData [0] = 100.0 ;
135  IP->CurrentVelocityVector->VecData [1] = -220.0 ;
136  IP->CurrentVelocityVector->VecData [2] = -50.0 ;
137 
138  IP->CurrentAccelerationVector->VecData [0] = -150.0 ;
139  IP->CurrentAccelerationVector->VecData [1] = 250.0 ;
140  IP->CurrentAccelerationVector->VecData [2] = -50.0 ;
141 
142  IP->MaxVelocityVector->VecData [0] = 300.0 ;
143  IP->MaxVelocityVector->VecData [1] = 100.0 ;
144  IP->MaxVelocityVector->VecData [2] = 300.0 ;
145 
146  IP->MaxAccelerationVector->VecData [0] = 300.0 ;
147  IP->MaxAccelerationVector->VecData [1] = 200.0 ;
148  IP->MaxAccelerationVector->VecData [2] = 100.0 ;
149 
150  IP->MaxJerkVector->VecData [0] = 400.0 ;
151  IP->MaxJerkVector->VecData [1] = 300.0 ;
152  IP->MaxJerkVector->VecData [2] = 200.0 ;
153 
154  IP->TargetPositionVector->VecData [0] = -600.0 ;
155  IP->TargetPositionVector->VecData [1] = -200.0 ;
156  IP->TargetPositionVector->VecData [2] = -350.0 ;
157 
158  IP->TargetVelocityVector->VecData [0] = 50.0 ;
159  IP->TargetVelocityVector->VecData [1] = -50.0 ;
160  IP->TargetVelocityVector->VecData [2] = -200.0 ;
161 
162  IP->SelectionVector->VecData [0] = true ;
163  IP->SelectionVector->VecData [1] = true ;
164  IP->SelectionVector->VecData [2] = true ;
165 
166  // ********************************************************************
167  // Checking the input parameters (optional)
168 
169  if (IP->CheckForValidity())
170  {
171  printf("Input values are valid!\n");
172  }
173  else
174  {
175  printf("Input values are INVALID!\n");
176  }
177 
178  // ********************************************************************
179  // Starting the control loop
180 
181  while (ResultValue != ReflexxesAPI::RML_FINAL_STATE_REACHED)
182  {
183 
184  // ****************************************************************
185  // Wait for the next timer tick
186  // (not implemented in this example in order to keep it simple)
187  // ****************************************************************
188 
189  // Calling the Reflexxes OTG algorithm
190  ResultValue = RML->RMLPosition( *IP
191  , OP
192  , Flags );
193 
194  if (ResultValue < 0)
195  {
196  printf("An error occurred (%d).\n", ResultValue );
197  break;
198  }
199 
200  // ****************************************************************
201  // The following part completely describes all output values
202  // of the Reflexxes Type II Online Trajectory Generation
203  // algorithm.
204 
205  if (!FirstCycleCompleted)
206  {
207  FirstCycleCompleted = true;
208 
209  printf("-------------------------------------------------------\n");
210  printf("General information:\n\n");
211 
212  printf("The execution time of the current trajectory is %.3lf seconds.\n", OP->GetSynchronizationTime());
213 
215  {
216  printf("The current trajectory is phase-synchronized.\n");
217  }
218  else
219  {
220  printf("The current trajectory is time-synchronized.\n");
221  }
223  {
224  printf("The trajectory was computed during the last computation cycle.\n");
225  }
226  else
227  {
228  printf("The input values did not change, and a new computation of the trajectory parameters was not required.\n");
229  }
230 
231  printf("-------------------------------------------------------\n");
232  printf("New state of motion:\n\n");
233 
234  printf("New position/pose vector : ");
235  for ( j = 0; j < NUMBER_OF_DOFS; j++)
236  {
237  printf("%10.3lf ", OP->NewPositionVector->VecData[j]);
238  }
239  printf("\n");
240  printf("New velocity vector : ");
241  for ( j = 0; j < NUMBER_OF_DOFS; j++)
242  {
243  printf("%10.3lf ", OP->NewVelocityVector->VecData[j]);
244  }
245  printf("\n");
246  printf("New acceleration vector : ");
247  for ( j = 0; j < NUMBER_OF_DOFS; j++)
248  {
249  printf("%10.3lf ", OP->NewAccelerationVector->VecData[j]);
250  }
251  printf("\n");
252  printf("-------------------------------------------------------\n");
253  printf("Extremes of the current trajectory:\n");
254 
255  for ( i = 0; i < NUMBER_OF_DOFS; i++)
256  {
257  printf("\n");
258  printf("Degree of freedom : %d\n", i);
259  printf("Minimum position : %10.3lf\n", OP->MinPosExtremaPositionVectorOnly->VecData[i]);
260  printf("Time, at which the minimum will be reached: %10.3lf\n", OP->MinExtremaTimesVector->VecData[i]);
261  printf("Position/pose vector at this time : ");
262  for ( j = 0; j < NUMBER_OF_DOFS; j++)
263  {
264  printf("%10.3lf ", OP->MinPosExtremaPositionVectorArray[i]->VecData[j]);
265  }
266  printf("\n");
267  printf("Velocity vector at this time : ");
268  for ( j = 0; j < NUMBER_OF_DOFS; j++)
269  {
270  printf("%10.3lf ", OP->MinPosExtremaVelocityVectorArray[i]->VecData[j]);
271  }
272  printf("\n");
273  printf("Acceleration vector at this time : ");
274  for ( j = 0; j < NUMBER_OF_DOFS; j++)
275  {
276  printf("%10.3lf ", OP->MinPosExtremaAccelerationVectorArray[i]->VecData[j]);
277  }
278  printf("\n");
279  printf("Maximum position : %10.3lf\n", OP->MaxPosExtremaPositionVectorOnly->VecData[i]);
280  printf("Time, at which the maximum will be reached: %10.3lf\n", OP->MaxExtremaTimesVector->VecData[i]);
281  printf("Position/pose vector at this time : ");
282  for ( j = 0; j < NUMBER_OF_DOFS; j++)
283  {
284  printf("%10.3lf ", OP->MaxPosExtremaPositionVectorArray[i]->VecData[j]);
285  }
286  printf("\n");
287  printf("Velocity vector at this time : ");
288  for ( j = 0; j < NUMBER_OF_DOFS; j++)
289  {
290  printf("%10.3lf ", OP->MaxPosExtremaVelocityVectorArray[i]->VecData[j]);
291  }
292  printf("\n");
293  printf("Acceleration vector at this time : ");
294  for ( j = 0; j < NUMBER_OF_DOFS; j++)
295  {
296  printf("%10.3lf ", OP->MaxPosExtremaAccelerationVectorArray[i]->VecData[j]);
297  }
298  printf("\n");
299  }
300  printf("-------------------------------------------------------\n");
301 
302  }
303  // ****************************************************************
304 
305  // ****************************************************************
306  // Feed the output values of the current control cycle back to
307  // input values of the next control cycle
308 
312  std::cout << IP->CurrentPositionVector->VecData [0]<< " " << IP->CurrentPositionVector->VecData [1] << " " << IP->CurrentPositionVector->VecData [2] << std::endl;
313  }
314 
315  // ********************************************************************
316  // Deleting the objects of the Reflexxes Motion Library end terminating
317  // the process
318 
319  delete RML ;
320  delete IP ;
321  delete OP ;
322 
323  exit(EXIT_SUCCESS) ;
324 }
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 .
#define CYCLE_TIME_IN_SECONDS
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...
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