Instantaneous Motion Generation for Robots and Machines.

Overview

Ruckig

Instantaneous Motion Generation for Robots and Machines.

CI Issues Releases MIT

Ruckig generates trajectories on-the-fly, allowing robots and machines to react instantaneously to sensor input. Ruckig calculates a trajectory to a target waypoint (with position, velocity, and acceleration) starting from any initial state limited by velocity, acceleration, and jerk constraints. Besides the target state, Ruckig allows to define intermediate positions for waypoint following. For state-to-state motions, Ruckig guarantees a time-optimal solution. With intermediate waypoints, Ruckig calculates the path and its time parametrization jointly, resulting in significantly faster trajectories compared to traditional methods.

More information can be found at ruckig.com and in the corresponding paper Jerk-limited Real-time Trajectory Generation with Arbitrary Target States, accepted for the Robotics: Science and Systems (RSS), 2021 conference.

Installation

Ruckig has no dependencies (except for testing). To build Ruckig using CMake, just run

mkdir -p build
cd build
cmake -DCMAKE_BUILD_TYPE=Release ..
make

To install Ruckig in a system-wide directory, use (sudo) make install. An example of using Ruckig in your CMake project is given by examples/CMakeLists.txt. However, you can also include Ruckig as a directory within your project and call add_subdirectory(ruckig) in your parent CMakeLists.txt.

Ruckig is also available as a Python module, in particular for development or debugging purposes. The Ruckig Community Version can be installed from PyPI via

pip install ruckig

When using CMake, the Python module can be built using the BUILD_PYTHON_MODULE flag. If you're only interested in the Python module (and not in the C++ library), you can build and install Ruckig via pip install ..

Tutorial

Furthermore, we will explain the basics to get started with online generated trajectories within your application. There is also a collection of examples that guide you through the most important features of Ruckig. A time-optimal trajectory for a single degree of freedom is shown in the figure below. We also added plots for the resulting trajectories of all examples. Let's get started!

Trajectory Profile

Waypoint-based Trajectory Generation

Ruckig provides three main interface classes: the Ruckig, the InputParameter, and the OutputParameter class.

First, you'll need to create a Ruckig instance with the number of DoFs as a template parameter, and the control cycle (e.g. in seconds) in the constructor.

Ruckig<6> ruckig {0.001}; // Number DoFs; control cycle in [s]

The input type has 3 blocks of data: the current state, the target state and the corresponding kinematic limits.

InputParameter<6> input; // Number DoFs
input.current_position = {0.2, ...};
input.current_velocity = {0.1, ...};
input.current_acceleration = {0.1, ...};
input.target_position = {0.5, ...};
input.target_velocity = {-0.1, ...};
input.target_acceleration = {0.2, ...};
input.max_velocity = {0.4, ...};
input.max_acceleration = {1.0, ...};
input.max_jerk = {4.0, ...};

OutputParameter<6> output; // Number DoFs

Given all input and output resources, we can iterate over the trajectory at each discrete time step. For most applications, this loop must run within a real-time thread and controls the actual hardware.

while (ruckig.update(input, output) == Result::Working) {
  // Make use of the new state here!
  // e.g. robot->setJointPositions(output.new_position);

  output.pass_to_input(input); // Don't forget this!
}

Within the control loop, you need to update the current state of the input parameter according to the calculated trajectory. Therefore, the pass_to_input method copies the new kinematic state of the output to the current kinematic state of the input parameter. If (in the next step) the current state is not the expected, pre-calculated trajectory, Ruckig will calculate a new trajectory based on the novel input. When the trajectory has reached the target state, the update function will return Result::Finished.

Intermediate Waypoints

The Ruckig Community Version now supports intermediate waypoints via a remote API. Make sure to include -DBUILD_ONLINE_CLIENT=ON as a CMake flag when compiling - the PyPI Python version should bring that out of the box. To allocate the necessary memory for a variable number of waypoints beforehand, we need to pass the maximum number of waypoints to Ruckig via

Ruckig<6> otg {0.001, 8};
InputParameter<6> input {8};
OutputParameter<6> output {8};

The InputParameter class takes the number of waypoints as an optional input, however usually you will fill in the values (and therefore reserve its memory) yourself. Then you're ready to set intermediate via points by

input.intermediate_positions = {
  {0.2, ...},
  {0.8, ...},
};

As soon as at least one intermediate positions is given, the Ruckig Community Version switches to the mentioned (of course, non real-time capable) remote API. If you require real-time calculation on your own hardware, we refer to the Ruckig Pro Version.

When using intermediate positions, both the underlying motion planning problem as well as its calculation changes significantly. In particular, there are some fundamental limitations for jerk-limited online trajectory generation regarding the usage of waypoints. Please find more information about these limitations here, and in general we recommend to use

input.intermediate_positions = otg.filter_intermediate_positions(input.intermediate_positions, {0.1, ...});

to filter waypoints according to a (high) threshold distance. Setting interrupt_calculation_duration makes sure to be real-time capable by refining the solution in the next control invocation. Note that this is a soft interruption of the calculation. Currently, no minimum or discrete durations are supported when using intermediate positions.

Input Parameter

To go into more detail, the InputParameter type has following members:

using Vector = std::array<double, DOFs>; // By default

Vector current_position;
Vector current_velocity; // Initialized to zero
Vector current_acceleration; // Initialized to zero

std::vector
    intermediate_positions; 
   // (only in Pro Version)

Vector target_position;
Vector target_velocity; 
   // Initialized to zero
Vector target_acceleration; 
   // Initialized to zero

Vector max_velocity;
Vector max_acceleration;
Vector max_jerk;

std::optional
   
     min_velocity; 
    // If not given, the negative maximum velocity will be used.
std::optional
    
      min_acceleration; 
     // If not given, the negative maximum acceleration will be used.

std::optional
     
       min_position; 
      // (only in Pro Version)
std::optional
      
        max_position; 
       // (only in Pro Version)

std::array<
       bool, DOFs> enabled; 
       // Initialized to true
std::optional<
       double> minimum_duration;
std::optional<
       double> interrupt_calculation_duration; 
       // [µs], (only in Pro Version)

ControlInterface control_interface; 
       // The default position interface controls the full kinematic state.
Synchronization synchronization; 
       // Synchronization behavior of multiple DoFs
DurationDiscretization duration_discretization; 
       // Whether the duration should be a discrete multiple of the control cycle (off by default)

std::optional
       
        
         > per_dof_control_interface; 
         // Sets the control interface for each DoF individually, overwrites global control_interface std::optional
         
          
           > per_dof_synchronization; 
           // Sets the synchronization for each DoF individually, overwrites global synchronization
          
         
        
       
      
     
    
   
  

On top of the current state, target state, and constraints, Ruckig allows for a few more advanced settings:

  • A minimum velocity and acceleration can be specified - these should be a negative number. If they are not given, the negative maximum velocity or acceleration will be used (similar to the jerk limit). For example, this might be useful in human robot collaboration settings with a different velocity limit towards a human. Or, when switching between different moving coordinate frames like picking from a conveyer belt.
  • You can overwrite the global kinematic limits to specify limits for each section between two waypoints separately by using e.g. per_section_max_velocity.
  • If a DoF is not enabled, it will be ignored in the calculation. Ruckig will output a trajectory with constant acceleration for those DoFs.
  • A minimum duration can be optionally given. Note that Ruckig can not guarantee an exact, but only a minimum duration of the trajectory.
  • The control interface (position or velocity control) can be switched easily. For example, a stop trajectory or visual servoing can be easily implemented with the velocity interface.
  • Different synchronization behaviors (i.a. phase, time, or no synchonization) are implemented. Phase synchronization results in straight-line motions.
  • The trajectory duration might be constrained to a multiple of the control cycle. This way, the exact state can be reached at a control loop execution.

We refer to the API documentation of the enumerations within the ruckig namespace for all available options.

Input Validation

To check that Ruckig is able to generate a trajectory before the actual calculation step,

ruckig.validate_input(input, check_current_state_within_limits=false, check_target_state_within_limits=true);
// returns boolean

returns false if an input is not valid. The two boolean arguments check that the current or target state are within the limits. The check includes a typical catch of jerk-limited trajectory generation: When the current state is at maximal velocity, any positive acceleration will inevitable lead to a velocity violation at a future timestep. In general, this condition is fulfilled when

Abs(acceleration) <= Sqrt(2 * max_jerk * (max_velocity - Abs(velocity))).

If both arguments are set to true, the calculated trajectory is guaranteed to be within the kinematic limits throughout its duration. Also, note that there are range constraints of the input due to numerical reasons, see below for more details.

Result Type

The update function of the Ruckig class returns a Result type that indicates the current state of the algorithm. This can either be working, finished if the trajectory has finished, or an error type if something went wrong during calculation. The result type can be compared as a standard integer.

State Error Code
Working 0
Finished 1
Error -1
ErrorInvalidInput -100
ErrorTrajectoryDuration -101
ErrorPositionalLimits -102
ErrorExecutionTimeCalculation -110
ErrorSynchronizationCalculation -111

Output Parameter

The output class includes the new kinematic state and the overall trajectory.

Vector new_position;
Vector new_velocity;
Vector new_acceleration;

Trajectory trajectory; // The current trajectory
double time; // The current, auto-incremented time. Reset to 0 at a new calculation.

size_t new_section; // Index of the section between two (possibly filtered) intermediate positions.
bool did_section_change; // Was a new section reached in the last cycle?

bool new_calculation; // Whether a new calculation was performed in the last cycle
bool was_calculation_interrupted; // Was the trajectory calculation interrupted? (only in Pro Version)
double calculation_duration; // Duration of the calculation in the last cycle [µs]

Moreover, the trajectory class has a range of useful parameters and methods.

double duration; // Duration of the trajectory
std::array<double, DOFs> independent_min_durations; // Time-optimal profile for each independent DoF

<...> at_time(double time); // Get the kinematic state of the trajectory at a given time
<...> get_position_extrema(); // Returns information about the position extrema and their times

Again, we refer to the API documentation for the exact signatures.

Offline Calculation

Ruckig also supports an offline approach for calculating a trajectory:

result = ruckig.calculate(input, trajectory);

When only using this method, the Ruckig constructor does not need a control cycle as an argument.

Dynamic Number of Degrees of Freedom

So far, we have told Ruckig the number of DoFs as a template parameter. If you don't know the number of DoFs at compile-time, you can set the template parameter to DynamicDOFs and pass the DoFs to the constructor:

Ruckig
    otg {
   6, 
   0.001};
InputParameter
   
     input {
    6};
OutputParameter
    
      output {
     6};
    
   
  

However, we recommend to keep the template parameter when possible: First, it has a performance benefit of a few percent. Second, it is convenient for real-time programming due to its easier handling of memory allocations. When using dynamic degrees of freedom, make sure to allocate the memory of all vectors beforehand.

Tests and Numerical Stability

The current test suite validates over 5.000.000.000 random trajectories. The numerical exactness is tested for the final position and final velocity to be within 1e-8, for the final acceleration to be within 1e-10, and for the velocity, acceleration and jerk limit to be within of a numerical error of 1e-12. These are absolute values - we suggest to scale your input so that these correspond to your required precision of the system. For example, for most real-world systems we suggest to use input values in [m] (instead of e.g. [mm]), as 1e-8m is sufficient precise for practical trajectory generation. Furthermore, all kinematic limits should be below 1e12. The maximal supported trajectory duration is 7e3, which again should suffice for most applications seeking for time-optimality. Note that Ruckig will also output values outside of this range, there is however no guarantee for correctness.

Benchmark

We find that Ruckig is more than twice as fast as Reflexxes Type IV for state-to-state motions and well-suited for control cycles as low as 250 microseconds. The Ruckig Community Version is in general a more powerful and open-source alternative to the Reflexxes Type IV library. In fact, Ruckig is the first Type V trajectory generator for arbitrary target states and even supports directional velocity and acceleration limits, while also being faster on top.

Benchmark

For trajectories with intermediate waypoints, we compare Ruckig to Toppra, a state-of-the-art library for robotic motion planning. Ruckig is able to improve the trajectory duration on average by around 10%, as the path planning and time parametrization are calculated jointly. Moreover, Ruckig is real-time capable and supports jerk-constraints.

Benchmark

Development

Ruckig is written in C++17. It is continuously tested on ubuntu-latest, macos-latest, and windows-latest against following versions

  • Doctest v2.4 (only for testing)
  • Pybind11 v2.6 (only for python wrapper)

If you still need to use C++11, you can patch the Ruckig Community Version by calling sh scripts/patch-c++11.sh. Note that this will result in a performance drop of a few percent. Moreover, the Python module is not supported.

Used By

  • CoppeliaSim in their upcoming release.
  • MoveIt 2 for trajectory smoothing.
  • Struckig, a port of Ruckig to Restructered Text for usage on PLCs.
  • Frankx for controlling the Franka Emika robot arm.
  • and others!

Citation

@article{berscheid2021jerk,
  title={Jerk-limited Real-time Trajectory Generation with Arbitrary Target States},
  author={Berscheid, Lars and Kr{\"o}ger, Torsten},
  journal={Robotics: Science and Systems XVII},
  year={2021}
}
Comments
  • pip install fails on Windows

    pip install fails on Windows

    Hey folks,

    i am trying to install the python package in my Windows Terminal. When running pip3 install ruckig, the following log occurs:

    Collecting ruckig
      Using cached ruckig-0.3.0.tar.gz (7.5 kB)
    Using legacy 'setup.py install' for ruckig, since package 'wheel' is not installed.
    Installing collected packages: ruckig
        Running setup.py install for ruckig ... error
        ERROR: Command errored out with exit status 1:
         command: 'C:\Users\xxx\AppData\Local\Microsoft\WindowsApps\PythonSoftwareFoundation.Python.3.9_qbz5n2kfra8p0\python.exe' -u -c 'import io, os, sys, setuptools, tokenize; sys.argv[0] = '"'"'C:\\Users\\xxx\\AppData\\Local\\Temp\\pip-install-yl3t984s\\ruckig_dfe9442aa6d744e48538d343aaff7e3c\\setup.py'"'"'; __file__='"'"'C:\\Users\\xxx\\AppData\\Local\\Temp\\pip-install-yl3t984s\\ruckig_dfe9442aa6d744e48538d343aaff7e3c\\setup.py'"'"';f = getattr(tokenize, '"'"'open'"'"', open)(__file__) if os.path.exists(__file__) else io.StringIO('"'"'from setuptools import setup; setup()'"'"');code = f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, __file__, '"'"'exec'"'"'))' install --record 'C:\Users\xxx\AppData\Local\Temp\pip-record-78ac38vs\install-record.txt' --single-version-externally-managed --user --prefix= --compile --install-headers 'C:\Users\xxx\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.9_qbz5n2kfra8p0\LocalCache\local-packages\Python39\Include\ruckig'
             cwd: C:\Users\xxx\AppData\Local\Temp\pip-install-yl3t984s\ruckig_dfe9442aa6d744e48538d343aaff7e3c\
        Complete output (38 lines):
        running install
        running build
        running build_ext
        CMake Error: The source directory "C:/Users/xxx/AppData/Local/Temp/pip-install-yl3t984s/ruckig_dfe9442aa6d744e48538d343aaff7e3c" does not appear to contain CMakeLists.txt.
        Specify --help for usage, or press the help button on the CMake GUI.
        Traceback (most recent call last):
          File "<string>", line 1, in <module>
          File "C:\Users\xxx\AppData\Local\Temp\pip-install-yl3t984s\ruckig_dfe9442aa6d744e48538d343aaff7e3c\setup.py", line 65, in <module>
            setup(
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\site-packages\setuptools\__init__.py", line 153, in setup
            return distutils.core.setup(**attrs)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\core.py", line 148, in setup
            dist.run_commands()
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\dist.py", line 966, in run_commands
            self.run_command(cmd)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\dist.py", line 985, in run_command
            cmd_obj.run()
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\site-packages\setuptools\command\install.py", line 61, in run
            return orig.install.run(self)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\command\install.py", line 546, in run
            self.run_command('build')
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\cmd.py", line 313, in run_command
            self.distribution.run_command(command)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\dist.py", line 985, in run_command
            cmd_obj.run()
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\command\build.py", line 135, in run
            self.run_command(cmd_name)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\cmd.py", line 313, in run_command
            self.distribution.run_command(command)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\distutils\dist.py", line 985, in run_command
            cmd_obj.run()
          File "C:\Users\xxx\AppData\Local\Temp\pip-install-yl3t984s\ruckig_dfe9442aa6d744e48538d343aaff7e3c\setup.py", line 36, in run
            self.build_extension(ext)
          File "C:\Users\xxx\AppData\Local\Temp\pip-install-yl3t984s\ruckig_dfe9442aa6d744e48538d343aaff7e3c\setup.py", line 61, in build_extension
            subprocess.check_call(['cmake', ext.sourcedir] + cmake_args, cwd=self.build_temp)
          File "C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.9_3.9.1520.0_x64__qbz5n2kfra8p0\lib\subprocess.py", line 373, in check_call
            raise CalledProcessError(retcode, cmd)
        subprocess.CalledProcessError: Command '['cmake', 'C:\\Users\\xxx\\AppData\\Local\\Temp\\pip-install-yl3t984s\\ruckig_dfe9442aa6d744e48538d343aaff7e3c', '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY=C:\\Users\\xxx\\AppData\\Local\\Temp\\pip-install-yl3t984s\\ruckig_dfe9442aa6d744e48538d343aaff7e3c\\build\\lib.win-amd64-3.9\\', '-DPYTHON_EXECUTABLE=C:\\Users\\xxx\\AppData\\Local\\Microsoft\\WindowsApps\\PythonSoftwareFoundation.Python.3.9_qbz5n2kfra8p0\\python.exe', '-DEXAMPLE_VERSION_INFO=0.3.0', '-DCMAKE_BUILD_TYPE=Release', '-DBUILD_PYTHON_MODULE=ON', '-DBUILD_SHARED_LIBS=OFF', '-DCMAKE_POSITION_INDEPENDENT_CODE=ON']' returned non-zero exit status 1.
        ----------------------------------------
    ERROR: Command errored out with exit status 1: 'C:\Users\xxx\AppData\Local\Microsoft\WindowsApps\PythonSoftwareFoundation.Python.3.9_qbz5n2kfra8p0\python.exe' -u -c 'import io, os, sys, setuptools, tokenize; sys.argv[0] = '"'"'C:\\Users\\xxx\\AppData\\Local\\Temp\\pip-install-yl3t984s\\ruckig_dfe9442aa6d744e48538d343aaff7e3c\\setup.py'"'"'; __file__='"'"'C:\\Users\\xxx\\AppData\\Local\\Temp\\pip-install-yl3t984s\\ruckig_dfe9442aa6d744e48538d343aaff7e3c\\setup.py'"'"';f = getattr(tokenize, '"'"'open'"'"', open)(__file__) if os.path.exists(__file__) else io.StringIO('"'"'from setuptools import setup; setup()'"'"');code = f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, __file__, '"'"'exec'"'"'))' install --record 'C:\Users\xxx\AppData\Local\Temp\pip-record-78ac38vs\install-record.txt' --single-version-externally-managed --user --prefix= --compile --install-headers 'C:\Users\xxx\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.9_qbz5n2kfra8p0\LocalCache\local-packages\Python39\Include\ruckig' Check the logs for full command output.
    

    I previously ran pip3 install cmake because it was complaining that there was no cmake.

    Thanks for your help!

    Edit just checked: same behaviour in my Debian WSL

    bug 
    opened by mdhom 20
  • Add a method to reset the Ruckig object with new `DOF` and `delta_t`

    Add a method to reset the Ruckig object with new `DOF` and `delta_t`

    I'm trying to do something like this with every control loop iteration because the period of my control loop might change:

    smoother = ruckig::Ruckig<ruckig::DynamicDOFs>(new_DOF, new_delta_t));

    It would be nice if there were something like a reset(size_t new_DOFs, double new_delta_t) method so I didn't have to re-initialize like that:

    smoother.reset(new_DOF, new_delta_t);

    Here's an explanation on why that's inefficient: https://stackoverflow.com/a/2530889/3499467

    enhancement 
    opened by AndyZe 13
  • Numerical issue on plc

    Numerical issue on plc

    Hi Pantor,

    i had an issue with some trajectories with higher jerks >100000. (If you need the parameters, tell me) => ruckig::Result::ErrorExecutionTimeCalculation

    But only on the PLC with GCC 6.3.0... In Visual Studio everything works fine...

    This issue appeared in "PositionStep1::time_vel". The "profile.check" caused this fault in the marked line on the following picture.

    grafik

    I changed the value to 1e-8, after that it's working fine. What does ist mean "This is not really needed..."?

    Is it ok to change this value?

    thx

    Daniel

    opened by Danielxyz123 10
  • Understanding ErrorExecutionTimeCalculation (-110) errors

    Understanding ErrorExecutionTimeCalculation (-110) errors

    I'm using Ruckig in a 6-DOF visual servoing application, updating input.target_position at a rate similar to the control cycle. I find that often when setpoints (updates to target_position) are quite close to each other, Ruckig will return a -110 status. Can you help me understand what causes this error? Are there any workarounds you'd suggest? Thank you.

    opened by isherman 10
  • Segmentation fault in VelocityStep1::addProfile

    Segmentation fault in VelocityStep1::addProfile

    Hello @pantor

    I'm having segfaults (see backtrace below) on master: image

    It might be related to the changes your made in 22cbb5da0eb9bd4017596ec3ba8197353d4c021a as I don't recall having these crashes before.

    As always, thanks for your help !

    bug 
    opened by fricher 9
  • Specific test case yields ErrorExecutionTimeCalculation

    Specific test case yields ErrorExecutionTimeCalculation

    I'm trying to bring Ruckig into MoveIt but have had some trouble. Usually the first waypoint fails. I'll give a specific test case here.

    The MoveIt PR is here and the Ruckig-related code is here.

    A spreadsheet of the parameters that cause this failure is attached. Let me know if any more info is needed to reproduce the issue.

    The failure code is -110 (ErrorExecutionTimeCalculation). Currently using the default Time synchronization (have also tried None) and Interface::Position (have also tried Velocity).

    I've tried to manually check the input parameters and they seem fine to me ¯_(ツ)_/¯

    On the bright side, I have seen a few successful calculations when the target vel/accel are very low.

    ruckig_issue.ods

    opened by AndyZe 9
  • Initial conditions with  brake phase violated for step1

    Initial conditions with brake phase violated for step1

    Dear Pantor,

    following issue. In our tests of ruckig we often see conditions where the final state of the initial brake phase does not satisfy the conditions on velocity. Here is a little simplified example for this behavior (used version for the results was commit-id 13c5e7f14ade734fd049355f0c965482b5031edc) :

    ` input.current_position = { 18879.4705012938102 }; input.current_velocity = { 110.229330653798357 }; input.current_acceleration = { 470.272491202182493 };

    input.target_position = { -18879.4705012938102 };
    input.target_velocity = { 0.035 };
    input.target_acceleration = { 0.0 };
    
    input.max_velocity = { 0.035 };
    input.max_acceleration = { 1014.76263156153846 };
    input.max_jerk = { 20000.0 };
    

    `

    If I debug into this I can see that the initial state of the remaining OTG fot step 1 is

      | Name | Wert | Typ -- | -- | -- | -- ▶ | p.brake | {duration=0.13762231604309033 t={ size=2 } j={ size=2 } ...} | ruckig::BrakeProfile   | p.p[0] | 18891.253748155214 | double   | p.v[0] | 25.708579960392669 | double   | p.a[0] | -1014.7626315610985 | double   | inp.max_velocity[dof] | 0.035000000000000003 | double   | inp.max_acceleration[dof] | 1014.7626315615385 | double   | inp.max_jerk[dof] | 20000.000000000000 | double

    Clearly the initial velocity violates the maximal velocity. As far as I understand your theory the reason for the initial brake phase was to get a safe kinematic state. Hence my questions:

    1. What maybe negative effects can we expect when the initial conditions for step 1 are violated?
    2. How important is it for the Step1 and later on Step 2 conditions satisfy all prerequisites on velocity and acceleration?
    3. How trustworthy is the OTG solution if the initial conditions are not met? Is it still time optimal for example.
    4. How exact should the brake phase hit the bounds on velocity/acceleration? In the above example it missed the velocity by far.

    I have to admit I mainly tested this on my fork including the prototype for the final acceleration phase where we had issues with accuracy in

    bool check(double jf, double vMax, double vMin, double aMax, double aMin)

    This method deliberately misses out on testing the initial state and only checks whether the target state and some intermediate states fulfill the conditions on accuracy and velocity resp. acceleration. Here we tested with special test cases where final acceleration phase must be symmetric to the initial brake phase by simply setting:

    for (int idx = 0; idx < DOFs; ++idx) { input.current_position[idx] = -input.target_position[idx]; input.current_velocity[idx] = input.target_velocity[idx]; input.current_acceleration[idx] = -input.target_acceleration[idx]; } In these cases we got a lot of errors where our adapted ruckig was not able to find valid solutions because some conditions inside the check-method failed and hence either ErrorExecutionTimeCalculation or ErrorSynchronizationCalculation was raised . Therefore for tests I integrated backward from the desired final state inside the check method and additionally tested this results on the side of the initial brake phase which brought us to the above conclusion that the OTG solution after the end of the initial brake phase is not yet satisfying the conditions on velocity as seen above and if tested would also raise the same errors.

    Btw. I have seen you started adding first commits with the final acceleration phase. Can we expect this feature to be officially supported with the next release 0.6.0?

    I am sorry this got quite lengthy.

    As always keep up your great work!

    Thanks Fubini

    opened by Fubini2 8
  • Odd trajectory output when used for path following

    Odd trajectory output when used for path following

    I've written a path following algorithm around Ruckig to control a robot through a number of waypoints (position, velocity, acceleration) and Ruckig will occasionally give me a suboptimal trajectory that oscillates about the goal position before continuing on course.

    Some background: I load Ruckig with the robots initial position (say 0,0 for a 2 DOF), then the target position is loaded with the first waypoint. I iterate ruckig with input=output and target constant until ruckig returns Finished, then I load the next waypoint (input is equal to the last waypoint) and keep on trucking. I've brought plots (position, velocity, acceleration): vscale-0 8-axis-1 vscale-0 8-axis-2

    The second tracks nicely, however the first axis seems to create a sinusoidal trajectory. One thing I've noticed is that the undesirable response comes when I set the planner to use significant amounts of the robot's velocity limit (0.8 in the above example). The same trajectory with a velocity scaling of 0.61 generates a nice trajectory, as seen in the following plots: vscale-0 61-axis-1 vscale-0 61-axis-2

    What can I do to avoid this response? Am I using Ruckig incorrectly, or perhaps is there a bug that I can work around or fix?

    I have uploaded the code used to create these trajectories to my area here on github: https://github.com/BryanStuurman/ruckig_work/blob/main/trajectory.py

    opened by BryanStuurman 8
  • How to check position extrema with new input parameters while ruckig is working

    How to check position extrema with new input parameters while ruckig is working

    Hi Pantor,

    i want to check the position extrema with new input parameters, while ruckig ist working and velocity & acceleration is not zero. If there is a position limit fault, ruckig should ignore the new parameters. How can i handle that? To get the limits, we have to call

    "otg.update(input, output);" and then "output.trajectory.get_position_extrema()" i think.

    Then ruckig is working and i cant't abort that.

    opened by Danielxyz123 8
  • ghost command generated by ruckig

    ghost command generated by ruckig

    Hi,

    I'm using ruckig to control a single joint. However, I have observed that ruckig generates "ghost command" for other joints at the same time (theoretically, these joints should not move at all, since the input_parameter.current_position = input_parameter.target_position). Any reason as to why?

    Thank you!

    question 
    opened by jessicaleu24 7
  • Non-deterministic outputs based on scope of Ruckig data structure

    Non-deterministic outputs based on scope of Ruckig data structure

    I was testing out Ruckig (nice package BTW), and noticed that I get different results if I recreate the Ruckig data structure for each new problem to solve rather than overwriting the input/target positions, velocities, and accelerations. I'm sorry I can't be more help than that right now It's late here, and I wanted to file this before stopping for the day. I'm sure you could reproduce by running some predetermined set of inputs/outputs in a loop with the Ruckig data structure inside/outside of the loop.

    For me, Its as simple as if the for loop below is at the bottom of the snipp or at the top, where I get different results on repeated solves.

       Ruckig<6> otg {0.001};
       InputParameter<6> input;
       OutputParameter<6> output;
       
       // Set input parameters
       input.max_velocity = maxVelocities;
       input.max_acceleration = maxAccelerations;
       input.max_jerk = max_joint_jerk_;
    
       for (std::size_t ii=0; ii < data.size(); ++ii) {
    
    opened by pbeeson 7
  • ErrorExecutionTimeCalculation in a very specific case

    ErrorExecutionTimeCalculation in a very specific case

    The ruckig.update() will return ErrorExecutionTimeCalculation in the codes below The strange thing is that if I change current_position very little, instead of 0.0049921875, like 0.0049921876 or 0.0049921874, the planning is ok... the version is v0.8.4

     constexpr int DOF{1};
      Ruckig<DOF> ruckig {0.001}; // Number DoFs; control cycle in [s]
      InputParameter<DOF> inp; // Number DoFs
      inp.current_position = {0.0049921875};
      inp.current_velocity = {0};
      inp.current_acceleration = {0};
      inp.target_position = {0.005};
      inp.target_velocity = { 0};
      inp.target_acceleration = { 0};
      inp.max_velocity = { 0.1};
      inp.max_acceleration = { 2.5};
      inp.max_jerk = {2000};
    
      OutputParameter<DOF> out; // Number DoFs
      auto res = ruckig.update(inp, out);
      std::cout << res << std::endl; // res == ErrorExecutionTimeCalculation
    
    opened by old-ma 2
  • Suggestion: move Result codes to a new header file

    Suggestion: move Result codes to a new header file

    Whenever I have to look up the Ruckig result codes, it takes awhile to find them in input_parameter.hpp. It seems like they don't really belong there, so I'd suggest moving them to a new header file.

    enhancement 
    opened by AndyZe 0
  • New ROS release

    New ROS release

    Hi @pantor,

    Quite a few great features and fixes have been added to Ruckig since latest ROS release (v0.6.3). Would you mind running a new Ruckig bloom release for ROS?

    help wanted 
    opened by aseligmann-ipu 9
  • ErrorSynchronizationCalculation error

    ErrorSynchronizationCalculation error

    Hello @pantor , ruckig fails to compute a trajectory from these parameters:

    const double cycle_time = .004;
    
    ruckig::Ruckig<6,true> ruckig(cycle_time);
    ruckig::InputParameter<6> inp;
    ruckig::Trajectory<6> traj;
    
    inp.control_interface = ruckig::ControlInterface::Position;
    inp.synchronization = ruckig::Synchronization::Phase;
    inp.duration_discretization = ruckig::DurationDiscretization::Continuous;
    inp.current_position = {1.635923973038584, -0.02664577603159074, 1.398772409994243, 0.7204359129215889, 0.7531949879258638, -0.3527181789404736};
    inp.current_velocity = {0.5997002460539949, 0.657823987334049, 0.6544488698370342, 0.6534667437575569, 0.6578239873340388, 0.6578239873340486};
    inp.current_acceleration = {-2.111156774102785, -4.363323129985824, -3.853477374887802, -4.32029086362776, -4.363323129985824, -4.363323129985824};
    inp.target_position = {1.6863294690542, 0.02475975543627795, 1.450144052898067, 0.7716208457168268, 0.8046005193937291, -0.301312647472602};
    std::ranges::fill(inp.target_velocity, 0);
    std::ranges::fill(inp.target_acceleration, 0);
    inp.target_velocity = {0, 0, 0, 0, 0, 0};
    inp.max_velocity = {5.235987755982989, 3.926990816987241, 3.926990816987241, 6.649704450098396, 5.427973973702365, 8.587019919812102};
    inp.max_acceleration = {4.363323129985824, 4.363323129985824, 4.363323129985824, 4.363323129985824, 4.363323129985824, 4.363323129985824};
    inp.max_jerk = {43.63323129985824, 43.63323129985824, 43.63323129985824, 43.63323129985824, 43.63323129985824, 43.63323129985824};
    
    auto result = ruckig.calculate(inp, traj);
    

    The result:

    [ruckig] error in step 2 in dof: 3 for t sync: 0.200762 input:
    inp.current_position = [1.635923973038584, -0.02664577603159074, 1.398772409994243, 0.7204359129215889, 0.7531949879258638, -0.3527181789404736]
    inp.current_velocity = [0.5997002460539949, 0.657823987334049, 0.6544488698370342, 0.6534667437575569, 0.6578239873340388, 0.6578239873340486]
    inp.current_acceleration = [-2.111156774102785, -4.363323129985824, -3.853477374887802, -4.32029086362776, -4.363323129985824, -4.363323129985824]
    inp.target_position = [1.6863294690542, 0.02475975543627795, 1.450144052898067, 0.7716208457168268, 0.8046005193937291, -0.301312647472602]
    inp.target_velocity = [0, 0, 0, 0, 0, 0]
    inp.target_acceleration = [0, 0, 0, 0, 0, 0]
    inp.max_velocity = [5.235987755982989, 3.926990816987241, 3.926990816987241, 6.649704450098396, 5.427973973702365, 8.587019919812102]
    inp.max_acceleration = [4.363323129985824, 4.363323129985824, 4.363323129985824, 4.363323129985824, 4.363323129985824, 4.363323129985824]
    inp.max_jerk = [43.63323129985824, 43.63323129985824, 43.63323129985824, 43.63323129985824, 43.63323129985824, 43.63323129985824]
    

    It seems to happen only when one or more dofs have an acceleration equal to their limit.

    Thanks for your help !

    bug 
    opened by fricher 0
  • Improvements of numerical stability

    Improvements of numerical stability

    Dear @pantor,

    we committed a new version https://github.com/Fubini2/ruckig/network to our fork including some numerical improvements we have been working on in our use case, see https://github.com/pantor/ruckig/issues/72 and https://github.com/pantor/ruckig/issues/71. These improvements enabled us to not only use your code with the addition of the final acceleration phase, but also allowed us to use the code without the need to scale inputs any more. Maybe you could think about adding those improvements to the main development line. So for now, let me add a few explanations on the main changes we did and the reasons why we did them. Feel free to ask any question about it:

    1. roots.hpp: For our use case the epsilons were much too high. We found out the main cases of your root solver works quite well, while the edge cases often failed due to numerical issues. By decreasing the epsilons we now almost always calculate the solution using the main case.
    2. brake.cpp: Adding or subtracting eps here on some values added some numerical uncertainty to otherwise perfectly fine values that hindered decision making on whether a solution is good or bad later on. So we reduced accuracy in the decision making process but not in the actual values that later on are used to integrate the solution.
    3. Some comparisons were numerically unstable so we added a "Unit in the last place (ULPS) https://en.wikipedia.org/wiki/Unit_in_the_last_place" based comparison method for these data (robust_*_check(...)).
    4. position.hpp: Having done the above alterations we have seen that sometimes a UDDU and a DUUD profile work because they are both inside the tolerance bounds which later on generated an error inside your code. So we added some code to specifically filter out one of those both case using the profileIsGreat method.

    Fubini2

    enhancement 
    opened by Fubini2 0
Releases(v0.8.4)
  • v0.8.4(Sep 13, 2022)

    This release includes two exciting new features: First, it extends phase synchronization for straight-line trajectories to the velocity control interface. Second, this release allows to use custom vector types (with support for Eigen types out of the box) for an easier interface to your code without any wrappers.

    ⚡ Features

    • Extends phase synchronization to the velocity control mode.
    • Introduces custom vector types that can be specified as a template template argument. More information can be found in the Readme section.
    • Built-in support for nlohmann/json based serialization of the trajectory class.
    • Adds a pyproject.toml file for easier setup of the Python module.

    🐛 Fixes

    • Fixes trajectory calculations when the current acceleration is on its limit due to an issue with the braking trajectory.
    • Removes -Werror as a default flag to let Ruckig build in case of compiler warnings.

    🥇 Sponsors

    Thanks to Fuzzy Logic Robotics for sponsoring this release!

    Source code(tar.gz)
    Source code(zip)
  • v0.7.1(Jul 10, 2022)

    With this release, Ruckig allows using a variable control rate!

    ⚡ Features

    • Makes delta_time non-constant.
    • Allows to reset Ruckig and therefore force a new trajectory computation (#132).

    🐛 Fixes

    • Improves the stability of the velocity control as well as the discrete duration mode (e.g. #116).
    • Fixes independent_min_duration in case of a brake trajectory (#128).
    • Fixes a rare issue where the first update does not calculate a trajectory (#115).
    • Fixes warnings for MSVC (e.g. #127, #133).
    Source code(tar.gz)
    Source code(zip)
  • v0.6.5(Mar 7, 2022)

    🐛 Fixes

    • Fixes a numerical instability in velocity control, in particular when calculating trajectories to a zero target state.
    • Fixes pip install for non-prebuild architectures.
    • Fixes an error when building the Online API flag (BUILD_ONLINE_CLIENT) with some C++17 compilers due to the nlohmann/json dependency.
    Source code(tar.gz)
    Source code(zip)
  • v0.6.3(Jan 22, 2022)

  • v0.6.0(Dec 7, 2021)

    This release brings trajectories with intermediate waypoints to the Community Version! Calculation is done on remote servers via this API, so this is only applicable for offline trajectory generation. Furthermore, this release...

    :zap: Features

    • Adds a method for filtering intermediate waypoints based on a threshold distance for each DoF. In general, Ruckig prefers as few waypoints as possible, so we recommend to filter the input with a threshold as high as possible.
    • Improves input validation. In particular, Ruckig is now able to guarantee the kinematic state to be below the constraints throughout the trajectory.

    :bug: Fixes

    • Fixes trajectories with zero duration.
    • Adds a stability improvement to Step 2 of the algorithm.
    Source code(tar.gz)
    Source code(zip)
  • v0.5.0(Nov 14, 2021)

    This release introduces the pass_to_input method of the OutputParameter class: We recommend to change the following usage in your code from

    while (ruckig.update(input, output) == Result::Working) {
      // Make use of the new state here!
    
      input.current_position = output.new_position;
      input.current_velocity = output.new_velocity;
      input.current_acceleration = output.new_acceleration;
    }
    

    to

    while (ruckig.update(input, output) == Result::Working) {
      // Make use of the new state here!
    
      output.pass_to_input(input);
    }
    

    While the old style works fine for now, it is now depreciated to support additional features coming in future releases. Moreover, this release includes:

    :zap: Features

    • Introduces the option to set the synchronization and control interface for each degree of freedom separately.
    • An overall performance improvement of around 15%.
    • Reduced the memory footprint of the Trajectory class by an order of magnitude.

    🐛 Fixes

    • Fixed a jump in the position output after a finished trajectory for disabled degrees of freedom.

    🔬 Misc

    • Added a to_string method for printing the OutputParameter class (#77).
    Source code(tar.gz)
    Source code(zip)
  • v0.4.0(Aug 23, 2021)

    :zap: Features

    • Ruckig now allows a dynamic number of DoFs with ruckig::DynamicDOFs. In particular, this allows the Python wrapper to be used with any number of DoF (#47).
    • Improved the performance for trajectory calculation by around 30%.
    • Added offline trajectory calculation without the need of a control cycle time.
    • Added the get_first_time_at_position method to calculate when a specific position is reached.

    :bug: Bug Fixes

    • Improved numeric stability, in particular for very long trajectories and very high limits.
    • Fixed min_velocity in phase synchronization.
    • Fixed several smaller bugs and compiler warnings.

    :robot: Tests

    • Added tests for secondary features like input validation, inverse position calculation, etc...
    Source code(tar.gz)
    Source code(zip)
  • v0.3.3(Jun 25, 2021)

  • v0.3.1(Jun 24, 2021)

    This release fixes two issues mostly regarding Windows. :bug:

    • Fixes an issue when building from the Python source package (#40)
    • Fixes the Python bindings using MSVC (#37)
    Source code(tar.gz)
    Source code(zip)
  • v0.3.0(Jun 16, 2021)

    This release primarily improves the numerical stability of Ruckig. In particular, we added tests (and fixed several issues) for difficult cases by stepping through time-optimal trajectories.

    :zap: Features

    • Added optional phase synchronization for straight-line trajectories (#13)

    :bug: Bug Fixes

    • Try to recalculate trajectory in the case of errors (#20)
    • Improved numeric stability for inputs with different order of magnitudes (#27)
    • Fixed a numeric bug for very small negative position differences (#30)
    • Fixes in the position extremum calculation (#33)
    • Fixes when calculating whether phase synchronization is possible (#32)
    • The Python wrapper for the at_time method now returns the new kinematic state (#34)
    • Fixed several compilation warnings and treat them as errors furthermore

    :robot: Tests

    • Add tests for stepping through calculated trajectories
    • Add tests for directional dependent velocity and acceleration constraints
    • Add tests for extremal position calculation
    Source code(tar.gz)
    Source code(zip)
  • v0.2.6(Mar 29, 2021)

  • v0.2(Feb 22, 2021)

    We made large steps towards a full-featured trajectory generator. This includes:

    ⚡ Features

    • Added velocity Interface for velocity-control.
    • Added setting for different time synchronization behaviors regarding multiple degrees of freedom.
    • Added optional minimum acceleration limit, similar to the minimum velocity limit.
    • Scaled tests to over 1.000.000.000 trajectories (100x improvement).
    • Improved performance and overtook Reflexxes Type IV in comparison.
    • Lot's of supplements and fixes for the Readme.
    • Moved tests to doctest for faster compilations.

    🐛 Fixes

    • Fixes real-time capability with own set container.
    • Fixes behavior after finishing the trajectory.
    • Now compiles without any warnings and errors on GCC and Clang.
    Source code(tar.gz)
    Source code(zip)
  • v0.1(Jan 25, 2021)

    First version with full support for target accelerations in multiple DoFs! 🎉

    • Added min velocity limit.
    • Added Doxygen-generated documentation and auto-publish via CI.
    • More tests. Now over 1.400.000 random multi-dof trajectories.
    • Added a benchmark for measuing the performance.
    • Lot's of code cleaning and optimizations.
    • Removed Eigen dependency.
    Source code(tar.gz)
    Source code(zip)
PaddleRobotics is an open-source algorithm library for robots based on Paddle, including open-source parts such as human-robot interaction, complex motion control, environment perception, SLAM positioning, and navigation.

简体中文 | English PaddleRobotics paddleRobotics是基于paddle的机器人开源算法库集,包括人机交互、复杂运动控制、环境感知、slam定位导航等开源算法部分。 人机交互 主动多模交互技术TFVT-HRI 主动多模交互技术是通过视觉、语音、触摸传感器等输入机器人

null 185 Dec 26, 2022
This repository contains the code for the paper "Hierarchical Motion Understanding via Motion Programs"

Hierarchical Motion Understanding via Motion Programs (CVPR 2021) This repository contains the official implementation of: Hierarchical Motion Underst

Sumith Kulal 40 Dec 5, 2022
Exploring Versatile Prior for Human Motion via Motion Frequency Guidance (3DV2021)

Exploring Versatile Prior for Human Motion via Motion Frequency Guidance This is the codebase for video-based human motion reconstruction in human-mot

Jiachen Xu 5 Jul 14, 2022
Official codebase for Legged Robots that Keep on Learning: Fine-Tuning Locomotion Policies in the Real World

Legged Robots that Keep on Learning Official codebase for Legged Robots that Keep on Learning: Fine-Tuning Locomotion Policies in the Real World, whic

Laura Smith 70 Dec 7, 2022
Manipulation OpenAI Gym environments to simulate robots at the STARS lab

Manipulator Learning This repository contains a set of manipulation environments that are compatible with OpenAI Gym and simulated in pybullet. In par

STARS Laboratory 5 Dec 8, 2022
Autonomous Robots Kalman Filters

Autonomous Robots Kalman Filters The Kalman Filter is an easy topic. However, ma

null 20 Jul 18, 2022
The personal repository of the work: *DanceNet3D: Music Based Dance Generation with Parametric Motion Transformer*.

DanceNet3D The personal repository of the work: DanceNet3D: Music Based Dance Generation with Parametric Motion Transformer. Dataset and Results Pleas

南嘉Nanga 36 Dec 21, 2022
Official Pytorch implementation of the paper "MotionCLIP: Exposing Human Motion Generation to CLIP Space"

MotionCLIP Official Pytorch implementation of the paper "MotionCLIP: Exposing Human Motion Generation to CLIP Space". Please visit our webpage for mor

Guy Tevet 173 Dec 26, 2022
Restricted Boltzmann Machines in Python.

How to Use First, initialize an RBM with the desired number of visible and hidden units. rbm = RBM(num_visible = 6, num_hidden = 2) Next, train the m

Edwin Chen 928 Dec 30, 2022
Probabilistic Gradient Boosting Machines

PGBM Probabilistic Gradient Boosting Machines (PGBM) is a probabilistic gradient boosting framework in Python based on PyTorch/Numba, developed by Air

Olivier Sprangers 112 Dec 28, 2022
Neural Turing Machines (NTM) - PyTorch Implementation

PyTorch Neural Turing Machine (NTM) PyTorch implementation of Neural Turing Machines (NTM). An NTM is a memory augumented neural network (attached to

Guy Zana 519 Dec 21, 2022
PyTorch implementation for the Neuro-Symbolic Sudoku Solver leveraging the power of Neural Logic Machines (NLM)

Neuro-Symbolic Sudoku Solver PyTorch implementation for the Neuro-Symbolic Sudoku Solver leveraging the power of Neural Logic Machines (NLM). Please n

Ashutosh Hathidara 60 Dec 10, 2022
Relaxed-machines - explorations in neuro-symbolic differentiable interpreters

Relaxed Machines Explorations in neuro-symbolic differentiable interpreters. Baby steps: inc_stop Libraries JAX Haiku Optax Resources Chapter 3 (∂4: A

Nada Amin 6 Feb 2, 2022
Source code for the GPT-2 story generation models in the EMNLP 2020 paper "STORIUM: A Dataset and Evaluation Platform for Human-in-the-Loop Story Generation"

Storium GPT-2 Models This is the official repository for the GPT-2 models described in the EMNLP 2020 paper [STORIUM: A Dataset and Evaluation Platfor

Nader Akoury 27 Dec 20, 2022
A weakly-supervised scene graph generation codebase. The implementation of our CVPR2021 paper ``Linguistic Structures as Weak Supervision for Visual Scene Graph Generation''

README.md shall be finished soon. WSSGG 0 Overview 1 Installation 1.1 Faster-RCNN 1.2 Language Parser 1.3 GloVe Embeddings 2 Settings 2.1 VG-GT-Graph

Keren Ye 35 Nov 20, 2022
Image-generation-baseline - MUGE Text To Image Generation Baseline

MUGE Text To Image Generation Baseline Requirements and Installation More detail

null 23 Oct 17, 2022
Object Depth via Motion and Detection Dataset

ODMD Dataset ODMD is the first dataset for learning Object Depth via Motion and Detection. ODMD training data are configurable and extensible, with ea

Brent Griffin 172 Dec 21, 2022
Synthesizing Long-Term 3D Human Motion and Interaction in 3D in CVPR2021

Long-term-Motion-in-3D-Scenes This is an implementation of the CVPR'21 paper "Synthesizing Long-Term 3D Human Motion and Interaction in 3D". Please ch

Jiashun Wang 76 Dec 13, 2022