ocra-recipes
Doxygen documentation for the ocra-recipes repository
Public Member Functions | List of all members
hocra::HocraController Class Reference

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

#include <HocraController.h>

Inheritance diagram for hocra::HocraController:
[legend]
Collaboration diagram for hocra::HocraController:
[legend]

Public Member Functions

 HocraController (const std::string &ctrlName, Model::Ptr innerModel, OneLevelSolver::Ptr innerSolver, bool useReducedProblem)
 
virtual void doAddContactSet (const ContactSet &contacts)
 
virtual void doAddTask (Task::Ptr task)
 
virtual void doComputeOutput (VectorXd &tau)
 
Task::Ptr doCreateContactTask (const std::string &name, ocra::PointContactFeature::Ptr feature, double mu, double margin) const
 
Task::Ptr doCreateTask (const std::string &name, ocra::Feature::Ptr feature) const
 
Task::Ptr doCreateTask (const std::string &name, ocra::Feature::Ptr feature, ocra::Feature::Ptr featureDes) const
 
virtual ~HocraController ()
 
- 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 ()
 

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...
 
- 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 doComputeOutput (Eigen::VectorXd &tau)=0
 
virtual void doAddTask (std::shared_ptr< Task > task)=0
 
virtual void doSetMaxJointTorques (const Eigen::VectorXd &tauMax)
 
virtual std::shared_ptr< TaskdoCreateTask (const std::string &name, Feature::Ptr feature, Feature::Ptr featureDes) const =0
 
virtual std::shared_ptr< TaskdoCreateTask (const std::string &name, Feature::Ptr feature) const =0
 
virtual std::shared_ptr< TaskdoCreateContactTask (const std::string &name, PointContactFeature::Ptr feature, double mu, double margin) const =0
 

Detailed Description

Hocra Controller based on LQP solver for the ocra framework.

Definition at line 35 of file HocraController.h.

Constructor & Destructor Documentation

hocra::HocraController::HocraController ( const std::string &  ctrlName,
Model::Ptr  innerModel,
OneLevelSolver::Ptr  innerSolver,
bool  useReducedProblem 
)

Definition at line 9 of file HocraController.cpp.

virtual hocra::HocraController::~HocraController ( )
inlinevirtual

Definition at line 48 of file HocraController.h.

Member Function Documentation

void hocra::HocraController::doAddContactSet ( const ContactSet contacts)
virtual

Implements ocra::Controller.

Definition at line 20 of file HocraController.cpp.

void hocra::HocraController::doAddTask ( Task::Ptr  task)
virtual

Definition at line 24 of file HocraController.cpp.

void hocra::HocraController::doComputeOutput ( VectorXd &  tau)
virtual

Definition at line 30 of file HocraController.cpp.

Task::Ptr hocra::HocraController::doCreateContactTask ( const std::string &  name,
ocra::PointContactFeature::Ptr  feature,
double  mu,
double  margin 
) const

Definition at line 48 of file HocraController.cpp.

Task::Ptr hocra::HocraController::doCreateTask ( const std::string &  name,
ocra::Feature::Ptr  feature 
) const
Task::Ptr hocra::HocraController::doCreateTask ( const std::string &  name,
ocra::Feature::Ptr  feature,
ocra::Feature::Ptr  featureDes 
) const

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