63 const std::string m_device_classname = {
"KdlSolver"};
64 const std::string m_device_name = {
"KdlSolver"};
65 bool m_parser_is_strict =
false;
73 const std::string m_quiet_defaultValue = {
"false"};
74 const std::string m_kinematics_defaultValue = {
""};
75 const std::string m_gravity_defaultValue = {
"(0.0 0.0 9.81)"};
76 const std::string m_ikPos_defaultValue = {
"st"};
77 const std::string m_ikVel_defaultValue = {
"pinv"};
78 const std::string m_epsPos_defaultValue = {
"1e-5"};
79 const std::string m_maxIterPos_defaultValue = {
"1000"};
80 const std::string m_epsVel_defaultValue = {
"1e-5"};
81 const std::string m_maxIterVel_defaultValue = {
"150"};
82 const std::string m_lambda_defaultValue = {
"0.01"};
83 const std::string m_weightsLMA_defaultValue = {
"(1.0 1.0 1.0 0.1 0.1 0.1)"};
84 const std::string m_weightsJS_defaultValue = {
""};
85 const std::string m_weightsTS_defaultValue = {
""};
86 const std::string m_invKinStrategy_defaultValue = {
"leastOverallAngularDisplacement"};
87 const std::string m_mins_defaultValue = {
""};
88 const std::string m_maxs_defaultValue = {
""};
90 bool m_quiet = {
false};
91 std::string m_kinematics = {};
92 std::vector<double> m_gravity = { };
93 std::string m_ikPos = {
"st"};
94 std::string m_ikVel = {
"pinv"};
95 double m_epsPos = {1e-5};
96 int m_maxIterPos = {1000};
97 double m_epsVel = {1e-5};
98 int m_maxIterVel = {150};
99 double m_lambda = {0.01};
100 std::vector<double> m_weightsLMA = { };
101 std::vector<double> m_weightsJS = {};
102 std::vector<double> m_weightsTS = {};
103 std::string m_invKinStrategy = {
"leastOverallAngularDisplacement"};
104 std::vector<double> m_mins = {};
105 std::vector<double> m_maxs = {};
107 bool parseParams(
const yarp::os::Searchable & config)
override;
108 std::string getDeviceClassName()
const override {
return m_device_classname; }
109 std::string getDeviceName()
const override {
return m_device_name; }
110 std::string getDocumentationOfDeviceParams()
const override;
111 std::vector<std::string> getListOfParams()
const override;