|
kinematics-dynamics
|
#include <KdlSolver_ParamsParser.h>
Classes | |
| struct | parser_version_type |
Public Attributes | |
| const std::string | m_device_classname = {"KdlSolver"} |
| const std::string | m_device_name = {"KdlSolver"} |
| bool | m_parser_is_strict = false |
| const parser_version_type | m_parser_version = {} |
| const std::string | m_quiet_defaultValue = {"false"} |
| const std::string | m_kinematics_defaultValue = {""} |
| const std::string | m_gravity_defaultValue = {"(0.0 0.0 9.81)"} |
| const std::string | m_ikPos_defaultValue = {"st"} |
| const std::string | m_ikVel_defaultValue = {"pinv"} |
| const std::string | m_epsPos_defaultValue = {"1e-5"} |
| const std::string | m_maxIterPos_defaultValue = {"1000"} |
| const std::string | m_epsVel_defaultValue = {"1e-5"} |
| const std::string | m_maxIterVel_defaultValue = {"150"} |
| const std::string | m_lambda_defaultValue = {"0.01"} |
| const std::string | m_weightsLMA_defaultValue = {"(1.0 1.0 1.0 0.1 0.1 0.1)"} |
| const std::string | m_weightsJS_defaultValue = {""} |
| const std::string | m_weightsTS_defaultValue = {""} |
| const std::string | m_invKinStrategy_defaultValue = {"leastOverallAngularDisplacement"} |
| const std::string | m_mins_defaultValue = {""} |
| const std::string | m_maxs_defaultValue = {""} |
| bool | m_quiet = {false} |
| std::string | m_kinematics = {} |
| std::vector< double > | m_gravity = { } |
| std::string | m_ikPos = {"st"} |
| std::string | m_ikVel = {"pinv"} |
| double | m_epsPos = {1e-5} |
| int | m_maxIterPos = {1000} |
| double | m_epsVel = {1e-5} |
| int | m_maxIterVel = {150} |
| double | m_lambda = {0.01} |
| std::vector< double > | m_weightsLMA = { } |
| std::vector< double > | m_weightsJS = {} |
| std::vector< double > | m_weightsTS = {} |
| std::string | m_invKinStrategy = {"leastOverallAngularDisplacement"} |
| std::vector< double > | m_mins = {} |
| std::vector< double > | m_maxs = {} |
This class is the parameters parser for class KdlSolver.
These are the used parameters:
| Group name | Parameter name | Type | Units | Default Value | Required | Description | Notes |
|---|---|---|---|---|---|---|---|
| - | quiet | bool | - | false | 0 | disable logging | - |
| - | 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 | - | st | 0 | IK position solver algorithm | lma, nrjl, st, id |
| - | ikVel | string | - | pinv | 0 | IK velocity solver algorithm | pinv, wdls |
| - | epsPos | double | m | 1e-5 | 0 | IK position solver precision | - |
| - | maxIterPos | int | - | 1000 | 0 | IK position solver max iterations | - |
| - | epsVel | double | m | 1e-5 | 0 | IK velocity solver precision | - |
| - | maxIterVel | int | - | 150 | 0 | IK velocity solver max iterations | - |
| - | lambda | double | - | 0.01 | 0 | lambda parameter for diff IK | - |
| - | weightsLMA | vector<double> | - | (1.0 1.0 1.0 0.1 0.1 0.1) | 0 | LMA algorithm weights | - |
| - | weightsJS | vector<double> | - | - | 0 | joint space weights | - |
| - | weightsTS | vector<double> | - | - | 0 | task space weights | - |
| - | invKinStrategy | string | - | leastOverallAngularDisplacement | 0 | IK configuration strategy | - |
| - | mins | vector<double> | deg | - | 1 | lower bound joint position limits | - |
| - | maxs | vector<double> | deg | - | 1 | upper bound joint position limits | - |
The device can be launched by yarpdev using one of the following examples (with and without all optional parameters):