stack_of_tasks_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_STACK_OF_TASKS_SOLVER_H
19 #define COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_STACK_OF_TASKS_SOLVER_H
20 
21 #include <set>
22 #include <ros/ros.h>
23 
26 
29 
30 #define START_CNT 40.0
31 
33 {
34  public:
36  const LimiterParams& limiter_params,
37  TaskStackController_t& task_stack_controller) :
38  ConstraintSolver(params, limiter_params, task_stack_controller)
39  {
40  this->last_time_ = ros::Time::now();
42  this->in_cart_vel_damping_ = 1.0;
43  }
44 
46  {}
47 
52  virtual Eigen::MatrixXd solve(const Vector6d_t& in_cart_velocities,
53  const JointStates& joint_states);
54 
58  void processState(std::set<ConstraintBase_t>::iterator& it,
59  const Eigen::MatrixXd& projector,
60  const Eigen::MatrixXd& particular_solution,
61  double inv_sum_of_prios,
62  Eigen::VectorXd& sum_of_gradient);
63 
64  protected:
68 };
69 
70 #endif // COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_STACK_OF_TASKS_SOLVER_H
EN_ConstraintStates global_constraint_state_
Eigen::Matrix< double, 6, 1 > Vector6d_t
virtual Eigen::MatrixXd solve(const Vector6d_t &in_cart_velocities, const JointStates &joint_states)
void processState(std::set< ConstraintBase_t >::iterator &it, const Eigen::MatrixXd &projector, const Eigen::MatrixXd &particular_solution, double inv_sum_of_prios, Eigen::VectorXd &sum_of_gradient)
Base class for solvers, defining interface methods.
static Time now()
StackOfTasksSolver(const TwistControllerParams &params, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller)


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:00