12 #include <hrpModel/Sensor.h> 13 #include <hrpModel/ModelLoaderUtil.h> 16 #include "hrpsys/util/Hrpsys.h" 17 #include <boost/assign.hpp> 19 #include "hrpsys/util/VectorConvert.h" 27 "implementation_id",
"ReferenceForceUpdater",
28 "type_name",
"ReferenceForceUpdater",
29 "description",
"update reference force",
30 "version", HRPSYS_PACKAGE_VERSION,
32 "category",
"example",
33 "activity_type",
"DataFlowComponent",
36 "lang_type",
"compile",
38 "conf.default.debugLevel",
"0",
43 static std::ostream&
operator<<(std::ostream& os,
const struct RTC::Time &tm)
45 int pre = os.precision();
46 os.setf(std::ios::fixed);
47 os << std::setprecision(6)
48 << (tm.sec + tm.nsec/1e9)
49 << std::setprecision(pre);
50 os.unsetf(std::ios::fixed);
57 m_qRefIn(
"qRef", m_qRef),
58 m_basePosIn(
"basePosIn", m_basePos),
59 m_baseRpyIn(
"baseRpyIn", m_baseRpy),
60 m_rpyIn(
"rpy", m_rpy),
61 m_diffFootOriginExtMomentIn(
"diffFootOriginExtMoment", m_diffFootOriginExtMoment),
62 m_refFootOriginExtMomentOut(
"refFootOriginExtMoment", m_refFootOriginExtMoment),
63 m_refFootOriginExtMomentIsHoldValueOut(
"refFootOriginExtMomentIsHoldValue", m_refFootOriginExtMomentIsHoldValue),
64 m_ReferenceForceUpdaterServicePort(
"ReferenceForceUpdaterService"),
68 use_sh_base_pos_rpy(false),
69 footoriginextmoment_name(
"footoriginextmoment"),
70 objextmoment0_name(
"objextmoment0")
83 std::cerr <<
"[" <<
m_profile.instance_name <<
"] onInitialize()" << std::endl;
116 std::string nameServer = rtcManager.
getConfig()[
"corba.nameservers"];
117 int comPos = nameServer.find(
",");
119 comPos = nameServer.length();
121 nameServer = nameServer.substr(0, comPos);
124 CosNaming::NamingContext::_duplicate(
naming.getRootContext())
126 std::cerr <<
"[" <<
m_profile.instance_name <<
"] failed to load model[" << prop[
"model"] <<
"]" << std::endl;
127 return RTC::RTC_ERROR;
131 std::vector<std::string> fsensor_names;
134 for (
unsigned int i=0;
i<npforce;
i++){
139 unsigned int nvforce =
m_vfs.size();
140 for (
unsigned int i=0;
i<nvforce;
i++){
141 for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it =
m_vfs.begin(); it !=
m_vfs.end(); it++ ) {
142 if (it->second.id == (
int)
i) fsensor_names.push_back(it->first);
147 unsigned int nforce = npforce + nvforce;
154 std::cerr <<
"[" <<
m_profile.instance_name <<
"] create force sensor ports" << std::endl;
155 for (
unsigned int i=0;
i<nforce;
i++){
165 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << fsensor_names[i] << std::endl;
171 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << fsensor_names[i] << std::endl;
177 if (end_effectors_str.size() > 0) {
178 size_t prop_num = 10;
179 size_t num = end_effectors_str.size()/prop_num;
180 for (
size_t i = 0;
i < num;
i++) {
181 std::string ee_name, ee_target, ee_base;
186 for (
size_t j = 0;
j < 3;
j++) {
190 for (
int j = 0;
j < 4;
j++ ) {
193 eet.
localR = Eigen::AngleAxis<double>(tmpv[3],
hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix();
196 bool is_ee_exists =
false;
197 for (
size_t j = 0;
j < nforce;
j++) {
200 while (alink != NULL && alink->
name != ee_base && !is_ee_exists) {
209 ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
211 if (( ee_name !=
"rleg" ) && ( ee_name !=
"lleg" ))
214 ee_index_map.insert(std::pair<std::string, size_t>(ee_name,
i));
215 ref_force.push_back(hrp::Vector3::Zero());
219 std::cerr <<
"[" <<
m_profile.instance_name <<
"] End Effector [" << ee_name <<
"]" << ee_target <<
" " << ee_base << std::endl;
220 std::cerr <<
"[" <<
m_profile.instance_name <<
"] target = " << ee_target <<
", base = " << ee_base <<
", sensor_name = " << eet.
sensor_name << std::endl;
221 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localPos = " << eet.
localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
222 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localR = " << eet.
localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
233 m_RFUParam[ee_name].act_force_filter->setCutOffFreq(25.0);
235 eet.
localPos = hrp::Vector3::Zero();
236 eet.
localR = hrp::Matrix33::Identity();
238 ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
240 ref_force.push_back(hrp::Vector3::Zero());
252 m_RFUParam[ee_name].act_force_filter->setCutOffFreq(20.0);
255 eet.
localPos = hrp::Vector3::Zero();
256 eet.
localR = hrp::Matrix33::Identity();
258 ee_map.insert(std::pair<std::string, ee_trans>(ee_name , eet));
260 ref_force.push_back(hrp::Vector3::Zero());
267 unsigned int dof =
m_robot->numJoints();
268 for (
unsigned int i = 0 ;
i < dof;
i++ ){
269 if ( (
int)
i !=
m_robot->joint(
i)->jointId ) {
270 std::cerr <<
"[" <<
m_profile.instance_name <<
"] jointId is not equal to the index number" << std::endl;
271 return RTC::RTC_ERROR;
286 std::cerr <<
"[" <<
m_profile.instance_name <<
"] onFinalize()" << std::endl;
314 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onActivated(" << ec_id <<
")" << std::endl;
320 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onDeactivated(" << ec_id <<
")" << std::endl;
325 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 ) 360 for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr =
m_RFUParam.begin(); itr !=
m_RFUParam.end(); itr++ ) {
361 std::string arm = itr->first;
364 if ( ! transition_interpolator_isEmpty ) {
367 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
m_qRef.tm <<
"] ReferenceForceUpdater [" << arm <<
"] active => inactive." << std::endl;
379 for (
unsigned int i=0;
i<
m_force.size();
i++ ){
382 for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr =
m_RFUParam.begin(); itr !=
m_RFUParam.end(); itr++ ) {
383 if (
ee_index_map[itr->first] ==
i) itr->second.act_force_filter->passFilter(act_force);
394 bool all_arm_is_not_active =
true;
395 const hrp::Vector3 default_ref_foot_origin_ext_moment = hrp::Vector3::Zero();
396 for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr =
m_RFUParam.begin(); itr !=
m_RFUParam.end(); itr++ ) {
397 std::string arm = itr->first;
399 if (
m_RFUParam[arm].is_active ) all_arm_is_not_active =
false;
402 for (
unsigned int j=0;
j<3;
j++ )
ref_force[arm_idx](
j) = default_ref_foot_origin_ext_moment(
j);
411 if ( all_arm_is_not_active ) {
413 for (
unsigned int j=0;
j<6;
j++ ) {
434 for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr =
m_RFUParam.begin(); itr !=
m_RFUParam.end(); itr++ ) {
435 std::string arm = itr->first;
449 for (
unsigned int j=0;
j<6;
j++ ) {
454 for (
unsigned int j=0;
j<3;
j++ ) {
463 for (
unsigned int j=0;
j<3;
j++ ) {
489 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ){
494 m_robot->calcForwardKinematics();
502 std::vector<hrp::Vector3> foot_pos;
503 std::vector<hrp::Matrix33> foot_rot;
504 std::vector<std::string> leg_names;
505 leg_names.push_back(
"rleg");
506 leg_names.push_back(
"lleg");
507 for (
size_t i = 0;
i < leg_names.size();
i++) {
509 foot_pos.push_back(target_link->
p + target_link->
R *
ee_map[leg_names[
i]].localPos);
510 foot_rot.push_back(target_link->
R *
ee_map[leg_names[i]].localR);
512 hrp::Vector3 current_foot_mid_pos ((foot_pos[0]+foot_pos[1])/2.0);
514 rats::mid_rot(current_foot_mid_rot, 0.5, foot_rot[0], foot_rot[1]);
525 new_foot_mid_rot(0,0) = xv1(0); new_foot_mid_rot(1,0) = xv1(1); new_foot_mid_rot(2,0) = xv1(2);
526 new_foot_mid_rot(0,1) = yv1(0); new_foot_mid_rot(1,1) = yv1(1); new_foot_mid_rot(2,1) = yv1(2);
527 new_foot_mid_rot(0,2) = ez(0); new_foot_mid_rot(1,2) = ez(1); new_foot_mid_rot(2,2) = ez(2);
530 hrp::Matrix33 tmpR (new_foot_mid_rot * current_foot_mid_rot.transpose());
531 m_robot->rootLink()->p = new_foot_mid_pos + tmpR * (
m_robot->rootLink()->p - current_foot_mid_pos);
533 m_robot->calcForwardKinematics();
546 for (std::map<std::string, ee_trans>::iterator itr =
ee_map.begin(); itr !=
ee_map.end(); itr++ ) {
547 if (itr->first.find(
"leg") == std::string::npos)
continue;
549 leg_c[i].
pos = target->
p;
554 leg_c[i].
rot(0,0) = xv1(0); leg_c[i].
rot(1,0) = xv1(1); leg_c[i].
rot(2,0) = xv1(2);
555 leg_c[i].
rot(0,1) = yv1(0); leg_c[i].
rot(1,1) = yv1(1); leg_c[i].
rot(2,1) = yv1(2);
556 leg_c[i].
rot(0,2) = ez(0); leg_c[i].
rot(1,2) = ez(1); leg_c[i].
rot(2,2) = ez(2);
561 foot_origin_pos = tmpc.
pos;
562 foot_origin_rot = tmpc.
rot;
567 double interpolation_time = 0;
577 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Updating reference moment [" << arm <<
"]" << std::endl;
578 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;
579 std::cerr <<
"[" <<
m_profile.instance_name <<
"] new foot origin ext moment = " <<
ref_force[arm_idx].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[Nm]" << std::endl;
591 hrp::Vector3 current_larm_ref_force = input_larm_ref_force - ref_force[arm_idx];
594 hrp::Vector3 diff_rarm_force = (
m_RFUParam[
"rarm"].act_force_filter->getCurrentValue() - current_rarm_ref_force);
595 if (diff_rarm_force(2) > 0) {
596 df(2) += diff_rarm_force(2);
598 hrp::Vector3 diff_larm_force = (
m_RFUParam[
"larm"].act_force_filter->getCurrentValue() - current_larm_ref_force);
599 if (diff_larm_force(2) > 0) {
600 df(2) -= diff_larm_force(2);
605 double interpolation_time = (1/
m_RFUParam[arm].update_freq) *
m_RFUParam[arm].update_time_ratio;
610 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Updating reference res moment [" << arm <<
"]" << std::endl;
611 std::cerr <<
"[" <<
m_profile.instance_name <<
"] df " << df.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[Nm], interpolation_time = " << interpolation_time <<
"[s]" << std::endl;
612 std::cerr <<
"[" <<
m_profile.instance_name <<
"] buffer = " << ref_force[arm_idx].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[Nm]" << std::endl;
613 std::cerr <<
"[" <<
m_profile.instance_name <<
"] diff_rarm_force = " << diff_rarm_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
614 <<
", act_rarm_force = " <<
m_RFUParam[
"rarm"].act_force_filter->getCurrentValue().format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
615 <<
", ref_rarm_force = " << current_rarm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
616 <<
", input_rarm_ref_force = " << input_rarm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
617 <<
"[N]" << std::endl;
618 std::cerr <<
"[" <<
m_profile.instance_name <<
"] diff_larm_force = " << diff_larm_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
619 <<
", act_larm_force = " <<
m_RFUParam[
"larm"].act_force_filter->getCurrentValue().format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
620 <<
", ref_larm_force = " << current_larm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
621 <<
", input_larm_ref_force = " << input_larm_ref_force.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
622 <<
"[N]" << std::endl;
629 double interpolation_time = 0;
634 ee_rot = target_link->
R *
ee_map[arm].localR;
636 abs_motion_dir = ee_rot *
m_RFUParam[arm].motion_dir;
639 std::vector<hrp::Matrix33> foot_rot;
640 std::vector<std::string> leg_names;
641 leg_names.push_back(
"rleg");
642 leg_names.push_back(
"lleg");
643 for (
size_t i = 0;
i < leg_names.size();
i++) {
645 foot_rot.push_back(target_link->
R *
ee_map[leg_names[
i]].localR);
647 rats::mid_rot(current_foot_mid_rot, 0.5, foot_rot[0], foot_rot[1]);
648 abs_motion_dir = current_foot_mid_rot *
m_RFUParam[arm].motion_dir;
652 double inner_product = 0;
653 if ( ! std::fabs((abs_motion_dir.norm() - 0.0)) < 1e-5 ) {
654 abs_motion_dir.normalize();
655 inner_product = df.dot(abs_motion_dir);
656 if ( ! (inner_product < 0 &&
ref_force[arm_idx].
dot(abs_motion_dir) < 0.0) ) {
667 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Updating reference force [" << arm <<
"]" << std::endl;
668 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;
669 std::cerr <<
"[" <<
m_profile.instance_name <<
"] new ref_force = " <<
ref_force[arm_idx].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[N]" << std::endl;
670 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;
671 std::cerr <<
"[" <<
m_profile.instance_name <<
"] df = " << df.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[N]" << std::endl;
712 std::string arm = std::string(i_name_);
713 std::cerr <<
"[" <<
m_profile.instance_name <<
"] setReferenceForceUpdaterParam [" << i_name_ <<
"]" << std::endl;
716 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found reference force updater param [" << i_name_ <<
"]" << std::endl;
719 if ( std::string(i_param.frame) !=
"local" && std::string(i_param.frame) !=
"world" ) {
720 std::cerr <<
"[" <<
m_profile.instance_name <<
"] \"frame\" parameter must be local/world. could not set \"" << std::string(i_param.frame) <<
"\"" <<std::endl;
726 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;
729 m_RFUParam[arm].update_freq = i_param.update_freq;
731 if ( !
eps_eq(
m_RFUParam[arm].update_time_ratio, i_param.update_time_ratio) ) {
732 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;
735 m_RFUParam[arm].update_time_ratio = i_param.update_time_ratio;
738 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;
744 m_RFUParam[arm].update_freq = i_param.update_freq;
745 m_RFUParam[arm].update_time_ratio = i_param.update_time_ratio;
747 m_RFUParam[arm].frame=std::string(i_param.frame);
753 m_RFUParam[arm].is_hold_value = i_param.is_hold_value;
754 m_RFUParam[arm].transition_time = i_param.transition_time;
755 m_RFUParam[arm].act_force_filter->setCutOffFreq(i_param.cutoff_freq);
756 for (
size_t i = 0;
i < 3;
i++ )
m_RFUParam[arm].motion_dir(
i) = i_param.motion_dir[
i];
765 std::string arm = std::string(i_name_);
766 std::cerr <<
"[" <<
m_profile.instance_name <<
"] getReferenceForceUpdaterParam [" << i_name_ <<
"]" << std::endl;
768 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found reference force updater param [" << i_name_ <<
"]" << std::endl;
775 i_param->update_freq =
m_RFUParam[arm].update_freq;
776 i_param->update_time_ratio =
m_RFUParam[arm].update_time_ratio;
777 i_param->frame =
m_RFUParam[arm].frame.c_str();
778 i_param->is_hold_value =
m_RFUParam[arm].is_hold_value;
779 i_param->transition_time =
m_RFUParam[arm].transition_time;
780 i_param->cutoff_freq =
m_RFUParam[arm].act_force_filter->getCutOffFreq();
781 for (
size_t i = 0;
i < 3;
i++ ) i_param->motion_dir[
i] =
m_RFUParam[arm].motion_dir(
i);
787 std::cerr <<
"[" <<
m_profile.instance_name <<
"] startReferenceForceUpdater [" << i_name_ <<
"]" << std::endl;
791 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found reference force updater param [" << i_name_ <<
"]" << std::endl;
798 double tmpstart = 0.0, tmpgoal = 1.0;
804 currentRefForce = hrp::Vector3::Zero();
820 std::cerr <<
"[" <<
m_profile.instance_name <<
"] stopReferenceForceUpdater [" << i_name_ <<
"]" << std::endl;
824 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Could not found reference force updater param [" << i_name_ <<
"]" << std::endl;
827 if (
m_RFUParam[i_name_].is_active ==
false ){
830 double tmpstart = 1.0, tmpgoal = 0.0;
860 std::cerr <<
"[" <<
m_profile.instance_name <<
"] getSupportedReferenceForceUpdaterNameSequence" << std::endl;
864 for (std::map<std::string, ReferenceForceUpdaterParam>::iterator itr =
m_RFUParam.begin(); itr !=
m_RFUParam.end(); itr++ ) {
865 o_names[i] = itr->first.c_str();
878 RTC::Create<ReferenceForceUpdater>,
879 RTC::Delete<ReferenceForceUpdater>);
ComponentProfile m_profile
png_infop png_charpp int png_charpp profile
std::map< std::string, hrp::VirtualForceSensorParam > m_vfs
bool stopReferenceForceUpdaterNoWait(const std::string &i_name_)
unsigned int m_debugLevel
InPort< TimedOrientation3D > m_baseRpyIn
OutPort< TimedPoint3D > m_refFootOriginExtMomentOut
const std::string objextmoment0_name
bool stringTo(To &val, const char *str)
void calcFootOriginCoords(hrp::Vector3 &foot_origin_pos, hrp::Matrix33 &foot_origin_rot)
InPort< TimedOrientation3D > m_rpyIn
coil::Guard< coil::Mutex > Guard
InPort< TimedPoint3D > m_diffFootOriginExtMomentIn
TimedOrientation3D m_baseRpy
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
std::map< std::string, ee_trans > ee_map
ReferenceForceUpdater(RTC::Manager *manager)
Constructor.
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
InPort< TimedPoint3D > m_basePosIn
void waitReferenceForceUpdaterTransition(const std::string &i_name_)
std::vector< TimedDoubleSeq > m_ref_force_out
ReferenceForceUpdaterService_impl m_ReferenceForceUpdaterService
coil::Properties & getProperties()
static Manager & instance()
TimedBoolean m_refFootOriginExtMomentIsHoldValue
bool addOutPort(const char *name, OutPortBase &outport)
bool stopReferenceForceUpdater(const std::string &i_name_)
boost::shared_ptr< Body > BodyPtr
std::vector< InPort< TimedDoubleSeq > * > m_ref_forceIn
virtual ~ReferenceForceUpdater()
Destructor.
void ReferenceForceUpdaterInit(RTC::Manager *manager)
Matrix33 rotFromRpy(const Vector3 &rpy)
std::vector< std::string > vstring
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
coil::Properties & getConfig()
void rotm3times(hrp::Matrix33 &m12, const hrp::Matrix33 &m1, const hrp::Matrix33 &m2)
ExecutionContextHandle_t UniqueId
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
def j(str, encoding="cp932")
bool startReferenceForceUpdaterNoWait(const std::string &i_name_)
std::map< std::string, size_t > ee_index_map
std::map< std::string, interpolator * > ref_force_interpolator
bool getReferenceForceUpdaterParam(const std::string &i_name_, OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam_out i_param)
hrp::Matrix33 foot_origin_rot
int loadBodyFromModelLoader(::World *world, const char *name, const char *url, CosNaming::NamingContext_var cxt)
std::vector< TimedDoubleSeq > m_force
std::vector< TimedDoubleSeq > m_ref_force_in
bool getSupportedReferenceForceUpdaterNameSequence(OpenHRP::ReferenceForceUpdaterService::StrSequence_out o_names)
void rfu(ReferenceForceUpdater *i_rfu)
std::vector< InPort< TimedDoubleSeq > * > m_forceIn
RTC::CorbaPort m_ReferenceForceUpdaterServicePort
bool startReferenceForceUpdater(const std::string &i_name_)
static std::ostream & operator<<(std::ostream &os, const struct RTC::Time &tm)
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
double dot(const Vector3 &v1, const Vector3 &v2)
InPort< TimedDoubleSeq > m_qRefIn
bool eps_eq(const double a, const double b, const double eps=1e-3)
bool setReferenceForceUpdaterParam(const std::string &i_name_, const OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam &i_param)
TimedPoint3D m_diffFootOriginExtMoment
void registerInPort(const char *name, InPortBase &inport)
bool addPort(PortBase &port)
virtual bool write(DataType &value)
TimedPoint3D m_refFootOriginExtMoment
OutPort< TimedBoolean > m_refFootOriginExtMomentIsHoldValueOut
void getTargetParameters()
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
std::vector< OutPort< TimedDoubleSeq > * > m_ref_forceOut
std::vector< double > transition_interpolator_ratio
void updateRefForces(const std::string &arm)
bool addInPort(const char *name, InPortBase &inport)
virtual RTC::ReturnCode_t onInitialize()
void mid_rot(hrp::Matrix33 &mid_rot, const double p, const hrp::Matrix33 &rot1, const hrp::Matrix33 &rot2, const double eps)
void registerOutPort(const char *name, OutPortBase &outport)
void updateRefObjExtMoment0(const std::string &arm)
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
std::vector< hrp::Vector3 > ref_force
const std::string footoriginextmoment_name
std::map< std::string, ReferenceForceUpdaterParam > m_RFUParam
std::map< std::string, interpolator * > transition_interpolator
virtual RTC::ReturnCode_t onFinalize()
void updateRefFootOriginExtMoment(const std::string &arm)
static const char * ReferenceForceUpdater_spec[]
void mid_coords(coordinates &mid_coords, const double p, const coordinates &c1, const coordinates &c2, const double eps)
int usleep(useconds_t usec)
bool registerProvider(const char *instance_name, const char *type_name, PortableServer::RefCountServantBase &provider)
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)