|
kinematics-dynamics
|
#include <KdlTreeSolver_ParamsParser.h>
Classes | |
| struct | parser_version_type |
Public Attributes | |
| const std::string | m_device_classname = {"KdlTreeSolver"} |
| const std::string | m_device_name = {"KdlTreeSolver"} |
| bool | m_parser_is_strict = false |
| const parser_version_type | m_parser_version = {} |
| const std::string | m_kinematics_defaultValue = {""} |
| const std::string | m_gravity_defaultValue = {"(0.0 0.0 9.81)"} |
| const std::string | m_ikPos_defaultValue = {"nrjl"} |
| const std::string | m_epsPos_defaultValue = {"1e-5"} |
| const std::string | m_maxIterPos_defaultValue = {"1000"} |
| const std::string | m_vTranslMax_defaultValue = {"1.0"} |
| const std::string | m_vRotMax_defaultValue = {"50.0"} |
| const std::string | m_lambda_defaultValue = {"0.01"} |
| const std::string | m_weightsJS_defaultValue = {""} |
| const std::string | m_weightsTS_defaultValue = {""} |
| const std::string | m_mins_defaultValue = {""} |
| const std::string | m_maxs_defaultValue = {""} |
| const std::string | m_maxvels_defaultValue = {""} |
| std::string | m_kinematics = {} |
| std::vector< double > | m_gravity = { } |
| std::string | m_ikPos = {"nrjl"} |
| double | m_epsPos = {1e-5} |
| int | m_maxIterPos = {1000} |
| double | m_vTranslMax = {1.0} |
| double | m_vRotMax = {50.0} |
| double | m_lambda = {0.01} |
| std::vector< double > | m_weightsJS = {} |
| std::vector< double > | m_weightsTS = {} |
| std::vector< double > | m_mins = {} |
| std::vector< double > | m_maxs = {} |
| std::vector< double > | m_maxvels = {} |
This class is the parameters parser for class KdlTreeSolver.
These are the used parameters:
| Group name | Parameter name | Type | Units | Default Value | Required | Description | Notes |
|---|---|---|---|---|---|---|---|
| - | kinematics | string | - | - | 0 | path to file with description of robot kinematics | - |
| - | gravity | vector<double> | m/s^2 | (0.0 0.0 9.81) | 0 | gravity vector | - |
| - | ikPos | string | - | nrjl | 0 | IK position solver algorithm | nrjl, online |
| - | epsPos | double | m | 1e-5 | 0 | IK position solver precision | - |
| - | maxIterPos | int | - | 1000 | 0 | IK position solver max iterations | - |
| - | vTranslMax | double | m/s | 1.0 | 0 | maximum translation speed | - |
| - | vRotMax | double | deg/s | 50.0 | 0 | maximum rotation speed | - |
| - | lambda | double | - | 0.01 | 0 | lambda parameter for diff IK | - |
| - | weightsJS | vector<double> | - | - | 0 | joint space weights | - |
| - | weightsTS | vector<double> | - | - | 0 | task space weights | - |
| - | mins | vector<double> | deg | - | 1 | lower bound joint position limits | - |
| - | maxs | vector<double> | deg | - | 1 | upper bound joint position limits | - |
| - | maxvels | vector<double> | deg/s | - | 1 | joint velocity limits | - |
The device can be launched by yarpdev using one of the following examples (with and without all optional parameters):