include
cob_twist_controller
constraint_solvers
solvers
wln_joint_limit_avoidance_solver.h
Go to the documentation of this file.
1
/*
2
* Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
18
#ifndef COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_WLN_JOINT_LIMIT_AVOIDANCE_SOLVER_H
19
#define COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_WLN_JOINT_LIMIT_AVOIDANCE_SOLVER_H
20
21
#include "
cob_twist_controller/cob_twist_controller_data_types.h
"
22
#include "
cob_twist_controller/constraint_solvers/solvers/weighted_least_norm_solver.h
"
23
26
class
WLN_JointLimitAvoidanceSolver
:
public
WeightedLeastNormSolver
27
{
28
public
:
29
WLN_JointLimitAvoidanceSolver
(
const
TwistControllerParams
& params,
30
const
LimiterParams
& limiter_params,
31
TaskStackController_t
& task_stack_controller) :
32
WeightedLeastNormSolver
(params, limiter_params, task_stack_controller)
33
{}
34
35
virtual
~WLN_JointLimitAvoidanceSolver
()
36
{}
37
38
private
:
46
virtual
Eigen::MatrixXd
calculateWeighting
(
const
JointStates
& joint_states)
const
;
47
};
48
49
#endif // COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_WLN_JOINT_LIMIT_AVOIDANCE_SOLVER_H
WeightedLeastNormSolver
Implementation of ConstraintSolver to solve inverse kinematics by using a weighted least norm.
Definition:
weighted_least_norm_solver.h:25
WLN_JointLimitAvoidanceSolver
Definition:
wln_joint_limit_avoidance_solver.h:26
weighted_least_norm_solver.h
WLN_JointLimitAvoidanceSolver::WLN_JointLimitAvoidanceSolver
WLN_JointLimitAvoidanceSolver(const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller)
Definition:
wln_joint_limit_avoidance_solver.h:29
LimiterParams
Definition:
cob_twist_controller_data_types.h:162
WLN_JointLimitAvoidanceSolver::~WLN_JointLimitAvoidanceSolver
virtual ~WLN_JointLimitAvoidanceSolver()
Definition:
wln_joint_limit_avoidance_solver.h:35
TaskStackController< uint32_t >
TwistControllerParams
Definition:
cob_twist_controller_data_types.h:209
JointStates
Definition:
cob_twist_controller_data_types.h:112
WLN_JointLimitAvoidanceSolver::calculateWeighting
virtual Eigen::MatrixXd calculateWeighting(const JointStates &joint_states) const
Definition:
wln_joint_limit_avoidance_solver.cpp:27
cob_twist_controller_data_types.h
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon
, Christoph Mark
, Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43