00001 /* 00002 * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA) 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 */ 00016 00017 00018 #ifndef COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_STACK_OF_TASKS_SOLVER_H 00019 #define COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_STACK_OF_TASKS_SOLVER_H 00020 00021 #include <set> 00022 #include <ros/ros.h> 00023 00024 #include "cob_twist_controller/cob_twist_controller_data_types.h" 00025 #include "cob_twist_controller/constraint_solvers/solvers/constraint_solver_base.h" 00026 00027 #include "cob_twist_controller/constraints/constraint_base.h" 00028 #include "cob_twist_controller/constraints/constraint.h" 00029 00030 #define START_CNT 40.0 00031 00032 class StackOfTasksSolver : public ConstraintSolver<> 00033 { 00034 public: 00035 StackOfTasksSolver(const TwistControllerParams& params, 00036 const LimiterParams& limiter_params, 00037 TaskStackController_t& task_stack_controller) : 00038 ConstraintSolver(params, limiter_params, task_stack_controller) 00039 { 00040 this->last_time_ = ros::Time::now(); 00041 this->global_constraint_state_ = NORMAL; 00042 this->in_cart_vel_damping_ = 1.0; 00043 } 00044 00045 virtual ~StackOfTasksSolver() 00046 {} 00047 00052 virtual Eigen::MatrixXd solve(const Vector6d_t& in_cart_velocities, 00053 const JointStates& joint_states); 00054 00058 void processState(std::set<ConstraintBase_t>::iterator& it, 00059 const Eigen::MatrixXd& projector, 00060 const Eigen::MatrixXd& particular_solution, 00061 double inv_sum_of_prios, 00062 Eigen::VectorXd& sum_of_gradient); 00063 00064 protected: 00065 ros::Time last_time_; 00066 EN_ConstraintStates global_constraint_state_; 00067 double in_cart_vel_damping_; 00068 }; 00069 00070 #endif // COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_STACK_OF_TASKS_SOLVER_H