ReferenceForceUpdater.cpp
Go to the documentation of this file.
00001 // -*- C++ -*-
00010 #include <rtm/CorbaNaming.h>
00011 #include <hrpModel/Link.h>
00012 #include <hrpModel/Sensor.h>
00013 #include <hrpModel/ModelLoaderUtil.h>
00014 #include <hrpModel/JointPath.h>
00015 #include <hrpUtil/MatrixSolvers.h>
00016 #include "hrpsys/util/Hrpsys.h"
00017 #include <boost/assign.hpp>
00018 #include "ReferenceForceUpdater.h"
00019 #include "hrpsys/util/VectorConvert.h"
00020 
00021 typedef coil::Guard<coil::Mutex> Guard;
00022 
00023 // Module specification
00024 // <rtc-template block="module_spec">
00025 static const char* ReferenceForceUpdater_spec[] =
00026   {
00027     "implementation_id", "ReferenceForceUpdater",
00028     "type_name",         "ReferenceForceUpdater",
00029     "description",       "update reference force",
00030     "version",           HRPSYS_PACKAGE_VERSION,
00031     "vendor",            "AIST",
00032     "category",          "example",
00033     "activity_type",     "DataFlowComponent",
00034     "max_instance",      "10",
00035     "language",          "C++",
00036     "lang_type",         "compile",
00037     // Configuration variables
00038     "conf.default.debugLevel", "0",
00039     ""
00040   };
00041 // </rtc-template>
00042 
00043 static std::ostream& operator<<(std::ostream& os, const struct RTC::Time &tm)
00044 {
00045     int pre = os.precision();
00046     os.setf(std::ios::fixed);
00047     os << std::setprecision(6)
00048        << (tm.sec + tm.nsec/1e9)
00049        << std::setprecision(pre);
00050     os.unsetf(std::ios::fixed);
00051     return os;
00052 }
00053 
00054 ReferenceForceUpdater::ReferenceForceUpdater(RTC::Manager* manager)
00055   : RTC::DataFlowComponentBase(manager),
00056     // <rtc-template block="initializer">
00057     m_qRefIn("qRef", m_qRef),
00058     m_basePosIn("basePosIn", m_basePos),
00059     m_baseRpyIn("baseRpyIn", m_baseRpy),
00060     m_rpyIn("rpy", m_rpy),
00061     m_diffFootOriginExtMomentIn("diffFootOriginExtMoment", m_diffFootOriginExtMoment),
00062     m_refFootOriginExtMomentOut("refFootOriginExtMoment", m_refFootOriginExtMoment),
00063     m_refFootOriginExtMomentIsHoldValueOut("refFootOriginExtMomentIsHoldValue", m_refFootOriginExtMomentIsHoldValue),
00064     m_ReferenceForceUpdaterServicePort("ReferenceForceUpdaterService"),
00065     // </rtc-template>
00066     m_robot(hrp::BodyPtr()),
00067     m_debugLevel(0),
00068     use_sh_base_pos_rpy(false),
00069     footoriginextmoment_name("footoriginextmoment"),
00070     objextmoment0_name("objextmoment0")
00071 {
00072   m_ReferenceForceUpdaterService.rfu(this);
00073 }
00074 
00075 ReferenceForceUpdater::~ReferenceForceUpdater()
00076 {
00077 }
00078 
00079 
00080 
00081 RTC::ReturnCode_t ReferenceForceUpdater::onInitialize()
00082 {
00083   std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
00084   // <rtc-template block="bind_config">
00085   // Bind variables and configuration variable
00086   bindParameter("debugLevel", m_debugLevel, "0");
00087 
00088   // </rtc-template>
00089 
00090   // Registration: InPort/OutPort/Service
00091   // <rtc-template block="registration">
00092   // Set InPort buffers
00093   addInPort("qRef", m_qRefIn);
00094   addInPort("basePosIn", m_basePosIn);
00095   addInPort("baseRpyIn",m_baseRpyIn);
00096   addInPort("rpy",m_rpyIn);
00097   addInPort("diffFootOriginExtMoment", m_diffFootOriginExtMomentIn);
00098 
00099   addOutPort("refFootOriginExtMoment", m_refFootOriginExtMomentOut);
00100   addOutPort("refFootOriginExtMomentIsHoldValue", m_refFootOriginExtMomentIsHoldValueOut);
00101 
00102   // Set service provider to Ports
00103   m_ReferenceForceUpdaterServicePort.registerProvider("service0", "ReferenceForceUpdaterService", m_ReferenceForceUpdaterService);
00104 
00105   // Set service consumers to Ports
00106   // Set CORBA Service Ports
00107   addPort(m_ReferenceForceUpdaterServicePort);
00108 
00109   // Get dt
00110   RTC::Properties& prop = getProperties(); // get properties information from .wrl file
00111   coil::stringTo(m_dt, prop["dt"].c_str());
00112 
00113   // Make m_robot instance
00114   m_robot = hrp::BodyPtr(new hrp::Body());
00115   RTC::Manager& rtcManager = RTC::Manager::instance();
00116   std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
00117   int comPos = nameServer.find(",");
00118   if (comPos < 0){
00119     comPos = nameServer.length();
00120   }
00121   nameServer = nameServer.substr(0, comPos);
00122   RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
00123   if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(), // load robot model for m_robot
00124                                CosNaming::NamingContext::_duplicate(naming.getRootContext())
00125                                )){
00126     std::cerr << "[" << m_profile.instance_name << "] failed to load model[" << prop["model"] << "]" << std::endl;
00127     return RTC::RTC_ERROR;
00128   }
00129 
00130   // Setting for wrench data ports (real + virtual)
00131   std::vector<std::string> fsensor_names;
00132   //   find names for real force sensors
00133   unsigned int npforce = m_robot->numSensors(hrp::Sensor::FORCE);
00134   for (unsigned int i=0; i<npforce; i++){
00135     fsensor_names.push_back(m_robot->sensor(hrp::Sensor::FORCE, i)->name);
00136   }
00137   // load virtual force sensors
00138   readVirtualForceSensorParamFromProperties(m_vfs, m_robot, prop["virtual_force_sensor"], std::string(m_profile.instance_name));
00139   unsigned int nvforce = m_vfs.size();
00140   for (unsigned int i=0; i<nvforce; i++){
00141     for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it = m_vfs.begin(); it != m_vfs.end(); it++ ) {
00142       if (it->second.id == (int)i) fsensor_names.push_back(it->first);
00143     }
00144   }
00145 
00146   //   add ports for all force sensors (real force, input and output of ref_force)
00147   unsigned int nforce  = npforce + nvforce;
00148   m_force.resize(nforce);
00149   m_forceIn.resize(nforce);
00150   m_ref_force_in.resize(nforce);
00151   m_ref_force_out.resize(nforce);
00152   m_ref_forceIn.resize(nforce);
00153   m_ref_forceOut.resize(nforce);
00154   std::cerr << "[" << m_profile.instance_name << "] create force sensor ports" << std::endl;
00155   for (unsigned int i=0; i<nforce; i++){
00156     // actual inport
00157     m_forceIn[i] = new InPort<TimedDoubleSeq>(fsensor_names[i].c_str(), m_force[i]);
00158     m_force[i].data.length(6);
00159     registerInPort(fsensor_names[i].c_str(), *m_forceIn[i]);
00160     // ref inport
00161     m_ref_force_in[i].data.length(6);
00162     for (unsigned int j=0; j<6; j++) m_ref_force_in[i].data[j] = 0.0;
00163     m_ref_forceIn[i] = new InPort<TimedDoubleSeq>(std::string("ref_"+fsensor_names[i]+"In").c_str(), m_ref_force_in[i]);
00164     registerInPort(std::string("ref_"+fsensor_names[i]+"In").c_str(), *m_ref_forceIn[i]);
00165     std::cerr << "[" << m_profile.instance_name << "]   name = " << fsensor_names[i] << std::endl;
00166     // ref Outport
00167     m_ref_force_out[i].data.length(6);
00168     for (unsigned int j=0; j<6; j++) m_ref_force_out[i].data[j] = 0.0;
00169     m_ref_forceOut[i] = new OutPort<TimedDoubleSeq>(std::string("ref_"+fsensor_names[i]+"Out").c_str(), m_ref_force_out[i]);
00170     registerOutPort(std::string("ref_"+fsensor_names[i]+"Out").c_str(), *m_ref_forceOut[i]);
00171     std::cerr << "[" << m_profile.instance_name << "]   name = " << fsensor_names[i] << std::endl;
00172   }
00173 
00174   // setting from conf file
00175   // rleg,TARGET_LINK,BASE_LINK,x,y,z,rx,ry,rz,rth #<=pos + rot (axis+angle)
00176   coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
00177   if (end_effectors_str.size() > 0) {
00178     size_t prop_num = 10;
00179     size_t num = end_effectors_str.size()/prop_num;
00180     for (size_t i = 0; i < num; i++) {
00181       std::string ee_name, ee_target, ee_base;
00182       coil::stringTo(ee_name, end_effectors_str[i*prop_num].c_str());
00183       coil::stringTo(ee_target, end_effectors_str[i*prop_num+1].c_str());
00184       coil::stringTo(ee_base, end_effectors_str[i*prop_num+2].c_str());
00185       ee_trans eet;
00186       for (size_t j = 0; j < 3; j++) {
00187         coil::stringTo(eet.localPos(j), end_effectors_str[i*prop_num+3+j].c_str());
00188       }
00189       double tmpv[4];
00190       for (int j = 0; j < 4; j++ ) {
00191         coil::stringTo(tmpv[j], end_effectors_str[i*prop_num+6+j].c_str());
00192       }
00193       eet.localR = Eigen::AngleAxis<double>(tmpv[3], hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix(); // rotation in VRML is represented by axis + angle
00194       eet.target_name = ee_target;
00195       {
00196           bool is_ee_exists = false;
00197           for (size_t j = 0; j < nforce; j++) {
00198               hrp::Sensor* sensor = m_robot->sensor(hrp::Sensor::FORCE, j);
00199               hrp::Link* alink = m_robot->link(ee_target);
00200               while (alink != NULL && alink->name != ee_base && !is_ee_exists) {
00201                   if ( alink->name == sensor->link->name ) {
00202                       is_ee_exists = true;
00203                       eet.sensor_name = sensor->name;
00204                   }
00205                   alink = alink->parent;
00206               }
00207           }
00208       }
00209       ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
00210 
00211       if (( ee_name != "rleg" ) && ( ee_name != "lleg" ))
00212         m_RFUParam.insert(std::pair<std::string, ReferenceForceUpdaterParam>(ee_name , ReferenceForceUpdaterParam(m_dt)));
00213 
00214       ee_index_map.insert(std::pair<std::string, size_t>(ee_name, i));
00215       ref_force.push_back(hrp::Vector3::Zero());
00216       //ref_force_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(3, m_dt)));
00217       ref_force_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(3, m_dt, interpolator::LINEAR)));
00218       if (( ee_name != "lleg" ) && ( ee_name != "rleg" )) transition_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(1, m_dt)));
00219       std::cerr << "[" << m_profile.instance_name << "] End Effector [" << ee_name << "]" << ee_target << " " << ee_base << std::endl;
00220       std::cerr << "[" << m_profile.instance_name << "]   target = " << ee_target << ", base = " << ee_base << ", sensor_name = " << eet.sensor_name << std::endl;
00221       std::cerr << "[" << m_profile.instance_name << "]   localPos = " << eet.localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[m]" << std::endl;
00222       std::cerr << "[" << m_profile.instance_name << "]   localR = " << eet.localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", "    [", "]")) << std::endl;
00223     }
00224     // For FootOriginExtMoment
00225     {
00226         std::string ee_name = footoriginextmoment_name;
00227         m_RFUParam.insert(std::pair<std::string, ReferenceForceUpdaterParam>(ee_name, ReferenceForceUpdaterParam(m_dt)));
00228         // Initial param
00229         m_RFUParam[ee_name].update_freq = 1/m_dt; // [Hz], update in every control loop
00230         m_RFUParam[ee_name].update_count = 1; // update in every control loop, round((1/rfu_param.update_freq)/m_dt)
00231         m_RFUParam[ee_name].update_time_ratio = 1.0;
00232         m_RFUParam[ee_name].p_gain = 0.003;
00233         m_RFUParam[ee_name].act_force_filter->setCutOffFreq(25.0); // [Hz]
00234         ee_trans eet;
00235         eet.localPos = hrp::Vector3::Zero();
00236         eet.localR = hrp::Matrix33::Identity();
00237         eet.target_name = "";
00238         ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
00239         ee_index_map.insert(std::pair<std::string, size_t>(ee_name, ref_force.size()));
00240         ref_force.push_back(hrp::Vector3::Zero());
00241         ref_force_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(3, m_dt, interpolator::LINEAR)));
00242         transition_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(1, m_dt)));
00243     }
00244     // For ObjExtMoment0
00245     {
00246         std::string ee_name = objextmoment0_name;
00247         m_RFUParam.insert(std::pair<std::string, ReferenceForceUpdaterParam>(ee_name, ReferenceForceUpdaterParam(m_dt)));
00248         // Initial param
00249         m_RFUParam[ee_name].update_freq = 1/m_dt; // [Hz], update in every control loop
00250         m_RFUParam[ee_name].update_count = 1; // update in every control loop, round((1/rfu_param.update_freq)/m_dt)
00251         m_RFUParam[ee_name].update_time_ratio = 1.0;
00252         m_RFUParam[ee_name].act_force_filter->setCutOffFreq(20.0); // [Hz]
00253         // other param
00254         ee_trans eet;
00255         eet.localPos = hrp::Vector3::Zero();
00256         eet.localR = hrp::Matrix33::Identity();
00257         eet.target_name = "";
00258         ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
00259         ee_index_map.insert(std::pair<std::string, size_t>(ee_name, ref_force.size()));
00260         ref_force.push_back(hrp::Vector3::Zero());
00261         ref_force_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(3, m_dt, interpolator::LINEAR)));
00262         transition_interpolator.insert(std::pair<std::string, interpolator*>(ee_name, new interpolator(1, m_dt)));
00263     }
00264   }
00265 
00266   // check if the dof of m_robot match the number of joint in m_robot
00267   unsigned int dof = m_robot->numJoints();
00268   for ( unsigned int i = 0 ; i < dof; i++ ){
00269     if ( (int)i != m_robot->joint(i)->jointId ) {
00270       std::cerr << "[" << m_profile.instance_name << "] jointId is not equal to the index number" << std::endl;
00271       return RTC::RTC_ERROR;
00272     }
00273   }
00274 
00275   loop = 0;
00276   transition_interpolator_ratio.reserve(transition_interpolator.size());
00277   for (unsigned int i=0; i<transition_interpolator.size(); i++ ) transition_interpolator_ratio[i] = 0;
00278 
00279   return RTC::RTC_OK;
00280 }
00281 
00282 
00283 
00284 RTC::ReturnCode_t ReferenceForceUpdater::onFinalize()
00285 {
00286   std::cerr << "[" << m_profile.instance_name << "] onFinalize()" << std::endl;
00287   for ( std::map<std::string, interpolator*>::iterator it = ref_force_interpolator.begin(); it != ref_force_interpolator.end(); it++ ) {
00288     delete it->second;
00289   }
00290   for ( std::map<std::string, interpolator*>::iterator it = transition_interpolator.begin(); it != transition_interpolator.end(); it++ ) {
00291     delete it->second;
00292   }
00293   ref_force_interpolator.clear();
00294   transition_interpolator.clear();
00295   return RTC::RTC_OK;
00296 }
00297 
00298 /*
00299 RTC::ReturnCode_t ReferenceForceUpdater::onStartup(RTC::UniqueId ec_id)
00300 {
00301   return RTC::RTC_OK;
00302 }
00303 */
00304 
00305 /*
00306 RTC::ReturnCode_t ReferenceForceUpdater::onShutdown(RTC::UniqueId ec_id)
00307 {
00308   return RTC::RTC_OK;
00309 }
00310 */
00311 
00312 RTC::ReturnCode_t ReferenceForceUpdater::onActivated(RTC::UniqueId ec_id)
00313 {
00314   std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
00315   return RTC::RTC_OK;
00316 }
00317 
00318 RTC::ReturnCode_t ReferenceForceUpdater::onDeactivated(RTC::UniqueId ec_id)
00319 {
00320   std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
00321   return RTC::RTC_OK;
00322 }
00323 
00324 
00325 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 )
00326 RTC::ReturnCode_t ReferenceForceUpdater::onExecute(RTC::UniqueId ec_id)
00327 {
00328   loop ++;
00329 
00330   // check dataport input
00331   for (unsigned int i=0; i<m_forceIn.size(); i++){
00332     if ( m_forceIn[i]->isNew() ) {
00333       m_forceIn[i]->read();
00334     }
00335     if ( m_ref_forceIn[i]->isNew() ) {
00336       m_ref_forceIn[i]->read();
00337     }
00338   }
00339   if (m_basePosIn.isNew()) {
00340     m_basePosIn.read();
00341   }
00342   if (m_baseRpyIn.isNew()) {
00343     m_baseRpyIn.read();
00344   }
00345   if (m_rpyIn.isNew()) {
00346     m_rpyIn.read();
00347   }
00348   if (m_diffFootOriginExtMomentIn.isNew()) {
00349       m_diffFootOriginExtMomentIn.read();
00350   }
00351   if (m_qRefIn.isNew()) {
00352     m_qRefIn.read();
00353   }
00354 
00355   //syncronize m_robot to the real robot
00356   if ( m_qRef.data.length() ==  m_robot->numJoints() ) {
00357     Guard guard(m_mutex);
00358 
00359     // Interpolator
00360     for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr = m_RFUParam.begin(); itr != m_RFUParam.end(); itr++ ) {
00361       std::string arm = itr->first;
00362       size_t arm_idx = ee_index_map[arm];
00363       bool transition_interpolator_isEmpty = transition_interpolator[arm]->isEmpty();
00364       if ( ! transition_interpolator_isEmpty ) {
00365         transition_interpolator[arm]->get(&transition_interpolator_ratio[arm_idx], true);
00366         if ( transition_interpolator[arm]->isEmpty() && m_RFUParam[arm].is_active && m_RFUParam[arm].is_stopping ) {
00367           std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm << "] ReferenceForceUpdater [" << arm << "] active => inactive." << std::endl;
00368           m_RFUParam[arm].is_active = false;
00369           m_RFUParam[arm].is_stopping = false;
00370         }
00371       }
00372     }
00373 
00374     // Get and set reference (target) parameters
00375     getTargetParameters();
00376 
00377     // Get force sensor values
00378     //   Force sensor's force value is absolute in reference frame
00379     for (unsigned int i=0; i<m_force.size(); i++ ){
00380         hrp::Sensor* sensor = m_robot->sensor(hrp::Sensor::FORCE, i);
00381         hrp::Vector3 act_force = (sensor->link->R * sensor->localR) * hrp::Vector3(m_force[i].data[0], m_force[i].data[1], m_force[i].data[2]);
00382         for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr = m_RFUParam.begin(); itr != m_RFUParam.end(); itr++ ) {
00383             if (ee_index_map[itr->first] == i) itr->second.act_force_filter->passFilter(act_force);
00384         }
00385     }
00386     //   DiffFootOriginExtMoment value is absolute in reference frame
00387     {
00388         hrp::Vector3 df = foot_origin_rot * (-1 * hrp::Vector3(m_diffFootOriginExtMoment.data.x, m_diffFootOriginExtMoment.data.y, m_diffFootOriginExtMoment.data.z)); // diff = ref - act;
00389         m_RFUParam[footoriginextmoment_name].act_force_filter->passFilter(df);
00390     }
00391 
00392     // If RFU is not active
00393     {
00394       bool all_arm_is_not_active = true;
00395       const hrp::Vector3 default_ref_foot_origin_ext_moment = hrp::Vector3::Zero();
00396       for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr = m_RFUParam.begin(); itr != m_RFUParam.end(); itr++ ) {
00397         std::string arm = itr->first;
00398         size_t arm_idx = ee_index_map[arm];
00399         if ( m_RFUParam[arm].is_active ) all_arm_is_not_active = false;
00400         else {
00401             if ( arm == footoriginextmoment_name ) {
00402                 for (unsigned int j=0; j<3; j++ ) ref_force[arm_idx](j) = default_ref_foot_origin_ext_moment(j);
00403             } else if ( arm == objextmoment0_name ) {
00404                 for (unsigned int j=0; j<3; j++ ) ref_force[arm_idx](j) = 0;
00405             } else {
00406                 for (unsigned int j=0; j<3; j++ ) ref_force[arm_idx](j) = m_ref_force_in[arm_idx].data[j];
00407             }
00408         }
00409       }
00410       //determin ref_force_out from ref_force_in
00411       if ( all_arm_is_not_active ) {
00412         for (unsigned int i=0; i<m_ref_force_in.size(); i++ ){
00413           for (unsigned int j=0; j<6; j++ ) {
00414             m_ref_force_out[i].data[j] = m_ref_force_in[i].data[j];
00415           }
00416           m_ref_force_out[i].tm = m_ref_force_in[i].tm;
00417           m_ref_forceOut[i]->write();
00418         }
00419         m_refFootOriginExtMoment.data.x = default_ref_foot_origin_ext_moment(0);
00420         m_refFootOriginExtMoment.data.y = default_ref_foot_origin_ext_moment(1);
00421         m_refFootOriginExtMoment.data.z = default_ref_foot_origin_ext_moment(2);
00422         m_refFootOriginExtMoment.tm = m_qRef.tm;
00423         m_refFootOriginExtMomentOut.write();
00424         m_refFootOriginExtMomentIsHoldValue.tm = m_qRef.tm;
00425         m_refFootOriginExtMomentIsHoldValue.data = m_RFUParam[footoriginextmoment_name].is_hold_value;
00426         m_refFootOriginExtMomentIsHoldValueOut.write();
00427         return RTC::RTC_OK;
00428       }
00429     }
00430 
00431     // If RFU is active
00432 
00433     // Update reference force
00434     for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr = m_RFUParam.begin(); itr != m_RFUParam.end(); itr++ ) {
00435       std::string arm = itr->first;
00436       if ( m_RFUParam[arm].is_active && loop % m_RFUParam[arm].update_count == 0 ) {
00437           if ( arm == footoriginextmoment_name ) updateRefFootOriginExtMoment(arm);
00438           else if ( arm == objextmoment0_name ) updateRefObjExtMoment0(arm);
00439           else updateRefForces(arm);
00440       }
00441       if (!ref_force_interpolator[arm]->isEmpty()) {
00442         ref_force_interpolator[arm]->get(ref_force[ee_index_map[arm]].data(), true);
00443       }
00444     }
00445   }
00446 
00447   //determin ref_force_out from ref_force_in
00448   for (unsigned int i=0; i<m_ref_force_in.size(); i++ ){
00449     for (unsigned int j=0; j<6; j++ ) {
00450       m_ref_force_out[i].data[j] = m_ref_force_in[i].data[j];
00451     }
00452     if (m_RFUParam[objextmoment0_name].is_active) { // TODO:tempolary
00453         size_t idx = ee_index_map[objextmoment0_name];
00454         for (unsigned int j=0; j<3; j++ ) {
00455             m_ref_force_out[i].data[j] = m_ref_force_in[i].data[j];
00456             if (ee_index_map["rarm"] == i) {
00457                 m_ref_force_out[i].data[j] += ref_force[idx](j) * transition_interpolator_ratio[idx];
00458             } else if (ee_index_map["larm"] == i) {
00459                 m_ref_force_out[i].data[j] -= ref_force[idx](j) * transition_interpolator_ratio[idx];
00460             }
00461         }
00462     } else {
00463         for (unsigned int j=0; j<3; j++ ) {
00464             m_ref_force_out[i].data[j] = ref_force[i](j) * transition_interpolator_ratio[i] + m_ref_force_in[i].data[j] * (1-transition_interpolator_ratio[i]);
00465         }
00466     }
00467     m_ref_force_out[i].tm = m_ref_force_in[i].tm;
00468     m_ref_forceOut[i]->write();
00469   }
00470 
00471   // FootOriginExtMoment
00472   size_t idx = ee_index_map[footoriginextmoment_name];
00473   hrp::Vector3 tmp_moment = (foot_origin_rot.transpose() * ref_force[idx]) * transition_interpolator_ratio[idx];
00474   m_refFootOriginExtMoment.data.x = tmp_moment(0);
00475   m_refFootOriginExtMoment.data.y = tmp_moment(1);
00476   m_refFootOriginExtMoment.data.z = tmp_moment(2);
00477   m_refFootOriginExtMoment.tm = m_qRef.tm;
00478   m_refFootOriginExtMomentOut.write();
00479   m_refFootOriginExtMomentIsHoldValue.tm = m_qRef.tm;
00480   m_refFootOriginExtMomentIsHoldValue.data = m_RFUParam[footoriginextmoment_name].is_hold_value;
00481   m_refFootOriginExtMomentIsHoldValueOut.write();
00482 
00483   return RTC::RTC_OK;
00484 }
00485 
00486 void ReferenceForceUpdater::getTargetParameters ()
00487 {
00488       // reference model
00489       for ( unsigned int i = 0; i < m_robot->numJoints(); i++ ){
00490         m_robot->joint(i)->q = m_qRef.data[i];
00491       }
00492       m_robot->rootLink()->p = hrp::Vector3(m_basePos.data.x, m_basePos.data.y, m_basePos.data.z);
00493       m_robot->rootLink()->R = hrp::rotFromRpy(m_baseRpy.data.r, m_baseRpy.data.p, m_baseRpy.data.y);
00494       m_robot->calcForwardKinematics();
00495       if ( (ee_map.find("rleg") != ee_map.end() && ee_map.find("lleg") != ee_map.end()) // if legged robot
00496            && !use_sh_base_pos_rpy ) {
00497         // TODO
00498         //  Tempolarily modify root coords to fix foot pos rot
00499         //  This will be removed after seq outputs adequate waistRPY discussed in https://github.com/fkanehiro/hrpsys-base/issues/272
00500 
00501         // get current foot mid pos + rot
00502         std::vector<hrp::Vector3> foot_pos;
00503         std::vector<hrp::Matrix33> foot_rot;
00504         std::vector<std::string> leg_names;
00505         leg_names.push_back("rleg");
00506         leg_names.push_back("lleg");
00507         for (size_t i = 0; i < leg_names.size(); i++) {
00508           hrp::Link* target_link = m_robot->link(ee_map[leg_names[i]].target_name);
00509           foot_pos.push_back(target_link->p + target_link->R * ee_map[leg_names[i]].localPos);
00510           foot_rot.push_back(target_link->R * ee_map[leg_names[i]].localR);
00511         }
00512         hrp::Vector3 current_foot_mid_pos ((foot_pos[0]+foot_pos[1])/2.0);
00513         hrp::Matrix33 current_foot_mid_rot;
00514         rats::mid_rot(current_foot_mid_rot, 0.5, foot_rot[0], foot_rot[1]);
00515         // calculate fix pos + rot
00516         hrp::Vector3 new_foot_mid_pos(current_foot_mid_pos);
00517         hrp::Matrix33 new_foot_mid_rot;
00518         {
00519           hrp::Vector3 ex = hrp::Vector3::UnitX();
00520           hrp::Vector3 ez = hrp::Vector3::UnitZ();
00521           hrp::Vector3 xv1 (current_foot_mid_rot * ex);
00522           xv1(2) = 0.0;
00523           xv1.normalize();
00524           hrp::Vector3 yv1(ez.cross(xv1));
00525           new_foot_mid_rot(0,0) = xv1(0); new_foot_mid_rot(1,0) = xv1(1); new_foot_mid_rot(2,0) = xv1(2);
00526           new_foot_mid_rot(0,1) = yv1(0); new_foot_mid_rot(1,1) = yv1(1); new_foot_mid_rot(2,1) = yv1(2);
00527           new_foot_mid_rot(0,2) = ez(0); new_foot_mid_rot(1,2) = ez(1); new_foot_mid_rot(2,2) = ez(2);
00528         }
00529         // fix root pos + rot to fix "coords" = "current_foot_mid_xx"
00530         hrp::Matrix33 tmpR (new_foot_mid_rot * current_foot_mid_rot.transpose());
00531         m_robot->rootLink()->p = new_foot_mid_pos + tmpR * (m_robot->rootLink()->p - current_foot_mid_pos);
00532         rats::rotm3times(m_robot->rootLink()->R, tmpR, m_robot->rootLink()->R);
00533         m_robot->calcForwardKinematics();
00534       }
00535 
00536       hrp::Vector3 foot_origin_pos;
00537       calcFootOriginCoords(foot_origin_pos, foot_origin_rot);
00538 };
00539 
00540 void ReferenceForceUpdater::calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot)
00541 {
00542   rats::coordinates leg_c[2], tmpc;
00543   hrp::Vector3 ez = hrp::Vector3::UnitZ();
00544   hrp::Vector3 ex = hrp::Vector3::UnitX();
00545   size_t i = 0;
00546   for (std::map<std::string, ee_trans>::iterator itr = ee_map.begin(); itr != ee_map.end(); itr++ ) {
00547       if (itr->first.find("leg") == std::string::npos) continue;
00548       hrp::Link* target = m_robot->sensor<hrp::ForceSensor>(itr->second.sensor_name)->link;
00549       leg_c[i].pos = target->p;
00550       hrp::Vector3 xv1(target->R * ex);
00551       xv1(2)=0.0;
00552       xv1.normalize();
00553       hrp::Vector3 yv1(ez.cross(xv1));
00554       leg_c[i].rot(0,0) = xv1(0); leg_c[i].rot(1,0) = xv1(1); leg_c[i].rot(2,0) = xv1(2);
00555       leg_c[i].rot(0,1) = yv1(0); leg_c[i].rot(1,1) = yv1(1); leg_c[i].rot(2,1) = yv1(2);
00556       leg_c[i].rot(0,2) = ez(0); leg_c[i].rot(1,2) = ez(1); leg_c[i].rot(2,2) = ez(2);
00557       i++;
00558   }
00559   // Only double support is assumed
00560   rats::mid_coords(tmpc, 0.5, leg_c[0], leg_c[1]);
00561   foot_origin_pos = tmpc.pos;
00562   foot_origin_rot = tmpc.rot;
00563 }
00564 
00565 void ReferenceForceUpdater::updateRefFootOriginExtMoment (const std::string& arm)
00566 {
00567     double interpolation_time = 0;
00568     size_t arm_idx = ee_index_map[arm];
00569     hrp::Vector3 df = m_RFUParam[arm].act_force_filter->getCurrentValue();
00570     if (!m_RFUParam[arm].is_hold_value)
00571         ref_force[arm_idx] = ref_force[arm_idx] + (m_RFUParam[arm].p_gain * transition_interpolator_ratio[arm_idx]) * df;
00572     interpolation_time = (1/m_RFUParam[arm].update_freq) * m_RFUParam[arm].update_time_ratio;
00573     if ( ref_force_interpolator[arm]->isEmpty() ) {
00574         ref_force_interpolator[arm]->setGoal(ref_force[arm_idx].data(), interpolation_time, true);
00575     }
00576     if ( DEBUGP ) {
00577         std::cerr << "[" << m_profile.instance_name << "] Updating reference moment [" << arm << "]" << std::endl;
00578         std::cerr << "[" << m_profile.instance_name << "]   diff foot origin ext moment = " << df.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[Nm], interpolation_time = " << interpolation_time << "[s]" << std::endl;
00579         std::cerr << "[" << m_profile.instance_name << "]   new foot origin ext moment = " << ref_force[arm_idx].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[Nm]" << std::endl;
00580     }
00581 };
00582 
00583 void ReferenceForceUpdater::updateRefObjExtMoment0 (const std::string& arm)
00584 {
00585     size_t arm_idx = ee_index_map[arm];
00586     size_t rarm_idx = ee_index_map["rarm"];
00587     size_t larm_idx = ee_index_map["larm"];
00588     hrp::Vector3 input_rarm_ref_force = hrp::Vector3(m_ref_force_in[rarm_idx].data[0], m_ref_force_in[rarm_idx].data[1], m_ref_force_in[rarm_idx].data[2]);
00589     hrp::Vector3 input_larm_ref_force = hrp::Vector3(m_ref_force_in[larm_idx].data[0], m_ref_force_in[larm_idx].data[1], m_ref_force_in[larm_idx].data[2]);
00590     hrp::Vector3 current_rarm_ref_force = input_rarm_ref_force + ref_force[arm_idx];
00591     hrp::Vector3 current_larm_ref_force = input_larm_ref_force - ref_force[arm_idx];
00592     //
00593     hrp::Vector3 df = hrp::Vector3::Zero();
00594     hrp::Vector3 diff_rarm_force = (m_RFUParam["rarm"].act_force_filter->getCurrentValue() - current_rarm_ref_force);
00595     if (diff_rarm_force(2) > 0) { // r > a, tarinai
00596         df(2) += diff_rarm_force(2);
00597     }
00598     hrp::Vector3 diff_larm_force = (m_RFUParam["larm"].act_force_filter->getCurrentValue() - current_larm_ref_force);
00599     if (diff_larm_force(2) > 0) { // r > a, tarinai
00600         df(2) -= diff_larm_force(2);
00601     }
00602     if (!m_RFUParam[arm].is_hold_value) {
00603         ref_force[arm_idx] += hrp::Vector3(0,0,((m_RFUParam[arm].p_gain * transition_interpolator_ratio[arm_idx]) * df)(2));
00604     }
00605     double interpolation_time = (1/m_RFUParam[arm].update_freq) * m_RFUParam[arm].update_time_ratio;
00606     if ( ref_force_interpolator[arm]->isEmpty() ) {
00607         ref_force_interpolator[arm]->setGoal(ref_force[arm_idx].data(), interpolation_time, true);
00608     }
00609     if ( DEBUGP ) {
00610         std::cerr << "[" << m_profile.instance_name << "] Updating reference res moment [" << arm << "]" << std::endl;
00611         std::cerr << "[" << m_profile.instance_name << "]   df " << df.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[Nm], interpolation_time = " << interpolation_time << "[s]" << std::endl;
00612         std::cerr << "[" << m_profile.instance_name << "]   buffer = " << ref_force[arm_idx].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[Nm]" << std::endl;
00613         std::cerr << "[" << m_profile.instance_name << "]   diff_rarm_force  = " << diff_rarm_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00614                   << ", act_rarm_force  = " << m_RFUParam["rarm"].act_force_filter->getCurrentValue().format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00615                   << ", ref_rarm_force  = " << current_rarm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00616                   << ", input_rarm_ref_force  = " << input_rarm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00617                   << "[N]" << std::endl;
00618         std::cerr << "[" << m_profile.instance_name << "]   diff_larm_force  = " << diff_larm_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00619                   << ", act_larm_force  = " << m_RFUParam["larm"].act_force_filter->getCurrentValue().format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00620                   << ", ref_larm_force  = " << current_larm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00621                   << ", input_larm_ref_force  = " << input_larm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]"))
00622                   << "[N]" << std::endl;
00623     }
00624 };
00625 
00626 void ReferenceForceUpdater::updateRefForces (const std::string& arm)
00627 {
00628     hrp::Vector3 internal_force = hrp::Vector3::Zero();
00629     double interpolation_time = 0;
00630     size_t arm_idx = ee_index_map[arm];
00631     hrp::Link* target_link = m_robot->link(ee_map[arm].target_name);
00632     hrp::Vector3 abs_motion_dir, df;
00633     hrp::Matrix33 ee_rot;
00634     ee_rot = target_link->R * ee_map[arm].localR;
00635     if ( m_RFUParam[arm].frame=="local" )
00636         abs_motion_dir = ee_rot * m_RFUParam[arm].motion_dir;
00637     else {
00638         hrp::Matrix33 current_foot_mid_rot;
00639         std::vector<hrp::Matrix33> foot_rot;
00640         std::vector<std::string> leg_names;
00641         leg_names.push_back("rleg");
00642         leg_names.push_back("lleg");
00643         for (size_t i = 0; i < leg_names.size(); i++) {
00644             hrp::Link* target_link = m_robot->link(ee_map[leg_names[i]].target_name);
00645             foot_rot.push_back(target_link->R * ee_map[leg_names[i]].localR);
00646         }
00647         rats::mid_rot(current_foot_mid_rot, 0.5, foot_rot[0], foot_rot[1]);
00648         abs_motion_dir = current_foot_mid_rot * m_RFUParam[arm].motion_dir;
00649     }
00650     // Calc abs force diff
00651     df = m_RFUParam[arm].act_force_filter->getCurrentValue() - ref_force[arm_idx];
00652     double inner_product = 0;
00653     if ( ! std::fabs((abs_motion_dir.norm() - 0.0)) < 1e-5 ) {
00654         abs_motion_dir.normalize();
00655         inner_product = df.dot(abs_motion_dir);
00656         if ( ! (inner_product < 0 && ref_force[arm_idx].dot(abs_motion_dir) < 0.0) ) {
00657             hrp::Vector3 in_f = ee_rot * internal_force;
00658             if (!m_RFUParam[arm].is_hold_value)
00659                 ref_force[arm_idx] = ref_force[arm_idx].dot(abs_motion_dir) * abs_motion_dir + in_f + (m_RFUParam[arm].p_gain * inner_product * transition_interpolator_ratio[arm_idx]) * abs_motion_dir;
00660             interpolation_time = (1/m_RFUParam[arm].update_freq) * m_RFUParam[arm].update_time_ratio;
00661             if ( ref_force_interpolator[arm]->isEmpty() ) {
00662                 ref_force_interpolator[arm]->setGoal(ref_force[arm_idx].data(), interpolation_time, true);
00663             }
00664         }
00665     }
00666     if ( DEBUGP ) {
00667         std::cerr << "[" << m_profile.instance_name << "] Updating reference force [" << arm << "]" << std::endl;
00668         std::cerr << "[" << m_profile.instance_name << "]   inner_product = " << inner_product << "[N], ref_force = " << ref_force[arm_idx].dot(abs_motion_dir) << "[N], interpolation_time = " << interpolation_time << "[s]" << std::endl;
00669         std::cerr << "[" << m_profile.instance_name << "]   new ref_force = " << ref_force[arm_idx].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[N]" << std::endl;
00670         std::cerr << "[" << m_profile.instance_name << "]   filtered act_force = " << m_RFUParam[arm].act_force_filter->getCurrentValue().format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[N]" << std::endl;
00671         std::cerr << "[" << m_profile.instance_name << "]   df = " << df.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "    [", "]")) << "[N]" << std::endl;
00672     }
00673 };
00674 
00675 /*
00676 RTC::ReturnCode_t ReferenceForceUpdater::onAborting(RTC::UniqueId ec_id)
00677 {
00678 return RTC::RTC_OK;
00679 }
00680 */
00681 
00682 /*
00683 RTC::ReturnCode_t ReferenceForceUpdater::onError(RTC::UniqueId ec_id)
00684 {
00685   return RTC::RTC_OK;
00686 }
00687 */
00688 
00689 /*
00690 RTC::ReturnCode_t ReferenceForceUpdater::onReset(RTC::UniqueId ec_id)
00691 {
00692   return RTC::RTC_OK;
00693 }
00694 */
00695 
00696 /*
00697 RTC::ReturnCode_t ReferenceForceUpdater::onStateUpdate(RTC::UniqueId ec_id)
00698 {
00699   return RTC::RTC_OK;
00700 }
00701 */
00702 
00703 /*
00704 RTC::ReturnCode_t ReferenceForceUpdater::onRateChanged(RTC::UniqueId ec_id)
00705 {
00706   return RTC::RTC_OK;
00707 }
00708 */
00709 
00710 bool ReferenceForceUpdater::setReferenceForceUpdaterParam(const std::string& i_name_, const OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam& i_param)
00711 {
00712   std::string arm = std::string(i_name_);
00713   std::cerr << "[" << m_profile.instance_name << "] setReferenceForceUpdaterParam [" << i_name_ << "]" << std::endl;
00714   Guard guard(m_mutex);
00715   if ( m_RFUParam.find(i_name_) == m_RFUParam.end() ) {
00716     std::cerr << "[" << m_profile.instance_name << "] Could not found reference force updater param [" << i_name_ << "]" << std::endl;
00717     return false;
00718   }
00719   if ( std::string(i_param.frame) != "local" && std::string(i_param.frame) != "world" ) {
00720     std::cerr << "[" << m_profile.instance_name << "] \"frame\" parameter must be local/world. could not set \"" << std::string(i_param.frame) << "\"" <<std::endl;
00721     return false;
00722   }
00723   // Parameters which cannot be changed when active
00724   if ( m_RFUParam[arm].is_active ) { // When active, check parameter changing, and if changed, do not change the value.
00725       if ( !eps_eq(m_RFUParam[arm].update_freq, i_param.update_freq) ) {
00726           std::cerr << "[" << m_profile.instance_name << "] Could not set update_freq because rfu [" << i_name_ << "] is active (current = " << m_RFUParam[arm].update_freq << ", new = " << i_param.update_freq << ")" << std::endl;
00727           return false;
00728       } else {
00729           m_RFUParam[arm].update_freq = i_param.update_freq;
00730       }
00731       if ( !eps_eq(m_RFUParam[arm].update_time_ratio, i_param.update_time_ratio) ) {
00732           std::cerr << "[" << m_profile.instance_name << "] Could not set update_time_ratio because rfu [" << i_name_ << "] is active (current = " << m_RFUParam[arm].update_time_ratio << ", new = " << i_param.update_time_ratio << ")" << std::endl;
00733           return false;
00734       } else {
00735           m_RFUParam[arm].update_time_ratio = i_param.update_time_ratio;
00736       }
00737       if ( m_RFUParam[arm].frame != std::string(i_param.frame) ) {
00738           std::cerr << "[" << m_profile.instance_name << "] Could not set frame because rfu [" << i_name_ << "] is active (current = " << m_RFUParam[arm].frame << ", new = " << i_param.frame << ")" << std::endl;
00739           return false;
00740       } else {
00741           m_RFUParam[arm].frame = i_param.frame;
00742       }
00743   } else { // When not active, update parameters
00744       m_RFUParam[arm].update_freq = i_param.update_freq;
00745       m_RFUParam[arm].update_time_ratio = i_param.update_time_ratio;
00746       m_RFUParam[arm].update_count=round((1/m_RFUParam[arm].update_freq)/m_dt);
00747       m_RFUParam[arm].frame=std::string(i_param.frame);
00748   }
00749   // Parameters which can be changed regardless of active/inactive
00750   m_RFUParam[arm].p_gain = i_param.p_gain;
00751   m_RFUParam[arm].d_gain = i_param.d_gain;
00752   m_RFUParam[arm].i_gain = i_param.i_gain;
00753   m_RFUParam[arm].is_hold_value = i_param.is_hold_value;
00754   m_RFUParam[arm].transition_time = i_param.transition_time;
00755   m_RFUParam[arm].act_force_filter->setCutOffFreq(i_param.cutoff_freq);
00756   for (size_t i = 0; i < 3; i++ ) m_RFUParam[arm].motion_dir(i) = i_param.motion_dir[i];
00757 
00758   // Print values
00759   m_RFUParam[arm].printParam(std::string(m_profile.instance_name));
00760   return true;
00761 };
00762 
00763 bool ReferenceForceUpdater::getReferenceForceUpdaterParam(const std::string& i_name_, OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam_out i_param)
00764 {
00765   std::string arm = std::string(i_name_);
00766   std::cerr << "[" << m_profile.instance_name << "] getReferenceForceUpdaterParam [" << i_name_ << "]" << std::endl;
00767   if ( m_RFUParam.find(i_name_) == m_RFUParam.end() ) {
00768     std::cerr << "[" << m_profile.instance_name << "] Could not found reference force updater param [" << i_name_ << "]" << std::endl;
00769     return false;
00770   }
00771   Guard guard(m_mutex);
00772   i_param->p_gain = m_RFUParam[arm].p_gain;
00773   i_param->d_gain = m_RFUParam[arm].d_gain;
00774   i_param->i_gain = m_RFUParam[arm].i_gain;
00775   i_param->update_freq = m_RFUParam[arm].update_freq;
00776   i_param->update_time_ratio = m_RFUParam[arm].update_time_ratio;
00777   i_param->frame = m_RFUParam[arm].frame.c_str();
00778   i_param->is_hold_value = m_RFUParam[arm].is_hold_value;
00779   i_param->transition_time = m_RFUParam[arm].transition_time;
00780   i_param->cutoff_freq = m_RFUParam[arm].act_force_filter->getCutOffFreq();
00781   for (size_t i = 0; i < 3; i++ ) i_param->motion_dir[i] = m_RFUParam[arm].motion_dir(i);
00782   return true;
00783 };
00784 
00785 bool ReferenceForceUpdater::startReferenceForceUpdaterNoWait(const std::string& i_name_)
00786 {
00787   std::cerr << "[" << m_profile.instance_name << "] startReferenceForceUpdater [" << i_name_ << "]" << std::endl;
00788   {
00789     Guard guard(m_mutex);
00790     if ( m_RFUParam.find(i_name_) == m_RFUParam.end() ) {
00791       std::cerr << "[" << m_profile.instance_name << "] Could not found reference force updater param [" << i_name_ << "]" << std::endl;
00792       return false;
00793     }
00794     if ( m_RFUParam[i_name_].is_active == true )
00795       return true;
00796     if (transition_interpolator[i_name_]->isEmpty()) {
00797       m_RFUParam[i_name_].is_active = true;
00798       double tmpstart = 0.0, tmpgoal = 1.0;
00799       size_t arm_idx = ee_index_map[i_name_];
00800       hrp::Vector3 currentRefForce;
00801       if ( std::string(i_name_) == footoriginextmoment_name ) {
00802           currentRefForce = hrp::Vector3 (m_diffFootOriginExtMoment.data.x, m_diffFootOriginExtMoment.data.y, m_diffFootOriginExtMoment.data.z);
00803       } else if ( std::string(i_name_) == objextmoment0_name ) {
00804           currentRefForce = hrp::Vector3::Zero();
00805       } else {
00806           currentRefForce = hrp::Vector3( m_ref_force_in[arm_idx].data[0], m_ref_force_in[arm_idx].data[1], m_ref_force_in[arm_idx].data[2] );
00807       }
00808       ref_force_interpolator[i_name_]->set(currentRefForce.data());
00809       transition_interpolator[i_name_]->set(&tmpstart);
00810       transition_interpolator[i_name_]->setGoal(&tmpgoal, m_RFUParam[i_name_].transition_time, true);
00811     } else {
00812       return false;
00813     }
00814   }
00815   return true;
00816 };
00817 
00818 bool ReferenceForceUpdater::stopReferenceForceUpdaterNoWait(const std::string& i_name_)
00819 {
00820   std::cerr << "[" << m_profile.instance_name << "] stopReferenceForceUpdater [" << i_name_ << "]" << std::endl;
00821   {
00822     Guard guard(m_mutex);
00823     if ( m_RFUParam.find(i_name_) == m_RFUParam.end() ) {
00824       std::cerr << "[" << m_profile.instance_name << "] Could not found reference force updater param [" << i_name_ << "]" << std::endl;
00825       return false;
00826     }
00827     if ( m_RFUParam[i_name_].is_active == false ){//already not active
00828       return true;
00829     }
00830     double tmpstart = 1.0, tmpgoal = 0.0;
00831     transition_interpolator[i_name_]->set(&tmpstart);
00832     transition_interpolator[i_name_]->setGoal(&tmpgoal, m_RFUParam[i_name_].transition_time, true);
00833     m_RFUParam[i_name_].is_stopping = true;
00834   }
00835   return true;
00836 };
00837 
00838 bool ReferenceForceUpdater::startReferenceForceUpdater(const std::string& i_name_)
00839 {
00840     bool ret = startReferenceForceUpdaterNoWait(i_name_);
00841     if (ret) waitReferenceForceUpdaterTransition(i_name_);
00842     return ret;
00843 };
00844 
00845 bool ReferenceForceUpdater::stopReferenceForceUpdater(const std::string& i_name_)
00846 {
00847     bool ret = stopReferenceForceUpdaterNoWait(i_name_);
00848     if (ret) waitReferenceForceUpdaterTransition(i_name_);
00849     return ret;
00850 };
00851 
00852 void ReferenceForceUpdater::waitReferenceForceUpdaterTransition(const std::string& i_name_)
00853 {
00854     while (!transition_interpolator[i_name_]->isEmpty()) usleep(1000);
00855     usleep(1000);
00856 };
00857 
00858 bool ReferenceForceUpdater::getSupportedReferenceForceUpdaterNameSequence(OpenHRP::ReferenceForceUpdaterService::StrSequence_out o_names)
00859 {
00860   std::cerr << "[" << m_profile.instance_name << "] getSupportedReferenceForceUpdaterNameSequence" << std::endl;
00861   Guard guard(m_mutex);
00862   o_names->length(m_RFUParam.size());
00863   size_t i = 0;
00864   for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr = m_RFUParam.begin(); itr != m_RFUParam.end(); itr++ ) {
00865       o_names[i] = itr->first.c_str();
00866       i++;
00867   }
00868   return true;
00869 };
00870 
00871 extern "C"
00872 {
00873 
00874   void ReferenceForceUpdaterInit(RTC::Manager* manager)
00875   {
00876     RTC::Properties profile(ReferenceForceUpdater_spec);
00877     manager->registerFactory(profile,
00878                              RTC::Create<ReferenceForceUpdater>,
00879                              RTC::Delete<ReferenceForceUpdater>);
00880   }
00881 
00882 };


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