task_priority_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_TASK_PRIORITY_SOLVER_H
19 #define COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_TASK_PRIORITY_SOLVER_H
20 
21 #include <set>
22 #include "ros/ros.h"
23 
26 
27 
30 
32 {
33  public:
35  const LimiterParams& limiter_params,
36  TaskStackController_t& task_stack_controller) :
37  ConstraintSolver(params, limiter_params, task_stack_controller)
38  {
39  this->last_time_ = ros::Time::now();
40  }
41 
43  {}
44 
49  virtual Eigen::MatrixXd solve(const Vector6d_t& in_cart_velocities,
50  const JointStates& joint_states);
51 
52  protected:
54 };
55 
56 #endif // COB_TWIST_CONTROLLER_CONSTRAINT_SOLVERS_SOLVERS_TASK_PRIORITY_SOLVER_H
Eigen::Matrix< double, 6, 1 > Vector6d_t
TaskPrioritySolver(const TwistControllerParams &params, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller)
Base class for solvers, defining interface methods.
static Time now()
virtual Eigen::MatrixXd solve(const Vector6d_t &in_cart_velocities, const JointStates &joint_states)


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