-
Notifications
You must be signed in to change notification settings - Fork 171
/
1_position.cpp
37 lines (27 loc) · 1.14 KB
/
1_position.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
#include <iostream>
#include <ruckig/ruckig.hpp>
using namespace ruckig;
int main() {
// Create instances: the Ruckig OTG as well as input and output parameters
Ruckig<3> otg {0.01}; // control cycle
InputParameter<3> input;
OutputParameter<3> output;
// Set input parameters
input.current_position = {0.0, 0.0, 0.5};
input.current_velocity = {0.0, -2.2, -0.5};
input.current_acceleration = {0.0, 2.5, -0.5};
input.target_position = {5.0, -2.0, -3.5};
input.target_velocity = {0.0, -0.5, -2.0};
input.target_acceleration = {0.0, 0.0, 0.5};
input.max_velocity = {3.0, 1.0, 3.0};
input.max_acceleration = {3.0, 2.0, 1.0};
input.max_jerk = {4.0, 3.0, 2.0};
// Generate the trajectory within the control loop
std::cout << "t | p1 | p2 | p3" << std::endl;
while (otg.update(input, output) == Result::Working) {
auto& p = output.new_position;
std::cout << output.time << " " << p[0] << " " << p[1] << " " << p[2] << " " << std::endl;
output.pass_to_input(input);
}
std::cout << "Trajectory duration: " << output.trajectory.get_duration() << " [s]." << std::endl;
}