12 #include <hrpModel/Sensor.h> 13 #include <hrpModel/ModelLoaderUtil.h> 18 #include "hrpsys/util/Hrpsys.h" 19 #include <boost/assign.hpp> 21 #define MAX_TRANSITION_COUNT (static_cast<int>(2/m_dt)) 28 "implementation_id",
"ImpedanceController",
29 "type_name",
"ImpedanceController",
30 "description",
"impedance controller component",
31 "version", HRPSYS_PACKAGE_VERSION,
33 "category",
"example",
34 "activity_type",
"DataFlowComponent",
37 "lang_type",
"compile",
39 "conf.default.debugLevel",
"0",
47 m_qCurrentIn(
"qCurrent", m_qCurrent),
48 m_qRefIn(
"qRef", m_qRef),
49 m_basePosIn(
"basePosIn", m_basePos),
50 m_baseRpyIn(
"baseRpyIn", m_baseRpy),
51 m_rpyIn(
"rpy", m_rpy),
53 m_ImpedanceControllerServicePort(
"ImpedanceControllerService"),
58 use_sh_base_pos_rpy(false)
70 std::cerr <<
"[" <<
m_profile.instance_name <<
"] onInitialize()" << std::endl;
105 std::string nameServer = rtcManager.
getConfig()[
"corba.nameservers"];
106 int comPos = nameServer.find(
",");
108 comPos = nameServer.length();
110 nameServer = nameServer.substr(0, comPos);
113 CosNaming::NamingContext::_duplicate(
naming.getRootContext())
115 std::cerr <<
"[" <<
m_profile.instance_name <<
"] failed to load model[" << prop[
"model"] <<
"]" << std::endl;
116 return RTC::RTC_ERROR;
121 std::vector<std::string> fsensor_names;
124 for (
unsigned int i=0;
i<npforce;
i++){
129 unsigned int nvforce =
m_vfs.size();
130 for (
unsigned int i=0;
i<nvforce;
i++){
131 for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it =
m_vfs.begin(); it !=
m_vfs.end(); it++ ) {
132 if (it->second.id == (
int)
i) fsensor_names.push_back(it->first);
136 unsigned int nforce = npforce + nvforce;
141 std::cerr <<
"[" <<
m_profile.instance_name <<
"] force sensor ports" << std::endl;
142 for (
unsigned int i=0;
i<nforce;
i++){
152 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << fsensor_names[i] << std::endl;
160 unsigned int dof =
m_robot->numJoints();
161 for (
unsigned int i = 0 ;
i < dof;
i++ ){
162 if ( (
int)
i !=
m_robot->joint(
i)->jointId ) {
163 std::cerr <<
"[" <<
m_profile.instance_name <<
"] jointId is not equal to the index number" << std::endl;
164 return RTC::RTC_ERROR;
171 std::map<std::string, std::string> base_name_map;
172 if (end_effectors_str.size() > 0) {
173 size_t prop_num = 10;
174 size_t num = end_effectors_str.size()/prop_num;
175 for (
size_t i = 0;
i < num;
i++) {
176 std::string ee_name, ee_target, ee_base;
181 for (
size_t j = 0;
j < 3;
j++) {
185 for (
int j = 0;
j < 4;
j++ ) {
188 eet.
localR = Eigen::AngleAxis<double>(tmpv[3],
hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix();
190 ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
191 base_name_map.insert(std::pair<std::string, std::string>(ee_name, ee_base));
192 std::cerr <<
"[" <<
m_profile.instance_name <<
"] End Effector [" << ee_name <<
"]" << ee_target <<
" " << ee_base << std::endl;
193 std::cerr <<
"[" <<
m_profile.instance_name <<
"] target = " << ee_target <<
", base = " << ee_base << std::endl;
194 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localPos = " << eet.
localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
195 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localR = " << eet.
localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
200 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Add impedance params" << std::endl;
202 std::string sensor_name =
m_forceIn[
i]->name();
204 std::string sensor_link_name;
207 sensor_link_name = sensor->
link->
name;
208 }
else if (
m_vfs.find(sensor_name) !=
m_vfs.end()) {
210 sensor_link_name =
m_vfs[sensor_name].link->name;
212 std::cerr <<
"[" <<
m_profile.instance_name <<
"] unknown force param" << std::endl;
217 bool is_ee_exists =
false;
218 for ( std::map<std::string, ee_trans>::iterator it =
ee_map.begin(); it !=
ee_map.end(); it++ ) {
220 std::string tmp_base_name = base_name_map[it->first];
221 while (alink != NULL && alink->
name != tmp_base_name && !is_ee_exists) {
222 if ( alink->
name == sensor_link_name ) {
230 std::cerr <<
"[" <<
m_profile.instance_name <<
"] No such ee setting for " << sensor_name <<
" and " << sensor_link_name <<
"!!. Impedance param for " << sensor_name <<
" cannot be added!!" << std::endl;
235 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Already impedance param (target_name=" << sensor_link_name <<
", ee_name=" << ee_name <<
") exists!!. Impedance param for " << sensor_name <<
" cannot be added!!" << std::endl;
243 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Invalid joint path from " << base_name_map[ee_name] <<
" to " << target_link->
name <<
"!! Impedance param for " << sensor_name <<
" cannot be added!!" << std::endl;
250 std::cerr <<
"[" <<
m_profile.instance_name <<
"] sensor = " << sensor_name <<
", sensor-link = " << sensor_link_name <<
", ee_name = " << ee_name <<
", ee-link = " << target_link->
name << std::endl;
253 std::vector<std::pair<hrp::Link*, hrp::Link*> > interlocking_joints;
255 if (interlocking_joints.size() > 0) {
257 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Interlocking Joints for [" << it->first <<
"]" << std::endl;
258 it->second.manip->setInterlockingJointPairIndices(interlocking_joints, std::string(
m_profile.instance_name));
263 m_q.data.length(dof);
293 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onActivated(" << ec_id <<
")" << std::endl;
300 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onDeactivated(" << ec_id <<
")" << std::endl;
302 if (it->second.is_active) {
304 it->second.transition_count = 1;
310 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 ) 345 std::cerr <<
"[" <<
m_profile.instance_name <<
"] qRef = ";
346 for (
unsigned int i = 0;
i <
m_qRef.data.length();
i++ ){
347 std::cerr <<
" " <<
m_qRef.data[
i];
349 std::cerr << std::endl;
357 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ){
368 for (
unsigned int j = 0;
j < param.
manip->numJoints();
j++ ){
369 int i = param.
manip->joint(
j)->jointId;
370 m_robot->joint(i)->q = qorg[i];
374 m_robot->calcForwardKinematics();
379 bool is_active =
false;
381 is_active = is_active || it->second.is_active;
384 for (
unsigned int i = 0;
i <
m_qRef.data.length();
i++ ){
396 if (
m_q.data.length() != 0 ) {
397 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ){
402 std::cerr <<
"[" <<
m_profile.instance_name <<
"] q = ";
403 for (
unsigned int i = 0;
i <
m_q.data.length();
i++ ){
404 std::cerr <<
" " <<
m_q.data[
i];
406 std::cerr << std::endl;
411 std::cerr <<
"ImpedanceController is not working..." << std::endl;
412 std::cerr <<
" m_qRef " <<
m_qRef.data.length() << std::endl;
413 std::cerr <<
" m_qCurrent " <<
m_qCurrent.data.length() << std::endl;
457 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ){
463 m_robot->calcForwardKinematics();
472 std::vector<hrp::Vector3> foot_pos;
473 std::vector<hrp::Matrix33> foot_rot;
474 std::vector<std::string> leg_names;
475 leg_names.push_back(
"rleg");
476 leg_names.push_back(
"lleg");
477 for (
size_t i = 0;
i < leg_names.size();
i++) {
479 foot_pos.push_back(target_link->
p + target_link->
R *
ee_map[leg_names[
i]].localPos);
480 foot_rot.push_back(target_link->
R *
ee_map[leg_names[i]].localR);
482 hrp::Vector3 current_foot_mid_pos ((foot_pos[0]+foot_pos[1])/2.0);
484 rats::mid_rot(current_foot_mid_rot, 0.5, foot_rot[0], foot_rot[1]);
495 new_foot_mid_rot(0,0) = xv1(0); new_foot_mid_rot(1,0) = xv1(1); new_foot_mid_rot(2,0) = xv1(2);
496 new_foot_mid_rot(0,1) = yv1(0); new_foot_mid_rot(1,1) = yv1(1); new_foot_mid_rot(2,1) = yv1(2);
497 new_foot_mid_rot(0,2) = ez(0); new_foot_mid_rot(1,2) = ez(1); new_foot_mid_rot(2,2) = ez(2);
500 hrp::Matrix33 tmpR (new_foot_mid_rot * current_foot_mid_rot.transpose());
501 m_robot->rootLink()->p = new_foot_mid_pos + tmpR * (
m_robot->rootLink()->p - current_foot_mid_pos);
503 m_robot->calcForwardKinematics();
509 std::string target_name =
ee_map[it->first].target_name;
520 std::string sensor_name =
m_forceIn[
i]->name();
527 std::cerr <<
"[" <<
m_profile.instance_name <<
"] force and moment [" << sensor_name <<
"]" << std::endl;
528 std::cerr <<
"[" <<
m_profile.instance_name <<
"] sensor force = " << data_p.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N]" << std::endl;
529 std::cerr <<
"[" <<
m_profile.instance_name <<
"] sensor moment = " << data_r.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[Nm]" << std::endl;
530 std::cerr <<
"[" <<
m_profile.instance_name <<
"] reference force = " << ref_data_p.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N]" << std::endl;
531 std::cerr <<
"[" <<
m_profile.instance_name <<
"] reference moment = " << ref_data_r.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[Nm]" << std::endl;
539 }
else if (
m_vfs.find(sensor_name) !=
m_vfs.end()) {
542 std::cerr <<
"[" <<
m_profile.instance_name <<
"] sensorR = " <<
m_vfs[sensor_name].localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
544 sensorR =
m_vfs[sensor_name].link->R *
m_vfs[sensor_name].localR;
545 sensorPos =
m_vfs[sensor_name].link->p +
m_vfs[sensor_name].link->R *
m_vfs[sensor_name].localPos;
547 std::cerr <<
"[" <<
m_profile.instance_name <<
"] unknown force param" << std::endl;
551 if ( it->second.sensor_name == sensor_name ) eePos = it->second.target_p0;
562 std::cerr <<
"[" <<
m_profile.instance_name <<
"] abs force = " <<
abs_forces[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N]" << std::endl;
563 std::cerr <<
"[" <<
m_profile.instance_name <<
"] abs moment = " <<
abs_moments[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[Nm]" << std::endl;
564 std::cerr <<
"[" <<
m_profile.instance_name <<
"] abs ref force = " <<
abs_ref_forces[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N]" << std::endl;
565 std::cerr <<
"[" <<
m_profile.instance_name <<
"] abs ref moment = " <<
abs_ref_moments[sensor_name].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[Nm]" << std::endl;
578 std::cerr <<
"[" <<
m_profile.instance_name <<
"] impedance mode " << it->first <<
" transition count = " << param.
transition_count <<
", ";
579 std::cerr <<
"MDK = " << param.
M_p <<
" " << param.
D_p <<
" " << param.
K_p <<
", ";
580 std::cerr <<
"MDK = " << param.
M_r <<
" " << param.
D_r <<
" " << param.
K_r <<
", ";
590 for (
unsigned int j = 0;
j < manip->numJoints();
j++ ) {
591 int i = manip->joint(
j)->jointId;
598 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Finished cleanup and erase impedance param " << it->first << std::endl;
646 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found impedance controller param [" << i_name_ <<
"]" << std::endl;
650 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Impedance control [" << i_name_ <<
"] is already started" << std::endl;
653 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Start impedance control [" << i_name_ <<
"]" << std::endl;
673 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found impedance controller param [" << i_name_ <<
"]" << std::endl;
677 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Impedance control [" << i_name_ <<
"] is already stopped" << std::endl;
680 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Stop impedance control [" << i_name_ <<
"]" << std::endl;
681 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ) {
701 std::string
name = std::string(i_name_);
703 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found impedance controller param [" << name <<
"]" << std::endl;
707 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Update impedance parameters" << std::endl;
726 std::vector<double> ov;
729 ov[
i] = i_param_.ik_optional_weight_vector[
i];
734 std::cerr <<
"[" <<
m_profile.instance_name <<
"] set parameters" << std::endl;
735 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name : " << name << std::endl;
738 std::cerr <<
"[" <<
m_profile.instance_name <<
"] force_gain : " <<
m_impedance_param[name].force_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
739 std::cerr <<
"[" <<
m_profile.instance_name <<
"] moment_gain : " <<
m_impedance_param[name].moment_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
740 std::cerr <<
"[" <<
m_profile.instance_name <<
"] manip_limit : " <<
m_impedance_param[name].manipulability_limit << std::endl;
751 i_param_.M_p = param.
M_p;
752 i_param_.D_p = param.
D_p;
753 i_param_.K_p = param.
K_p;
754 i_param_.M_r = param.
M_r;
755 i_param_.D_r = param.
D_r;
756 i_param_.K_r = param.
K_r;
757 for (
size_t i = 0;
i < 3;
i++) i_param_.force_gain[
i] = param.
force_gain(
i,
i);
759 i_param_.sr_gain = param.
sr_gain;
763 if (param.
is_active) i_param_.controller_mode = OpenHRP::ImpedanceControllerService::MODE_IMP;
764 else i_param_.controller_mode = OpenHRP::ImpedanceControllerService::MODE_IDLE;
765 if (param.
manip == NULL) i_param_.ik_optional_weight_vector.length(0);
767 i_param_.ik_optional_weight_vector.length(param.
manip->numJoints());
768 std::vector<double> ov;
769 ov.resize(param.
manip->numJoints());
770 param.
manip->getOptionalWeightVector(ov);
771 for (
size_t i = 0;
i < param.
manip->numJoints();
i++) {
772 i_param_.ik_optional_weight_vector[
i] = ov[
i];
790 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found impedance controller param [" << i_name_ <<
"]" << std::endl;
817 RTC::Create<ImpedanceController>,
818 RTC::Delete<ImpedanceController>);
ComponentProfile m_profile
png_infop png_charpp int png_charpp profile
void updateRootLinkPosRot(TimedOrientation3D tmprpy)
std::map< std::string, ImpedanceParam > m_impedance_param
void readInterlockingJointsParamFromProperties(std::vector< std::pair< Link *, Link * > > &pairs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
TimedOrientation3D m_baseRpy
bool stringTo(To &val, const char *str)
#define MAX_TRANSITION_COUNT
const hrp::Vector3 & getOutputPos()
std::vector< TimedDoubleSeq > m_ref_force
png_infop png_charpp name
std::map< std::string, hrp::Vector3 > abs_ref_moments
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
std::map< std::string, hrp::Vector3 > abs_moments
void getTargetParameters()
InPort< TimedOrientation3D > m_rpyIn
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
bool startImpedanceController(const std::string &i_name_)
boost::shared_ptr< JointPathEx > JointPathExPtr
RTC::CorbaPort m_ImpedanceControllerServicePort
coil::Properties & getProperties()
InPort< TimedDoubleSeq > m_qRefIn
void resetPreviousTargetParam()
static Manager & instance()
virtual ~ImpedanceController()
bool addOutPort(const char *name, OutPortBase &outport)
hrp::dvector transition_joint_q
boost::shared_ptr< Body > BodyPtr
ImpedanceControllerService_impl m_service0
impedance control component
std::map< std::string, hrp::VirtualForceSensorParam > m_vfs
void ImpedanceControllerInit(RTC::Manager *manager)
Matrix33 rotFromRpy(const Vector3 &rpy)
std::vector< std::string > vstring
void resetPreviousCurrentParam()
hrp::Matrix33 moment_gain
coil::Properties & getConfig()
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
void rotm3times(hrp::Matrix33 &m12, const hrp::Matrix33 &m1, const hrp::Matrix33 &m2)
InPort< TimedPoint3D > m_basePosIn
void impedance(ImpedanceController *i_impedance)
ExecutionContextHandle_t UniqueId
std::map< std::string, hrp::Vector3 > abs_ref_forces
InPort< TimedDoubleSeq > m_qCurrentIn
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
def j(str, encoding="cp932")
std::vector< InPort< TimedDoubleSeq > * > m_forceIn
hrp::JointPathExPtr manip
bool stopImpedanceControllerNoWait(const std::string &i_name_)
void waitImpedanceControllerTransition(std::string i_name_)
int loadBodyFromModelLoader(::World *world, const char *name, const char *url, CosNaming::NamingContext_var cxt)
TimedDoubleSeq m_qCurrent
OutPort< TimedDoubleSeq > m_qOut
unsigned int m_debugLevel
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onFinalize()
std::vector< TimedDoubleSeq > m_force
double manipulability_limit
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
Vector3 cross(const Vector3 &v1, const Vector3 &v2)
bool startImpedanceControllerNoWait(const std::string &i_name_)
bool setImpedanceControllerParam(const std::string &i_name_, OpenHRP::ImpedanceControllerService::impedanceParam i_param_)
void registerInPort(const char *name, InPortBase &inport)
bool addPort(PortBase &port)
virtual bool write(DataType &value)
std::map< std::string, ee_trans > ee_map
static const char * impedancecontroller_spec[]
coil::Guard< coil::Mutex > Guard
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
InPort< TimedOrientation3D > m_baseRpyIn
bool addInPort(const char *name, InPortBase &inport)
const hrp::Matrix33 & getOutputRot()
void calcImpedanceControl()
ImpedanceController(RTC::Manager *manager)
void mid_rot(hrp::Matrix33 &mid_rot, const double p, const hrp::Matrix33 &rot1, const hrp::Matrix33 &rot2, const double eps)
std::vector< InPort< TimedDoubleSeq > * > m_ref_forceIn
bool getImpedanceControllerParam(const std::string &i_name_, OpenHRP::ImpedanceControllerService::impedanceParam &i_param_)
void copyImpedanceParam(OpenHRP::ImpedanceControllerService::impedanceParam &i_param_, const ImpedanceParam ¶m)
std::map< std::string, hrp::Vector3 > abs_forces
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
bool stopImpedanceController(const std::string &i_name_)
int usleep(useconds_t usec)
bool registerProvider(const char *instance_name, const char *type_name, PortableServer::RefCountServantBase &provider)
void calcTargetVelocity(hrp::Vector3 &vel_p, hrp::Vector3 &vel_r, const hrp::Matrix33 &eeR, const hrp::Vector3 &force_diff, const hrp::Vector3 &moment_diff, const double _dt, const bool printp=false, const std::string &print_str="", const std::string &ee_name="")
virtual RTC::ReturnCode_t onInitialize()