41 i_param_ =
new OpenHRP::ImpedanceControllerService::impedanceParam();
42 i_param_->force_gain.length(3);
43 i_param_->moment_gain.length(3);
CORBA::Boolean stopImpedanceControllerNoWait(const char *i_name_)
virtual ~ImpedanceControllerService_impl()
CORBA::Boolean setImpedanceControllerParam(const char *i_name_, const OpenHRP::ImpedanceControllerService::impedanceParam &i_param_)
bool startImpedanceController(const std::string &i_name_)
impedance control component
CORBA::Boolean startImpedanceControllerNoWait(const char *i_name_)
ImpedanceController * m_impedance
void impedance(ImpedanceController *i_impedance)
bool stopImpedanceControllerNoWait(const std::string &i_name_)
void waitImpedanceControllerTransition(std::string i_name_)
CORBA::Boolean getImpedanceControllerParam(const char *i_name_, OpenHRP::ImpedanceControllerService::impedanceParam_out i_param_)
CORBA::Boolean stopImpedanceController(const char *i_name_)
ImpedanceControllerService_impl()
bool startImpedanceControllerNoWait(const std::string &i_name_)
bool setImpedanceControllerParam(const std::string &i_name_, OpenHRP::ImpedanceControllerService::impedanceParam i_param_)
CORBA::Boolean startImpedanceController(const char *i_name_)
bool getImpedanceControllerParam(const std::string &i_name_, OpenHRP::ImpedanceControllerService::impedanceParam &i_param_)
bool stopImpedanceController(const std::string &i_name_)
void waitImpedanceControllerTransition(const char *i_name_)