task_priority_solver.h
Go to the documentation of this file.
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_TASK_PRIORITY_SOLVER_H
00019 #define COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_TASK_PRIORITY_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 
00028 #include "cob_twist_controller/constraints/constraint_base.h"
00029 #include "cob_twist_controller/constraints/constraint.h"
00030 
00031 class TaskPrioritySolver : public ConstraintSolver<>
00032 {
00033     public:
00034         TaskPrioritySolver(const TwistControllerParams& params,
00035                            const LimiterParams& limiter_params,
00036                            TaskStackController_t& task_stack_controller) :
00037                 ConstraintSolver(params, limiter_params, task_stack_controller)
00038         {
00039             this->last_time_ = ros::Time::now();
00040         }
00041 
00042         virtual ~TaskPrioritySolver()
00043         {}
00044 
00049         virtual Eigen::MatrixXd solve(const Vector6d_t& in_cart_velocities,
00050                                       const JointStates& joint_states);
00051 
00052     protected:
00053         ros::Time last_time_;
00054 };
00055 
00056 #endif  // COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_TASK_PRIORITY_SOLVER_H


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26