Ruckig 0.15.0
Motion Generation for Robots and Machines
|
Output of the Ruckig algorithm. More...
#include <output_parameter.hpp>
Public Member Functions | |
template<size_t D = DOFs, typename std::enable_if<(D >=1), int >::type = 0> | |
OutputParameter () | |
template<size_t D = DOFs, typename std::enable_if<(D==0), int >::type = 0> | |
OutputParameter (size_t dofs) | |
template<size_t D = DOFs, typename std::enable_if<(D >=1), int >::type = 0> | |
OutputParameter (size_t max_number_of_waypoints) | |
template<size_t D = DOFs, typename std::enable_if<(D==0), int >::type = 0> | |
OutputParameter (size_t dofs, size_t max_number_of_waypoints) | |
template<size_t D = DOFs, typename std::enable_if<(D >=1), int >::type = 0> | |
OutputParameter (const MemoryRequirement &memory_requirement) | |
template<size_t D = DOFs, typename std::enable_if<(D==0), int >::type = 0> | |
OutputParameter (size_t dofs, const MemoryRequirement &memory_requirement) | |
void | pass_to_input (InputParameter< DOFs, CustomVector > &input) const |
Copies the new output state to the current state of the input. | |
std::string | to_string () const |
Get a string representation of the parameters. | |
Public Attributes | |
size_t | degrees_of_freedom |
Degrees of freedom. | |
Trajectory< DOFs, CustomVector > | trajectory |
Current trajectory. | |
CustomVector< double, DOFs > | new_position |
New position values at the given time. | |
CustomVector< double, DOFs > | new_velocity |
New velocity values at the given time. | |
CustomVector< double, DOFs > | new_acceleration |
New acceleration values at the given time. | |
CustomVector< double, DOFs > | new_jerk |
New jerk values at the given time. | |
double | time |
Current time on the trajectory. | |
size_t | new_section |
Index of the current section between two (possibly filtered) intermediate positions (only relevant in Ruckig Pro) | |
bool | did_section_change |
Was a new section reached in the last cycle? (only relevant in Ruckig Pro) | |
bool | new_calculation |
Was a new trajectory calculation performed in the last cycle? | |
bool | was_calculation_interrupted |
Was the trajectory calculation interrupted? (only in Ruckig Pro) | |
double | calculation_duration |
Computational duration of the last update call. | |
Output of the Ruckig algorithm.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
Copies the new output state to the current state of the input.
|
inline |
Get a string representation of the parameters.
double ruckig::OutputParameter< DOFs, CustomVector >::calculation_duration |
Computational duration of the last update call.
size_t ruckig::OutputParameter< DOFs, CustomVector >::degrees_of_freedom |
Degrees of freedom.
bool ruckig::OutputParameter< DOFs, CustomVector >::did_section_change |
Was a new section reached in the last cycle? (only relevant in Ruckig Pro)
CustomVector<double, DOFs> ruckig::OutputParameter< DOFs, CustomVector >::new_acceleration |
New acceleration values at the given time.
bool ruckig::OutputParameter< DOFs, CustomVector >::new_calculation |
Was a new trajectory calculation performed in the last cycle?
CustomVector<double, DOFs> ruckig::OutputParameter< DOFs, CustomVector >::new_jerk |
New jerk values at the given time.
CustomVector<double, DOFs> ruckig::OutputParameter< DOFs, CustomVector >::new_position |
New position values at the given time.
size_t ruckig::OutputParameter< DOFs, CustomVector >::new_section |
Index of the current section between two (possibly filtered) intermediate positions (only relevant in Ruckig Pro)
CustomVector<double, DOFs> ruckig::OutputParameter< DOFs, CustomVector >::new_velocity |
New velocity values at the given time.
double ruckig::OutputParameter< DOFs, CustomVector >::time |
Current time on the trajectory.
This refers to the time along the trajectory, not necessarily the passed clock time. This might be different when using the speed parameter of the Ruckig class.
Trajectory<DOFs, CustomVector> ruckig::OutputParameter< DOFs, CustomVector >::trajectory |
Current trajectory.
bool ruckig::OutputParameter< DOFs, CustomVector >::was_calculation_interrupted |
Was the trajectory calculation interrupted? (only in Ruckig Pro)