Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes
MotorTorqueController Class Reference

#include <MotorTorqueController.h>

List of all members.

Classes

class  MotorController

Public Types

enum  controller_state_t { INACTIVE, STOP, ACTIVE }
enum  motor_model_t { TWO_DOF_CONTROLLER, TWO_DOF_CONTROLLER_PD_MODEL, TWO_DOF_CONTROLLER_DYNAMICS_MODEL }

Public Member Functions

bool activate (void)
bool deactivate (void)
bool disable (void)
bool enable (void)
double execute (double _tau, double _tauMax)
bool getControllerParam (TwoDofController::TwoDofControllerParam &_param)
bool getControllerParam (TwoDofControllerPDModel::TwoDofControllerPDModelParam &_param)
bool getControllerParam (TwoDofControllerDynamicsModel::TwoDofControllerDynamicsModelParam &_param)
std::string getJointName (void)
controller_state_t getMotorControllerState (void)
motor_model_t getMotorModelType (void)
bool isEnabled (void)
 MotorTorqueController ()
 MotorTorqueController (std::string _jname, TwoDofController::TwoDofControllerParam &_param)
 MotorTorqueController (std::string _jname, TwoDofControllerPDModel::TwoDofControllerPDModelParam &_param)
 MotorTorqueController (std::string _jname, TwoDofControllerDynamicsModel::TwoDofControllerDynamicsModelParam &_param)
void printMotorControllerVariables (void)
void setErrorPrefix (const std::string &_error_prefix)
bool setReferenceTorque (double _tauRef)
void setupController (TwoDofController::TwoDofControllerParam &_param)
void setupController (TwoDofControllerPDModel::TwoDofControllerPDModelParam &_param)
void setupController (TwoDofControllerDynamicsModel::TwoDofControllerDynamicsModelParam &_param)
void setupMotorControllerControlMinMaxDq (double _min_dq, double _max_dq)
void setupMotorControllerTransitionMinMaxDq (double _min_transition_dq, double _max_transition_dq)
bool updateControllerParam (TwoDofController::TwoDofControllerParam &_param)
bool updateControllerParam (TwoDofControllerPDModel::TwoDofControllerPDModelParam &_param)
bool updateControllerParam (TwoDofControllerDynamicsModel::TwoDofControllerDynamicsModelParam &_param)
 ~MotorTorqueController (void)

Private Member Functions

void prepareStop (MotorController &_mc)
void resetMotorControllerVariables (MotorController &_mc)
void setupControllerCommon (std::string _jname, double _dt)
void updateController (double _tau, double _tauRef, MotorController &_mc)

Private Attributes

double m_actual_tauRef
double m_command_tauRef
double m_current_tau
double m_dt
MotorController m_emergencyController
bool m_enable_flag
std::string m_error_prefix
std::string m_joint_name
motor_model_t m_motor_model_type
MotorController m_normalController
int m_transition_count

Detailed Description

Definition at line 21 of file MotorTorqueController.h.


Member Enumeration Documentation

Enumerator:
INACTIVE 
STOP 
ACTIVE 

Definition at line 29 of file MotorTorqueController.h.

Enumerator:
TWO_DOF_CONTROLLER 
TWO_DOF_CONTROLLER_PD_MODEL 
TWO_DOF_CONTROLLER_DYNAMICS_MODEL 

Definition at line 23 of file MotorTorqueController.h.


Constructor & Destructor Documentation

Definition at line 27 of file MotorTorqueController.cpp.

Definition at line 39 of file MotorTorqueController.cpp.

Definition at line 44 of file MotorTorqueController.cpp.

Definition at line 85 of file MotorTorqueController.cpp.

Definition at line 126 of file MotorTorqueController.cpp.


Member Function Documentation

Definition at line 209 of file MotorTorqueController.cpp.

Definition at line 224 of file MotorTorqueController.cpp.

Definition at line 173 of file MotorTorqueController.cpp.

Definition at line 167 of file MotorTorqueController.cpp.

double MotorTorqueController::execute ( double  _tau,
double  _tauMax 
)

Definition at line 236 of file MotorTorqueController.cpp.

Definition at line 59 of file MotorTorqueController.cpp.

Definition at line 100 of file MotorTorqueController.cpp.

Definition at line 141 of file MotorTorqueController.cpp.

Definition at line 290 of file MotorTorqueController.cpp.

Definition at line 295 of file MotorTorqueController.cpp.

Definition at line 330 of file MotorTorqueController.cpp.

Definition at line 304 of file MotorTorqueController.cpp.

Definition at line 357 of file MotorTorqueController.cpp.

Definition at line 316 of file MotorTorqueController.cpp.

Definition at line 350 of file MotorTorqueController.cpp.

void MotorTorqueController::setErrorPrefix ( const std::string &  _error_prefix)

Definition at line 309 of file MotorTorqueController.cpp.

Definition at line 230 of file MotorTorqueController.cpp.

Definition at line 52 of file MotorTorqueController.cpp.

Definition at line 93 of file MotorTorqueController.cpp.

Definition at line 134 of file MotorTorqueController.cpp.

void MotorTorqueController::setupControllerCommon ( std::string  _jname,
double  _dt 
) [private]

Definition at line 336 of file MotorTorqueController.cpp.

void MotorTorqueController::setupMotorControllerControlMinMaxDq ( double  _min_dq,
double  _max_dq 
)

Definition at line 189 of file MotorTorqueController.cpp.

void MotorTorqueController::setupMotorControllerTransitionMinMaxDq ( double  _min_transition_dq,
double  _max_transition_dq 
)

Definition at line 199 of file MotorTorqueController.cpp.

void MotorTorqueController::updateController ( double  _tau,
double  _tauRef,
MotorTorqueController::MotorController _mc 
) [private]

Definition at line 371 of file MotorTorqueController.cpp.

Definition at line 71 of file MotorTorqueController.cpp.

Definition at line 112 of file MotorTorqueController.cpp.

Definition at line 153 of file MotorTorqueController.cpp.


Member Data Documentation

Definition at line 123 of file MotorTorqueController.h.

Definition at line 122 of file MotorTorqueController.h.

Definition at line 121 of file MotorTorqueController.h.

double MotorTorqueController::m_dt [private]

Definition at line 120 of file MotorTorqueController.h.

Definition at line 125 of file MotorTorqueController.h.

Definition at line 127 of file MotorTorqueController.h.

Definition at line 126 of file MotorTorqueController.h.

std::string MotorTorqueController::m_joint_name [private]

Definition at line 117 of file MotorTorqueController.h.

Definition at line 118 of file MotorTorqueController.h.

Definition at line 124 of file MotorTorqueController.h.

Definition at line 119 of file MotorTorqueController.h.


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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:20