Skip to content

Commit

Permalink
refine max time deviation to 1e-8
Browse files Browse the repository at this point in the history
  • Loading branch information
pantor committed Dec 26, 2020
1 parent 0a03c62 commit 4d0e94e
Show file tree
Hide file tree
Showing 9 changed files with 1,299 additions and 569 deletions.
50 changes: 50 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,54 @@ make
make install
```

A python module can be built using the `BUILD_PYTHON_MODULE` CMake flag.


## Tutorial

Figure.


### Real-time trajectory generation

```c++
Ruckig<6> ruckig {0.001}; // DoF, control cycle in [s]

InputParameter<6> input;
input.current_position = {};
input.current_velocity = {};
input.current_acceleration = {};
input.target_position = {};
input.target_velocity = {};
input.target_acceleration = {};
input.max_velocity = {};
input.max_acceleration = {};
input.max_jerk = {};

OutputParameter<6> output;

while (otg.update(input, output) == Result::Working) {
// output.new_position

input.current_position = output.new_position;
input.current_velocity = output.new_velocity;
input.current_acceleration = output.new_acceleration;
}

```

### Input Type


### Result Type


### Output Type


### Exceptions


## Development

Ruckig is written in C++17. It is currently tested against following versions
Expand All @@ -43,3 +91,5 @@ Ruckig is written in C++17. It is currently tested against following versions
- Catch2 v2.13.3 (only for testing)
- Reflexxes v1.2.7 (only for testing)
- Pybind11 v2.6.0 (only for prototyping)

The current test suite validates over 170.000 trajectories based on random inputs.
7 changes: 3 additions & 4 deletions include/ruckig/ruckig.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,6 @@ class Step1 {
double p0, v0, a0;
double pf, vf, af;

Profile fastest;
std::vector<Profile> valid_profiles;

void add_profile(Profile profile, Profile::Limits limits, double jMax);
Expand Down Expand Up @@ -165,7 +164,7 @@ class Ruckig {

t_sync = possible_t_sync;
limiting_dof = std::ceil((i + 1.0) / 3) - 1;
// std::cout << limiting_dof << " " << i % 3 << " " << t_sync << std::endl;
// std::cout << "sync: " << limiting_dof << " " << i % 3 << " " << t_sync << std::endl;
switch (i % 3) {
case 0: {
profiles[limiting_dof] = blocks[limiting_dof].p_min;
Expand Down Expand Up @@ -265,7 +264,7 @@ class Ruckig {
Step2 step2 {t_profile, p0s[dof], v0s[dof], a0s[dof], input.target_position[dof], input.target_velocity[dof], input.target_acceleration[dof], input.max_velocity[dof], input.max_acceleration[dof], input.max_jerk[dof]};
bool found_time_synchronization = step2.get_profile(profiles[dof], input.max_velocity[dof], input.max_acceleration[dof], input.max_jerk[dof]);
if (!found_time_synchronization) {
throw std::runtime_error("[ruckig] error in step 2: " + input.to_string(dof) + " all: " + input.to_string());
throw std::runtime_error("[ruckig] error in step 2 in dof: " + std::to_string(dof) + " for t sync: " + std::to_string(tf) + " | " + input.to_string(dof) + " all: " + input.to_string());
}
}
}
Expand Down Expand Up @@ -297,7 +296,7 @@ class Ruckig {
auto stop = std::chrono::high_resolution_clock::now();
output.calculation_duration = std::chrono::duration_cast<std::chrono::nanoseconds>(stop - start).count() / 1000.0;

if (t > tf) {
if (t + delta_time > tf) {
return Result::Finished;
}

Expand Down
Loading

0 comments on commit 4d0e94e

Please sign in to comment.