ocra-recipes
Doxygen documentation for the ocra-recipes repository
GHCJTTask.h
Go to the documentation of this file.
1 
9 #ifndef __GHCJTTask_H__
10 #define __GHCJTTask_H__
11 
12 // OCRA INCLUDES
16 
17 
18 #include "ocra/control/Task.h"
19 #include "ocra/control/Feature.h"
22 
23 //#include "gocra/Constraints/gOcraConstraint.h"
24 
25 
26 using namespace ocra;
27 namespace ocra
28 {
30 }
31 namespace gocra
32 {
33 
41 class GHCJTTask: public Task
42 {
43 public:
44 
45 
46  GHCJTTask(const std::string& taskName, const Model& innerModel, Feature::Ptr feature, Feature::Ptr featureDes);
47  GHCJTTask(const std::string& taskName, const Model& innerModel, Feature::Ptr feature);
48  virtual ~GHCJTTask();
49 
50 
51  const Eigen::VectorXd& getComputedForce() const;
52 
53  const Eigen::MatrixXd& getPriority() const;
54  void setPriority(Eigen::MatrixXd& alpha);
55  int getTaskDimension() const;
56  const std::string& getTaskName() const;
57  void setIndexBegin(int index);
58  int getIndexBegin() const;
59  void setIndexEnd(int index);
60  int getIndexEnd() const;
61  void setProjector(Eigen::MatrixXd& proj);
62  void setTaskiProjector(Eigen::MatrixXd& proj);
63  const Eigen::MatrixXd& getProjector() const;
64  const Eigen::MatrixXd& getTaskiProjector() const;
65  LinearFunction* getInnerObjectiveFunction() const;
66  const Variable& getVariable() const;
67 
68 
69  //------------------------ friendship ------------------------//
70 protected:
71  friend class GHCJTController; //Only the GHCJTController should know about the following functions
72  void connectToController(ocra::OneLevelSolver& _solver, SumOfLinearFunctions& seConstraint);
73  void disconnectFromController();
74  void update();
75 
76 
77 protected:
78  virtual void doGetOutput(Eigen::VectorXd& output) const;
79 
80  void addContactPointInModel();
81  void removeContactPointInModel();
82 
83  virtual void doActivateContactMode();
84  virtual void doDeactivateContactMode();
85  virtual void doSetFrictionCoeff();
86  virtual void doSetMargin();
87 
88  virtual void doSetWeight();
89 
90  virtual void doActivateAsObjective();
91  virtual void doDeactivateAsObjective();
92  virtual void doActivateAsConstraint();
93  virtual void doDeactivateAsConstraint();
94 
95  void checkIfConnectedToController() const;
96 
97 private:
98  struct Pimpl;
99  boost::shared_ptr<Pimpl> pimpl;
100 
101 };
102 
103  // end group task
105 
106 }
107 
108 #endif
Classes that represent frames.
Declaration file of the SquaredLinearFunction class.
Define the internal solver class that can be used in the wOcra controller.
A class hierarchy to compute task errors based on control frames.
Model class.
Definition: Model.h:38
LinearFunction class.
gOcra Controller based on LQP solver for the ocra framework.
Optimization-based Robot Controller namespace. a library of classes to write and solve optimization p...
A generic abstract task for the GHCJT controller.
Definition: GHCJTTask.h:41
This class represents a variable in a mathematical sense.
Definition: Variable.h:105
Declaration file of the WeightedSquareDistanceFunction class.
A generic abstract class the solvers that can be used in the wOcra Controller.