ocra-recipes
Doxygen documentation for the ocra-recipes repository
Classes | Public Member Functions | Protected Member Functions | List of all members
gocra::GHCJTController Class Reference

gOcra Controller based on LQP solver for the ocra framework. More...

#include <GHCJTController.h>

Inheritance diagram for gocra::GHCJTController:
[legend]
Collaboration diagram for gocra::GHCJTController:
[legend]

Classes

struct  Pimpl
 

Public Member Functions

 GHCJTController (const std::string &ctrlName, Model &innerModel, ocra::OneLevelSolver &innerSolver, bool useGrav)
 
virtual ~GHCJTController ()
 
ModelgetModel ()
 
ocra::OneLevelSolvergetSolver ()
 
void takeIntoAccountGravity (bool useGrav)
 
void writePerformanceInStream (std::ostream &myOstream, bool addCommaAtEnd) const
 
std::string getPerformances () const
 
void addConstraint (ocra::LinearConstraint &constraint) const
 
void removeConstraint (ocra::LinearConstraint &constraint) const
 
GHCJTTaskcreateGHCJTTask (const std::string &name, Feature::Ptr feature, Feature::Ptr featureDes) const
 
GHCJTTaskcreateGHCJTTask (const std::string &name, Feature::Ptr feature) const
 
GHCJTTaskcreateGHCJTContactTask (const std::string &name, PointContactFeature::Ptr feature, double mu, double margin) const
 
void setActiveTaskVector ()
 
void doUpdateAugmentedJacobian ()
 
void doUpdateProjector ()
 
std::vector< GHCJTTask * > & getActiveTask ()
 
int getNbActiveTask () const
 
int getTotalActiveTaskDimensions () const
 
void initPriorityMatrix ()
 
std::pair< Eigen::VectorXd, Eigen::MatrixXd > sortRows (const Eigen::MatrixXd &C, const Eigen::MatrixXd &J)
 
void computeProjector (const Eigen::MatrixXd &C, const Eigen::MatrixXd &J, Eigen::MatrixXd &projector)
 
void computeTaskiProjector (const Eigen::MatrixXd &J, Eigen::MatrixXd &projector)
 
void setTaskProjectors (Eigen::MatrixXd &param)
 
- Public Member Functions inherited from ocra::Controller
virtual ~Controller ()=0
 
void printInfo (int level, const std::string &filename)
 
void setMaxJointTorques (const Eigen::VectorXd &tau_max)
 
const Eigen::VectorXd & getMaxJointTorques () const
 
void addTask (std::shared_ptr< Task > task)
 
void addTasks (const std::vector< std::shared_ptr< Task >> &tasks)
 
void removeTask (const std::string &taskName)
 
void removeTasks (const std::vector< std::string > tasks)
 
std::vector< std::string > getTaskNames ()
 
std::string getTaskPortName (const std::string &taskName)
 
std::vector< std::string > getTaskPortNames ()
 
void addContactSet (const ContactSet &contacts)
 
std::shared_ptr< TaskgetTask (const std::string &name)
 
const std::shared_ptr< TaskgetTask (const std::string &name) const
 
const std::map< std::string, std::shared_ptr< Task > > & getTasks () const
 
void computeOutput (Eigen::VectorXd &tau)
 Computation of output torques based on the tasks added to the controller. More...
 
const Eigen::VectorXd & computeOutput ()
 
std::shared_ptr< TaskcreateContactTask (const std::string &name, PointContactFeature::Ptr feature, double mu, double margin) const
 Creates a contact task. More...
 
std::shared_ptr< TaskcreateTask (const std::string &name, Feature::Ptr feature, Feature::Ptr featureDes) const
 Generic task creation. More...
 
std::shared_ptr< TaskcreateTask (const std::string &name, Feature::Ptr feature) const
 
void enableErrorHandling ()
 
void disableErrorHandling ()
 
bool isErrorHandlingEnabled () const
 
const std::string & getErrorMessage () const
 
void clearErrorFlag ()
 
int getErrorFlag () const
 
void setMaxJointTorqueNorm (double maxTau)
 
double getMaxJointTorqueNorm () const
 
void setFixedLinkForOdometry (std::string newFixedLink)
 
void setUseOdometry (bool useOdometry)
 
void getFixedLinkForOdometry (std::string &currentFixedLink)
 
void setContactState (int isInLeftSupport, int isInRightSupport)
 
void getContactState (int &leftSupport, int &rightSupport)
 
- Public Member Functions inherited from ocra::NamedInstance
 NamedInstance (const std::string &name)
 
const std::string & getName () const
 
virtual ~NamedInstance ()
 

Protected Member Functions

virtual void doComputeOutput (Eigen::VectorXd &tau)
 
virtual void doAddTask (Task &task)
 
virtual void doAddContactSet (const ContactSet &contacts)
 
virtual TaskdoCreateTask (const std::string &name, Feature::Ptr feature, Feature::Ptr featureDes) const
 
virtual TaskdoCreateTask (const std::string &name, Feature::Ptr feature) const
 
virtual TaskdoCreateContactTask (const std::string &name, PointContactFeature::Ptr feature, double mu, double margin) const
 
- Protected Member Functions inherited from ocra::Controller
 Controller (const std::string &name, Model &model)
 
const std::vector< std::shared_ptr< Task > > & getActiveTasks () const
 
void setErrorFlag (int eflag)
 
void setErrorMessage (const std::string &msg)
 
virtual void doAddTask (std::shared_ptr< Task > task)=0
 
virtual void doSetMaxJointTorques (const Eigen::VectorXd &tauMax)
 

Additional Inherited Members

- Public Types inherited from ocra::Controller
enum  ErrorFlag {
  SUCCESS = 0, CRITICAL_ERROR = 1, STATIC_EQ_LOSS = 2, DYN_EQ_LOSS = 4,
  INSTABILITY = 8 + 1, OTHER = 16
}
 Error handling. More...
 

Detailed Description

gOcra Controller based on LQP solver for the ocra framework.

Definition at line 40 of file GHCJTController.h.

Constructor & Destructor Documentation

gocra::GHCJTController::GHCJTController ( const std::string &  ctrlName,
Model innerModel,
ocra::OneLevelSolver innerSolver,
bool  useGrav 
)

Initialize GHCJT controller.

Parameters
ctrlNameThe name of the controller
innerModelThe internal model of the robot one wants to control
innerSolverThe internal solver one wants to use to make the quadratic optimization
useGravWhether to activate gravity compensation or not

Definition at line 85 of file GHCJTController.cpp.

gocra::GHCJTController::~GHCJTController ( )
virtual

Destructor

Definition at line 95 of file GHCJTController.cpp.

Member Function Documentation

void gocra::GHCJTController::addConstraint ( ocra::LinearConstraint constraint) const

Definition at line 134 of file GHCJTController.cpp.

void gocra::GHCJTController::computeProjector ( const Eigen::MatrixXd &  C,
const Eigen::MatrixXd &  J,
Eigen::MatrixXd &  projector 
)

Definition at line 494 of file GHCJTController.cpp.

void gocra::GHCJTController::computeTaskiProjector ( const Eigen::MatrixXd &  J,
Eigen::MatrixXd &  projector 
)

Definition at line 532 of file GHCJTController.cpp.

GHCJTTask & gocra::GHCJTController::createGHCJTContactTask ( const std::string &  name,
PointContactFeature::Ptr  feature,
double  mu,
double  margin 
) const

Definition at line 200 of file GHCJTController.cpp.

GHCJTTask & gocra::GHCJTController::createGHCJTTask ( const std::string &  name,
Feature::Ptr  feature,
Feature::Ptr  featureDes 
) const

Definition at line 188 of file GHCJTController.cpp.

GHCJTTask & gocra::GHCJTController::createGHCJTTask ( const std::string &  name,
Feature::Ptr  feature 
) const

Definition at line 194 of file GHCJTController.cpp.

void gocra::GHCJTController::doAddContactSet ( const ContactSet contacts)
protectedvirtual

Internal implementation inside the addContactSet method.

Parameters
contactsThe contact set to add in the controller
Todo:
this method has not been implemented!!!

Implements ocra::Controller.

Definition at line 180 of file GHCJTController.cpp.

void gocra::GHCJTController::doAddTask ( Task task)
protectedvirtual

Internal implementation inside the addTask method.

Parameters
taskThe task to add in the controller

Definition at line 163 of file GHCJTController.cpp.

void gocra::GHCJTController::doComputeOutput ( Eigen::VectorXd &  tau)
protectedvirtual

Compute the output of the controller.

Parameters
tauThe joint torques, which is the output of our problem

Here, the controller solves the optimization problem depending on the tasks and constraints, and the result is set in the variable of the problem $ \force_c $. The torque $ \tau $ is computed using $ \force_c $, and it is finally applied to the robot.

Implements ocra::Controller.

Definition at line 272 of file GHCJTController.cpp.

Task * gocra::GHCJTController::doCreateContactTask ( const std::string &  name,
PointContactFeature::Ptr  feature,
double  mu,
double  margin 
) const
protectedvirtual

Internal implementation inside the createContactTask method.

Parameters
nameThe task name, a unique identifier
featureThe contact point feature of the robot one wants to control
muThe friction cone coefficient $ \mu $ such as $ \Vert \force_t \Vert < \mu \force_n $
marginThe margin inside the friction cone
Returns
The pointer to the new created contact task

This method is called by the higher level methods #createGHCJTContactTask(const std::string&, PointContactFeature::Ptr, , double, double, int, double) const and is the concrete implementation required by the xde Controller class.

Implements ocra::Controller.

Definition at line 254 of file GHCJTController.cpp.

Task * gocra::GHCJTController::doCreateTask ( const std::string &  name,
Feature::Ptr  feature,
Feature::Ptr  featureDes 
) const
protectedvirtual

Internal implementation inside the createTask method.

Parameters
nameThe task name, a unique identifier
featureThe part of the robot one wants to control (full state, frame, CoM,...)
featureDesThe desired state one wants to reach, depends on the feature argument
Returns
The pointer to the new created task

This method is called by the higher level methods #createGHCJTTask(const std::string&, const Feature&, const Feature&, int, double) const and #createGHCJTTask(const std::string&, const Feature&, int, double) const and is the concrete implementation required by the xde Controller class.

Implements ocra::Controller.

Definition at line 220 of file GHCJTController.cpp.

Task * gocra::GHCJTController::doCreateTask ( const std::string &  name,
Feature::Ptr  feature 
) const
protectedvirtual

Internal implementation inside the createTask method.

Parameters
nameThe task name, a unique identifier
featureThe part of the robot one wants to control (full state, frame, CoM,...)
Returns
The pointer to the new created task

This method is called by the higher level methods #createGHCJTTask(const std::string&, const Feature&, const Feature&, int, double) const and #createGHCJTTask(const std::string&, const Feature&, int, double) const and is the concrete implementation required by the xde Controller class.

Implements ocra::Controller.

Definition at line 236 of file GHCJTController.cpp.

void gocra::GHCJTController::doUpdateAugmentedJacobian ( )

Definition at line 405 of file GHCJTController.cpp.

void gocra::GHCJTController::doUpdateProjector ( )

Definition at line 422 of file GHCJTController.cpp.

std::vector< GHCJTTask * > & gocra::GHCJTController::getActiveTask ( )

Definition at line 437 of file GHCJTController.cpp.

Model & gocra::GHCJTController::getModel ( )
Returns
the inner model used to construct this controller instance

Definition at line 113 of file GHCJTController.cpp.

int gocra::GHCJTController::getNbActiveTask ( ) const

Definition at line 442 of file GHCJTController.cpp.

std::string gocra::GHCJTController::getPerformances ( ) const

Get information about performances through a string.

Information are saved in a JSON way (http://www.json.org/). It returns a of dictionnary on the form:

{
"performance_info_1": [0.01, 0.02, 0.01, ... , 0.03, 0.01],
...
"performance_info_n": [0.01, 0.02, 0.01, ... , 0.03, 0.01]
}

where performance_info are:

  • controller_update_tasks
  • controller_solve_problem
  • solver_prepare
  • solver_solve

See gocra::GHCJTController::writePerformanceInStream(std::ostream&, bool) and gocra::ocra::OneLevelSolver::writePerformanceInStream(std::ostream&, bool).

Definition at line 371 of file GHCJTController.cpp.

ocra::OneLevelSolver & gocra::GHCJTController::getSolver ( )
Returns
the inner solver used to construct this controller instance

Definition at line 121 of file GHCJTController.cpp.

int gocra::GHCJTController::getTotalActiveTaskDimensions ( ) const

Definition at line 447 of file GHCJTController.cpp.

void gocra::GHCJTController::initPriorityMatrix ( )

Definition at line 452 of file GHCJTController.cpp.

void gocra::GHCJTController::removeConstraint ( ocra::LinearConstraint constraint) const

Definition at line 140 of file GHCJTController.cpp.

void gocra::GHCJTController::setActiveTaskVector ( )

Definition at line 381 of file GHCJTController.cpp.

void gocra::GHCJTController::setTaskProjectors ( Eigen::MatrixXd &  param)

Definition at line 544 of file GHCJTController.cpp.

std::pair< VectorXd, MatrixXd > gocra::GHCJTController::sortRows ( const Eigen::MatrixXd &  C,
const Eigen::MatrixXd &  J 
)

Definition at line 467 of file GHCJTController.cpp.

void gocra::GHCJTController::takeIntoAccountGravity ( bool  useGrav)

Definition at line 127 of file GHCJTController.cpp.

void gocra::GHCJTController::writePerformanceInStream ( std::ostream &  outstream,
bool  addCommaAtEnd 
) const

Write information about controller performances in a string stream.

Parameters
outstreamthe output stream where to write the performances information
addCommaAtEndIf true, add a comma at the end of the stream. If false, it means that this is the end of the json file, nothing will be added after that, no comma is added.

See gocra::GHCJTController::getPerformances() to know more. Here it saves:

  • controller_update_tasks
  • controller_solve_problem

Definition at line 341 of file GHCJTController.cpp.


The documentation for this class was generated from the following files: