diff --git a/CMakeLists.txt b/CMakeLists.txt index 0cb1c196f6..08b2836389 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,7 +15,7 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON) option(ICUB_COMPILE_BINDINGS "Compile optional language bindings" FALSE) set(YCM_REQUIRED_VERSION 0.13.0) -set(YARP_REQUIRED_VERSION 3.3.2) +set(YARP_REQUIRED_VERSION 3.5.1) find_package(YCM ${YCM_REQUIRED_VERSION} REQUIRED) find_package(YARP ${YARP_REQUIRED_VERSION} REQUIRED) diff --git a/src/core/emotionInterface/emotionInterface.h b/src/core/emotionInterface/emotionInterface.h index c9ff875b4c..e0efad92cf 100644 --- a/src/core/emotionInterface/emotionInterface.h +++ b/src/core/emotionInterface/emotionInterface.h @@ -39,28 +39,28 @@ class iCub::contrib::IEmotionInterface }; -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_SET = yarp::os::createVocab('s','e','t'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_GET = yarp::os::createVocab('g','e','t'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_IS = yarp::os::createVocab('i','s'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_FAILED = yarp::os::createVocab('f','a','i','l'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_OK = yarp::os::createVocab('o','k'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_HELP = yarp::os::createVocab('h','e','l','p'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_SET = yarp::os::createVocab32('s','e','t'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_GET = yarp::os::createVocab32('g','e','t'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_IS = yarp::os::createVocab32('i','s'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_FAILED = yarp::os::createVocab32('f','a','i','l'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_OK = yarp::os::createVocab32('o','k'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_HELP = yarp::os::createVocab32('h','e','l','p'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_MOUTH = yarp::os::createVocab('m','o','u'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_EYELIDS = yarp::os::createVocab('e','l','i'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_LEFTEYEBROW = yarp::os::createVocab('l','e','b'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_RIGHTEYEBROW = yarp::os::createVocab('r','e','b'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_ALL = yarp::os::createVocab('a','l','l'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_RAW = yarp::os::createVocab('r','a','w'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_COLOR = yarp::os::createVocab('c','o','l'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_BRIG = yarp::os::createVocab('b','r','i','g'); -constexpr yarp::conf::vocab32_t EMOTION_VOCAB_MASK = yarp::os::createVocab('m','a','s','k'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_MOUTH = yarp::os::createVocab32('m','o','u'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_EYELIDS = yarp::os::createVocab32('e','l','i'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_LEFTEYEBROW = yarp::os::createVocab32('l','e','b'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_RIGHTEYEBROW = yarp::os::createVocab32('r','e','b'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_ALL = yarp::os::createVocab32('a','l','l'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_RAW = yarp::os::createVocab32('r','a','w'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_COLOR = yarp::os::createVocab32('c','o','l'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_BRIG = yarp::os::createVocab32('b','r','i','g'); +constexpr yarp::conf::vocab32_t EMOTION_VOCAB_MASK = yarp::os::createVocab32('m','a','s','k'); inline bool EMOTION_CHECK_FAIL(bool ok, yarp::os::Bottle& response) { if (ok) { - if (response.get(0).isVocab() && response.get(0).asVocab() == EMOTION_VOCAB_FAILED) { + if (response.get(0).isVocab32() && response.get(0).asVocab32() == EMOTION_VOCAB_FAILED) { return false; } } diff --git a/src/core/emotionInterface/emotionInterfaceModule.cpp b/src/core/emotionInterface/emotionInterfaceModule.cpp index 9bf227647b..a1ac3cd14c 100644 --- a/src/core/emotionInterface/emotionInterfaceModule.cpp +++ b/src/core/emotionInterface/emotionInterfaceModule.cpp @@ -6,6 +6,7 @@ * */ +#include #include #include #include @@ -25,7 +26,7 @@ std::bitset<32> populateBitset(const yarp::os::Bottle& bt) { std::bitset<32> bitSet{}; for(size_t i=0; igetInfo(info); - double hwver=info.find("arm_version").asDouble(); + double hwver=info.find("arm_version").asFloat64(); map remap{{ACTIONPRIM_TORSO_PITCH,0},{ACTIONPRIM_TORSO_ROLL,1},{ACTIONPRIM_TORSO_YAW,2}}; if (hwver>=3.0) { @@ -432,8 +432,8 @@ bool ActionPrimitives::handleTorsoDOF(Property &opt, const string &key) cartCtrl->getLimits(j,&min,&max); - min=opt.check(minKey,Value(min)).asDouble(); - max=opt.check(maxKey,Value(max)).asDouble(); + min=opt.check(minKey,Value(min)).asFloat64(); + max=opt.check(maxKey,Value(max)).asFloat64(); cartCtrl->setLimits(j,min,max); cartCtrl->getLimits(j,&min,&max); @@ -485,7 +485,7 @@ bool ActionPrimitives::configHandSeq(Property &opt) return false; } - int numSequences=bGeneral.find("numSequences").asInt(); + int numSequences=bGeneral.find("numSequences").asInt32(); // SEQUENCE groups for (int i=0; iget(fng).asDouble(); + double val=pB->get(fng).asFloat64(); double thres=curGraspDetectionThres[fng]; // detect contact on the finger @@ -1562,7 +1562,7 @@ bool ActionPrimitives::addHandSequence(const string &handSeqKey, const Bottle &s return false; } - int numWayPoints=sequence.find("numWayPoints").asInt(); + int numWayPoints=sequence.find("numWayPoints").asInt32(); bool ret=false; for (int j=0; jsize()); for (size_t k=0; kget(k).asDouble(); + poss[k]=bPoss->get(k).asFloat64(); Bottle *bVels=bWP.find("vels").asList(); Vector vels(bVels->size()); for (size_t k=0; kget(k).asDouble(); + vels[k]=bVels->get(k).asFloat64(); Bottle *bTols=bWP.find("tols").asList(); Vector tols(bTols->size()); for (size_t k=0; kget(k).asDouble(); + tols[k]=bTols->get(k).asFloat64(); Bottle *bThres=bWP.find("thres").asList(); Vector thres(bThres->size()); for (size_t k=0; kget(k).asDouble(); + thres[k]=bThres->get(k).asFloat64(); - double tmo=bWP.find("tmo").asDouble(); + double tmo=bWP.find("tmo").asFloat64(); if (addHandSeqWP(handSeqKey,poss,vels,tols,thres,tmo)) ret=true; // at least one WP has been added @@ -1695,7 +1695,7 @@ bool ActionPrimitives::getHandSequence(const string &handSeqKey, Bottle &sequenc // numWayPoints part Bottle &bNum=sequence.addList(); bNum.addString("numWayPoints"); - bNum.addInt((int)handWP.size()); + bNum.addInt32((int)handWP.size()); // wayPoints parts for (unsigned int i=0; i::max())).asDouble(); + ext_force_thres=opt.check("ext_force_thres",Value(std::numeric_limits::max())).asFloat64(); string wbdynStemName=opt.check("wbdyn_stem_name",Value(ACTIONPRIM_DEFAULT_WBDYN_STEMNAME)).asString(); string wbdynPortName=opt.check("wbdyn_port_name",Value(ACTIONPRIM_DEFAULT_WBDYN_PORTNAME)).asString(); diff --git a/src/libraries/ctrlLib/src/clustering.cpp b/src/libraries/ctrlLib/src/clustering.cpp index 94eb8d3dac..0516b8f647 100644 --- a/src/libraries/ctrlLib/src/clustering.cpp +++ b/src/libraries/ctrlLib/src/clustering.cpp @@ -152,8 +152,8 @@ namespace iCub { map> DBSCAN::cluster(const vector &data, const Property &options) { - double epsilon=options.check("epsilon",Value(1.0)).asDouble(); - size_t minpts=(size_t)options.check("minpts",Value(2)).asInt(); + double epsilon=options.check("epsilon",Value(1.0)).asFloat64(); + size_t minpts=(size_t)options.check("minpts",Value(2)).asInt32(); shared_ptr augData(new dbscan::Data_t(data,epsilon,minpts)); size_t id=0; diff --git a/src/libraries/ctrlLib/src/functionEncoder.cpp b/src/libraries/ctrlLib/src/functionEncoder.cpp index e8d590d786..56e4068684 100644 --- a/src/libraries/ctrlLib/src/functionEncoder.cpp +++ b/src/libraries/ctrlLib/src/functionEncoder.cpp @@ -171,7 +171,7 @@ bool WaveletEncoder::setEncoderOptions(const Property &options) { if (options.check("resolution")) { - double R=options.find("resolution").asDouble(); + double R=options.find("resolution").asFloat64(); // apply saturation resolution=std::max(0.0,std::min(R,double(WAVELET_LUP_SIZE-1))); diff --git a/src/libraries/ctrlLib/src/minJerkCtrl.cpp b/src/libraries/ctrlLib/src/minJerkCtrl.cpp index 6921ae0599..a61dda613b 100644 --- a/src/libraries/ctrlLib/src/minJerkCtrl.cpp +++ b/src/libraries/ctrlLib/src/minJerkCtrl.cpp @@ -213,22 +213,22 @@ void minJerkVelCtrlForNonIdealPlant::setPlantParameters(const Property ¶mete for (int i=0; icheck("Kp")) - Kp[i]=options->find("Kp").asDouble(); + Kp[i]=options->find("Kp").asFloat64(); if (options->check("Tz")) - Tz[i]=options->find("Tz").asDouble(); + Tz[i]=options->find("Tz").asFloat64(); if (options->check("Tw")) - Tw[i]=options->find("Tw").asDouble(); + Tw[i]=options->find("Tw").asFloat64(); if (options->check("Zeta")) - Zeta[i]=options->find("Zeta").asDouble(); + Zeta[i]=options->find("Zeta").asFloat64(); } } } diff --git a/src/libraries/ctrlLib/src/neuralNetworks.cpp b/src/libraries/ctrlLib/src/neuralNetworks.cpp index c96d019ee4..7b0fb8d6b5 100644 --- a/src/libraries/ctrlLib/src/neuralNetworks.cpp +++ b/src/libraries/ctrlLib/src/neuralNetworks.cpp @@ -48,7 +48,7 @@ void ff2LayNN::setItem(Property &options, const string &tag, const Vector &item) { Bottle b; Bottle &v=b.addList(); for (size_t i=0; isize()); for (size_t i=0; iget(i).asDouble(); + item[i]=b->get(i).asFloat64(); return true; } @@ -116,7 +116,7 @@ bool ff2LayNN::configure(const Property &options) !options.check("numOutputNodes")) return false; - int numHiddenNodes=options.find("numHiddenNodes").asInt(); + int numHiddenNodes=options.find("numHiddenNodes").asInt32(); for (int i=0; i ModifiedThompsonTau::detect(const Vector &data, const Property &opti if (options.check("mean") && options.check("std")) { - mean=options.find("mean").asDouble(); - stdev=options.find("std").asDouble(); + mean=options.find("mean").asFloat64(); + stdev=options.find("std").asFloat64(); } else if (N>0) { diff --git a/src/libraries/ctrlLib/src/pids.cpp b/src/libraries/ctrlLib/src/pids.cpp index 66c10d75bd..e2972524fa 100644 --- a/src/libraries/ctrlLib/src/pids.cpp +++ b/src/libraries/ctrlLib/src/pids.cpp @@ -140,7 +140,7 @@ void helperPID::addVectorToOption(Bottle &option, const char *key, const Vector bKey.addString(key); Bottle &bKeyContent=bKey.addList(); for (size_t i=0; iget(i).asDouble(); + val[i]=b->get(i).asFloat64(); return true; } @@ -281,7 +281,7 @@ void parallelPID::getOptions(Bottle &options) Bottle &bTs=options.addList(); bTs.addString("Ts"); - bTs.addDouble(Ts); + bTs.addFloat64(Ts); } @@ -321,7 +321,7 @@ void parallelPID::setOptions(const Bottle &options) if (options.check("Ts")) { - double _Ts=options.find("Ts").asDouble(); + double _Ts=options.find("Ts").asFloat64(); if (_Ts>0.0) { Ts=_Ts; @@ -493,7 +493,7 @@ void seriesPID::getOptions(Bottle &options) Bottle &bTs=options.addList(); bTs.addString("Ts"); - bTs.addDouble(Ts); + bTs.addFloat64(Ts); } @@ -530,7 +530,7 @@ void seriesPID::setOptions(const Bottle &options) if (options.check("Ts")) { - double _Ts=options.find("Ts").asDouble(); + double _Ts=options.find("Ts").asFloat64(); if (_Ts>0.0) { Ts=_Ts; diff --git a/src/libraries/ctrlLib/src/tuning.cpp b/src/libraries/ctrlLib/src/tuning.cpp index 56102ccf9e..c3f33a34ab 100644 --- a/src/libraries/ctrlLib/src/tuning.cpp +++ b/src/libraries/ctrlLib/src/tuning.cpp @@ -162,22 +162,22 @@ bool OnlineStictionEstimator::configure(PolyDriver &driver, const Property &opti if (!ok) return false; - joint=options.find("joint").asInt(); - setPeriod(options.check("Ts",Value(0.01)).asDouble()); + joint=options.find("joint").asInt32(); + setPeriod(options.check("Ts",Value(0.01)).asFloat64()); - T=options.check("T",Value(2.0)).asDouble(); - Kp=options.check("Kp",Value(10.0)).asDouble(); - Ki=options.check("Ki",Value(250.0)).asDouble(); - Kd=options.check("Kd",Value(15.0)).asDouble(); - vel_thres=fabs(options.check("vel_thres",Value(5.0)).asDouble()); - e_thres=fabs(options.check("e_thres",Value(1.0)).asDouble()); + T=options.check("T",Value(2.0)).asFloat64(); + Kp=options.check("Kp",Value(10.0)).asFloat64(); + Ki=options.check("Ki",Value(250.0)).asFloat64(); + Kd=options.check("Kd",Value(15.0)).asFloat64(); + vel_thres=fabs(options.check("vel_thres",Value(5.0)).asFloat64()); + e_thres=fabs(options.check("e_thres",Value(1.0)).asFloat64()); gamma.resize(2,1.0); if (Bottle *pB=options.find("gamma").asList()) { size_t len=std::min(gamma.length(),(size_t)pB->size()); for (size_t i=0; iget(i).asDouble(); + gamma[i]=pB->get(i).asFloat64(); } stiction.resize(2,0.0); @@ -185,7 +185,7 @@ bool OnlineStictionEstimator::configure(PolyDriver &driver, const Property &opti { size_t len=std::min(stiction.length(),(size_t)pB->size()); for (size_t i=0; iget(i).asDouble(); + stiction[i]=pB->get(i).asFloat64(); } return configured=true; @@ -201,28 +201,28 @@ bool OnlineStictionEstimator::reconfigure(const Property &options) if (configured) { if (options.check("joint")) - joint=options.find("joint").asInt(); + joint=options.find("joint").asInt32(); if (options.check("Ts")) - setPeriod(options.find("Ts").asDouble()); + setPeriod(options.find("Ts").asFloat64()); if (options.check("T")) - T=options.find("T").asDouble(); + T=options.find("T").asFloat64(); if (options.check("Kp")) - Kp=options.find("Kp").asDouble(); + Kp=options.find("Kp").asFloat64(); if (options.check("Ki")) - Ki=options.find("Ki").asDouble(); + Ki=options.find("Ki").asFloat64(); if (options.check("Kd")) - Kd=options.find("Kd").asDouble(); + Kd=options.find("Kd").asFloat64(); if (options.check("vel_thres")) - vel_thres=options.find("vel_thres").asDouble(); + vel_thres=options.find("vel_thres").asFloat64(); if (options.check("e_thres")) - e_thres=options.find("e_thres").asDouble(); + e_thres=options.find("e_thres").asFloat64(); if (options.check("gamma")) { @@ -230,7 +230,7 @@ bool OnlineStictionEstimator::reconfigure(const Property &options) { size_t len=std::min(gamma.length(),(size_t)pB->size()); for (size_t i=0; iget(i).asDouble(); + gamma[i]=pB->get(i).asFloat64(); } } @@ -240,7 +240,7 @@ bool OnlineStictionEstimator::reconfigure(const Property &options) { size_t len=std::min(stiction.length(),(size_t)pB->size()); for (size_t i=0; iget(i).asDouble(); + stiction[i]=pB->get(i).asFloat64(); } } @@ -482,7 +482,7 @@ bool OnlineCompensatorDesign::configure(PolyDriver &driver, const Property &opti if (!optGeneral.check("joint")) return false; - joint=optGeneral.find("joint").asInt(); + joint=optGeneral.find("joint").asInt32(); if (optGeneral.check("port")) { @@ -509,14 +509,14 @@ bool OnlineCompensatorDesign::configure(PolyDriver &driver, const Property &opti x_max-=0.1*x_range; x0.resize(4,0.0); - x0[2]=optPlant.check("tau",Value(1.0)).asDouble(); - x0[3]=optPlant.check("K",Value(1.0)).asDouble(); + x0[2]=optPlant.check("tau",Value(1.0)).asFloat64(); + x0[3]=optPlant.check("K",Value(1.0)).asFloat64(); - double Ts=optPlant.check("Ts",Value(0.01)).asDouble(); - double Q=optPlant.check("Q",Value(1.0)).asDouble(); - double R=optPlant.check("R",Value(1.0)).asDouble(); - P0=optPlant.check("P0",Value(1e5)).asDouble(); - max_pwm=optPlant.check("max_pwm",Value(800)).asDouble(); + double Ts=optPlant.check("Ts",Value(0.01)).asFloat64(); + double Q=optPlant.check("Q",Value(1.0)).asFloat64(); + double R=optPlant.check("R",Value(1.0)).asFloat64(); + P0=optPlant.check("P0",Value(1e5)).asFloat64(); + max_pwm=optPlant.check("max_pwm",Value(800)).asFloat64(); setPeriod(Ts); @@ -731,9 +731,9 @@ void OnlineCompensatorDesign::run() info.resize(4); info[0]=2.0; - info[1]=stiction_info.find("voltage").asDouble(); - info[2]=stiction_info.find("position").asDouble(); - info[3]=stiction_info.find("reference").asDouble(); + info[1]=stiction_info.find("voltage").asFloat64(); + info[2]=stiction_info.find("position").asFloat64(); + info[3]=stiction_info.find("reference").asFloat64(); Vector results; stiction.getResults(results); @@ -842,10 +842,10 @@ bool OnlineCompensatorDesign::tuneController(const Property &options, !options.check("type") || !options.check("f_c")) return false; - double tau=options.find("tau").asDouble(); - double K=options.find("K").asDouble(); + double tau=options.find("tau").asFloat64(); + double K=options.find("K").asFloat64(); string type=options.check("type",Value("PI")).asString(); - double omega_c=2.0*M_PI*options.find("f_c").asDouble(); + double omega_c=2.0*M_PI*options.find("f_c").asFloat64(); double Kp,Ki; // P design @@ -859,7 +859,7 @@ bool OnlineCompensatorDesign::tuneController(const Property &options, { double T_dr=1.0/omega_c; if (options.check("T_dr")) - T_dr=options.find("T_dr").asDouble(); + T_dr=options.find("T_dr").asFloat64(); double tau_dr=T_dr/3.0; double omega_dr=1.0/tau_dr; @@ -893,8 +893,8 @@ bool OnlineCompensatorDesign::startPlantEstimation(const Property &options) if (!configured) return false; - max_time=options.check("max_time",Value(0.0)).asDouble(); - switch_timeout=options.check("switch_timeout",Value(0.0)).asDouble(); + max_time=options.check("max_time",Value(0.0)).asFloat64(); + switch_timeout=options.check("switch_timeout",Value(0.0)).asFloat64(); mode=plant_estimation; return PeriodicThread::start(); @@ -907,19 +907,19 @@ bool OnlineCompensatorDesign::startPlantValidation(const Property &options) if (!configured || !options.check("tau") || !options.check("K")) return false; - max_time=options.check("max_time",Value(0.0)).asDouble(); - switch_timeout=options.check("switch_timeout",Value(0.0)).asDouble(); - measure_update_ticks=options.check("measure_update_ticks",Value(100)).asInt(); + max_time=options.check("max_time",Value(0.0)).asFloat64(); + switch_timeout=options.check("switch_timeout",Value(0.0)).asFloat64(); + measure_update_ticks=options.check("measure_update_ticks",Value(100)).asInt32(); - double tau=options.find("tau").asDouble(); - double K=options.find("K").asDouble(); + double tau=options.find("tau").asFloat64(); + double K=options.find("K").asFloat64(); double Ts=getPeriod(); double a=1.0/tau; double b=K/tau; - double Q=options.check("Q",Value(1.0)).asDouble(); - double R=options.check("R",Value(1.0)).asDouble(); - double P0=options.check("P0",Value(this->P0)).asDouble(); + double Q=options.check("Q",Value(1.0)).asFloat64(); + double R=options.check("R",Value(1.0)).asFloat64(); + double P0=options.check("P0",Value(this->P0)).asFloat64(); // set up the Kalman filter double _exp=exp(-Ts*a); @@ -956,7 +956,7 @@ bool OnlineCompensatorDesign::startStictionEstimation(const Property &options) return false; Property opt=options; - max_time=opt.check("max_time",Value(0.0)).asDouble(); + max_time=opt.check("max_time",Value(0.0)).asFloat64(); opt.unput("joint"); if (!stiction.reconfigure(opt)) @@ -973,15 +973,15 @@ bool OnlineCompensatorDesign::startControllerValidation(const Property &options) if (!configured || !options.check("Kp")) return false; - max_time=options.check("max_time",Value(0.0)).asDouble(); + max_time=options.check("max_time",Value(0.0)).asFloat64(); ipid->getPid(VOCAB_PIDTYPE_POSITION,joint,&pidOld); pidNew=pidOld; // enforce the correct sign of gains - double Kp=options.find("Kp").asDouble(); - double Ki=options.check("Ki",Value(0.0)).asDouble(); - double Kd=options.check("Kd",Value(0.0)).asDouble(); + double Kp=options.find("Kp").asFloat64(); + double Ki=options.check("Ki",Value(0.0)).asFloat64(); + double Kd=options.check("Kd",Value(0.0)).asFloat64(); Kp=(Kp*pidOld.kp>0.0)?Kp:-Kp; Ki=(Ki*pidOld.ki>0.0)?Ki:-Ki; Kd=(Kd*pidOld.kd>0.0)?Kd:-Kd; @@ -991,12 +991,12 @@ bool OnlineCompensatorDesign::startControllerValidation(const Property &options) pidNew.setStictionValues(0.0,0.0); if (options.check("scale")) - pidNew.setScale(options.find("scale").asInt()); + pidNew.setScale(options.find("scale").asInt32()); controller_validation_ref_square=(options.check("ref_type",Value("square")).asString()=="square"); - controller_validation_ref_period=options.check("ref_period",Value(2.0)).asDouble(); - controller_validation_ref_sustain_time=options.check("ref_sustain_time",Value(0.0)).asDouble(); - controller_validation_cycles_to_switch=options.check("cycles_to_switch",Value(1)).asInt(); + controller_validation_ref_period=options.check("ref_period",Value(2.0)).asFloat64(); + controller_validation_ref_sustain_time=options.check("ref_sustain_time",Value(0.0)).asFloat64(); + controller_validation_cycles_to_switch=options.check("cycles_to_switch",Value(1)).asInt32(); controller_validation_stiction_yarp=(options.check("stiction_compensation",Value("firmware")).asString()!="firmware"); controller_validation_stiction_up=controller_validation_stiction_down=0.0; @@ -1006,8 +1006,8 @@ bool OnlineCompensatorDesign::startControllerValidation(const Property &options) { if (pB->size()>=2) { - controller_validation_stiction_up=pB->get(0).asDouble(); - controller_validation_stiction_down=pB->get(1).asDouble(); + controller_validation_stiction_up=pB->get(0).asFloat64(); + controller_validation_stiction_down=pB->get(1).asFloat64(); if (!controller_validation_stiction_yarp) pidNew.setStictionValues(controller_validation_stiction_up, diff --git a/src/libraries/iCubDev/include/iCub/DebugInterfaces.h b/src/libraries/iCubDev/include/iCub/DebugInterfaces.h index 3cfc00577d..b7eb9a1da3 100644 --- a/src/libraries/iCubDev/include/iCub/DebugInterfaces.h +++ b/src/libraries/iCubDev/include/iCub/DebugInterfaces.h @@ -44,8 +44,8 @@ #include // for printf // additional vocabs defined for the IDebug interface. -#define VOCAB_GENERIC_PARAMETER yarp::os::createVocab('g','e','n','p') -#define VOCAB_DEBUG_PARAMETER yarp::os::createVocab('d','b','g','p') +#define VOCAB_GENERIC_PARAMETER yarp::os::createVocab32('g','e','n','p') +#define VOCAB_DEBUG_PARAMETER yarp::os::createVocab32('d','b','g','p') /* LATER: is it likely that some of these would move into iCub::dev namespace? */ namespace yarp{ diff --git a/src/libraries/iDyn/include/iCub/iDyn/iDynVocabs.h b/src/libraries/iDyn/include/iCub/iDyn/iDynVocabs.h index 7212786b09..bb82bccd46 100644 --- a/src/libraries/iDyn/include/iCub/iDyn/iDynVocabs.h +++ b/src/libraries/iDyn/include/iCub/iDyn/iDynVocabs.h @@ -10,9 +10,9 @@ #include -#define IDYN_NEWTEUL_VOCAB_MODE_STAT yarp::os::createVocab('s','t','a','t') -#define IDYN_NEWTEUL_VOCAB_MODE_DYN yarp::os::createVocab('d','y','n') -#define IDYN_NEWTEUL_VOCAB_MODE_DYNR yarp::os::createVocab('d','y','n','r') +#define IDYN_NEWTEUL_VOCAB_MODE_STAT yarp::os::createVocab32('s','t','a','t') +#define IDYN_NEWTEUL_VOCAB_MODE_DYN yarp::os::createVocab32('d','y','n') +#define IDYN_NEWTEUL_VOCAB_MODE_DYNR yarp::os::createVocab32('d','y','n','r') #endif diff --git a/src/libraries/iDyn/src/iDyn.cpp b/src/libraries/iDyn/src/iDyn.cpp index 7bcbde5f51..573634a28c 100644 --- a/src/libraries/iDyn/src/iDyn.cpp +++ b/src/libraries/iDyn/src/iDyn.cpp @@ -1789,7 +1789,7 @@ bool iDynLimb::fromLinksProperties(const Property &option) H0.zero(); for(int cnt=0; (cntsize()) && (cntget(cnt).asDouble(); + H0(i,j)=bH0->get(cnt).asFloat64(); if(++j>=H0.cols()) { i++; @@ -1799,7 +1799,7 @@ bool iDynLimb::fromLinksProperties(const Property &option) } //number of links - int numLinks=option.check("numLinks",Value(0)).asInt(); + int numLinks=option.check("numLinks",Value(0)).asInt32(); if(numLinks==0) { yError("Error: invalid number of links (0) specified! \n"); @@ -1824,16 +1824,16 @@ bool iDynLimb::fromLinksProperties(const Property &option) } //kinematics parameters - double A=bLink.check("A",Value(0.0)).asDouble(); - double D=bLink.check("D",Value(0.0)).asDouble(); - double alpha=CTRL_DEG2RAD*bLink.check("alpha",Value(0.0)).asDouble(); - double offset=CTRL_DEG2RAD*bLink.check("offset",Value(0.0)).asDouble(); - double min=CTRL_DEG2RAD*bLink.check("min",Value(0.0)).asDouble(); - double max=CTRL_DEG2RAD*bLink.check("max",Value(0.0)).asDouble(); + double A=bLink.check("A",Value(0.0)).asFloat64(); + double D=bLink.check("D",Value(0.0)).asFloat64(); + double alpha=CTRL_DEG2RAD*bLink.check("alpha",Value(0.0)).asFloat64(); + double offset=CTRL_DEG2RAD*bLink.check("offset",Value(0.0)).asFloat64(); + double min=CTRL_DEG2RAD*bLink.check("min",Value(0.0)).asFloat64(); + double max=CTRL_DEG2RAD*bLink.check("max",Value(0.0)).asFloat64(); //dynamic parameters //mass - double mass=bLink.check("mass",Value(0.0)).asDouble(); + double mass=bLink.check("mass",Value(0.0)).asFloat64(); //inertia if(Bottle *bI=option.find("Inertia").asList()) { @@ -1841,7 +1841,7 @@ bool iDynLimb::fromLinksProperties(const Property &option) I.zero(); for(int cnt=0; (cntsize()) && (cntget(cnt).asDouble(); + I(i,j)=bI->get(cnt).asFloat64(); if(++j>=I.cols()) { i++; @@ -1856,7 +1856,7 @@ bool iDynLimb::fromLinksProperties(const Property &option) HC.zero(); for(int cnt=0; (cntsize()) && (cntget(cnt).asDouble(); + HC(i,j)=bHC->get(cnt).asFloat64(); if(++j>=HC.cols()) { i++; @@ -1869,7 +1869,7 @@ bool iDynLimb::fromLinksProperties(const Property &option) pushLink(new iDynLink(mass,HC,I,A,D,alpha,offset,min,max)); if(bLink.check("blocked")) - blockLink(iLink,CTRL_DEG2RAD*bLink.find("blocked").asDouble()); + blockLink(iLink,CTRL_DEG2RAD*bLink.find("blocked").asFloat64()); } return configured=true; diff --git a/src/libraries/iKin/include/iCub/iKin/iKinVocabs.h b/src/libraries/iKin/include/iCub/iKin/iKinVocabs.h index 29b5b8748e..e94b83709b 100644 --- a/src/libraries/iKin/include/iCub/iKin/iKinVocabs.h +++ b/src/libraries/iKin/include/iCub/iKin/iKinVocabs.h @@ -13,39 +13,39 @@ #include -#define IKINSLV_VOCAB_CMD_GET yarp::os::createVocab('g','e','t') -#define IKINSLV_VOCAB_CMD_SET yarp::os::createVocab('s','e','t') -#define IKINSLV_VOCAB_CMD_ASK yarp::os::createVocab('a','s','k') -#define IKINSLV_VOCAB_CMD_SUSP yarp::os::createVocab('s','u','s','p') -#define IKINSLV_VOCAB_CMD_RUN yarp::os::createVocab('r','u','n') -#define IKINSLV_VOCAB_CMD_STATUS yarp::os::createVocab('s','t','a','t') -#define IKINSLV_VOCAB_CMD_HELP yarp::os::createVocab('h','e','l','p') -#define IKINSLV_VOCAB_CMD_CFG yarp::os::createVocab('c','f','g') -#define IKINSLV_VOCAB_CMD_QUIT yarp::os::createVocab('q','u','i','t') -#define IKINSLV_VOCAB_OPT_MODE yarp::os::createVocab('m','o','d','e') -#define IKINSLV_VOCAB_OPT_POSE yarp::os::createVocab('p','o','s','e') -#define IKINSLV_VOCAB_OPT_PRIO yarp::os::createVocab('p','r','i','o') -#define IKINSLV_VOCAB_OPT_DOF yarp::os::createVocab('d','o','f') -#define IKINSLV_VOCAB_OPT_LIM yarp::os::createVocab('l','i','m') -#define IKINSLV_VOCAB_OPT_XD yarp::os::createVocab('x','d') -#define IKINSLV_VOCAB_OPT_X yarp::os::createVocab('x') -#define IKINSLV_VOCAB_OPT_Q yarp::os::createVocab('q') -#define IKINSLV_VOCAB_OPT_TOKEN yarp::os::createVocab('t','o','k') -#define IKINSLV_VOCAB_OPT_VERB yarp::os::createVocab('v','e','r','b') -#define IKINSLV_VOCAB_OPT_REST_POS yarp::os::createVocab('r','e','s','p') -#define IKINSLV_VOCAB_OPT_REST_WEIGHTS yarp::os::createVocab('r','e','s','w') -#define IKINSLV_VOCAB_OPT_TIP_FRAME yarp::os::createVocab('t','i','p') -#define IKINSLV_VOCAB_OPT_TASK2 yarp::os::createVocab('t','s','k','2') -#define IKINSLV_VOCAB_OPT_CONVERGENCE yarp::os::createVocab('c','o','n','v') -#define IKINSLV_VOCAB_VAL_POSE_FULL yarp::os::createVocab('f','u','l','l') -#define IKINSLV_VOCAB_VAL_POSE_XYZ yarp::os::createVocab('x','y','z') -#define IKINSLV_VOCAB_VAL_PRIO_XYZ yarp::os::createVocab('x','y','z') -#define IKINSLV_VOCAB_VAL_PRIO_ANG yarp::os::createVocab('a','n','g') -#define IKINSLV_VOCAB_VAL_MODE_TRACK yarp::os::createVocab('c','o','n','t') -#define IKINSLV_VOCAB_VAL_MODE_SINGLE yarp::os::createVocab('s','h','o','t') -#define IKINSLV_VOCAB_VAL_ON yarp::os::createVocab('o','n') -#define IKINSLV_VOCAB_VAL_OFF yarp::os::createVocab('o','f','f') -#define IKINSLV_VOCAB_REP_ACK yarp::os::createVocab('a','c','k') -#define IKINSLV_VOCAB_REP_NACK yarp::os::createVocab('n','a','c','k') +#define IKINSLV_VOCAB_CMD_GET yarp::os::createVocab32('g','e','t') +#define IKINSLV_VOCAB_CMD_SET yarp::os::createVocab32('s','e','t') +#define IKINSLV_VOCAB_CMD_ASK yarp::os::createVocab32('a','s','k') +#define IKINSLV_VOCAB_CMD_SUSP yarp::os::createVocab32('s','u','s','p') +#define IKINSLV_VOCAB_CMD_RUN yarp::os::createVocab32('r','u','n') +#define IKINSLV_VOCAB_CMD_STATUS yarp::os::createVocab32('s','t','a','t') +#define IKINSLV_VOCAB_CMD_HELP yarp::os::createVocab32('h','e','l','p') +#define IKINSLV_VOCAB_CMD_CFG yarp::os::createVocab32('c','f','g') +#define IKINSLV_VOCAB_CMD_QUIT yarp::os::createVocab32('q','u','i','t') +#define IKINSLV_VOCAB_OPT_MODE yarp::os::createVocab32('m','o','d','e') +#define IKINSLV_VOCAB_OPT_POSE yarp::os::createVocab32('p','o','s','e') +#define IKINSLV_VOCAB_OPT_PRIO yarp::os::createVocab32('p','r','i','o') +#define IKINSLV_VOCAB_OPT_DOF yarp::os::createVocab32('d','o','f') +#define IKINSLV_VOCAB_OPT_LIM yarp::os::createVocab32('l','i','m') +#define IKINSLV_VOCAB_OPT_XD yarp::os::createVocab32('x','d') +#define IKINSLV_VOCAB_OPT_X yarp::os::createVocab32('x') +#define IKINSLV_VOCAB_OPT_Q yarp::os::createVocab32('q') +#define IKINSLV_VOCAB_OPT_TOKEN yarp::os::createVocab32('t','o','k') +#define IKINSLV_VOCAB_OPT_VERB yarp::os::createVocab32('v','e','r','b') +#define IKINSLV_VOCAB_OPT_REST_POS yarp::os::createVocab32('r','e','s','p') +#define IKINSLV_VOCAB_OPT_REST_WEIGHTS yarp::os::createVocab32('r','e','s','w') +#define IKINSLV_VOCAB_OPT_TIP_FRAME yarp::os::createVocab32('t','i','p') +#define IKINSLV_VOCAB_OPT_TASK2 yarp::os::createVocab32('t','s','k','2') +#define IKINSLV_VOCAB_OPT_CONVERGENCE yarp::os::createVocab32('c','o','n','v') +#define IKINSLV_VOCAB_VAL_POSE_FULL yarp::os::createVocab32('f','u','l','l') +#define IKINSLV_VOCAB_VAL_POSE_XYZ yarp::os::createVocab32('x','y','z') +#define IKINSLV_VOCAB_VAL_PRIO_XYZ yarp::os::createVocab32('x','y','z') +#define IKINSLV_VOCAB_VAL_PRIO_ANG yarp::os::createVocab32('a','n','g') +#define IKINSLV_VOCAB_VAL_MODE_TRACK yarp::os::createVocab32('c','o','n','t') +#define IKINSLV_VOCAB_VAL_MODE_SINGLE yarp::os::createVocab32('s','h','o','t') +#define IKINSLV_VOCAB_VAL_ON yarp::os::createVocab32('o','n') +#define IKINSLV_VOCAB_VAL_OFF yarp::os::createVocab32('o','f','f') +#define IKINSLV_VOCAB_REP_ACK yarp::os::createVocab32('a','c','k') +#define IKINSLV_VOCAB_REP_NACK yarp::os::createVocab32('n','a','c','k') #endif diff --git a/src/libraries/iKin/src/iKinFwd.cpp b/src/libraries/iKin/src/iKinFwd.cpp index fc1e36e052..02790d68b5 100644 --- a/src/libraries/iKin/src/iKinFwd.cpp +++ b/src/libraries/iKin/src/iKinFwd.cpp @@ -1367,7 +1367,7 @@ void iKinLimb::getMatrixFromProperties(const Property &options, const string &ta H.zero(); for (int cnt=0; (cntsize()) && (cntget(cnt).asDouble(); + H(i,j)=bH->get(cnt).asFloat64(); if (++j>=H.cols()) { i++; @@ -1385,7 +1385,7 @@ void iKinLimb::setMatrixToProperties(Property &options, const string &tag, Bottle b; Bottle &l=b.addList(); for (int r=0; rsize()==0) @@ -52,17 +52,17 @@ bool CartesianHelper::getDesiredOption(const Bottle &reply, Vector &xdhat, xdhat.resize(3); for (size_t i=0; iget(i).asDouble(); + xdhat[i]=xData->get(i).asFloat64(); odhat.resize(4); for (size_t i=0; iget(xdhat.length()+i).asDouble(); + odhat[i]=xData->get(xdhat.length()+i).asFloat64(); } else return false; // qdhat part - if (reply.check(Vocab::decode(IKINSLV_VOCAB_OPT_Q))) + if (reply.check(Vocab32::decode(IKINSLV_VOCAB_OPT_Q))) { Bottle *qData=getJointsOption(reply); if (qData->size()==0) @@ -70,7 +70,7 @@ bool CartesianHelper::getDesiredOption(const Bottle &reply, Vector &xdhat, qdhat.resize(qData->size()); for (size_t i=0; iget(i).asDouble(); + qdhat[i]=qData->get(i).asFloat64(); } else return false; @@ -114,12 +114,12 @@ void CartesianHelper::addJointsRestWeightsOption(Bottle &b, const Vector &restWe void CartesianHelper::addPoseOption(Bottle &b, const unsigned int pose) { Bottle &posePart=b.addList(); - posePart.addVocab(IKINSLV_VOCAB_OPT_POSE); + posePart.addVocab32(IKINSLV_VOCAB_OPT_POSE); if (pose==IKINCTRL_POSE_FULL) - posePart.addVocab(IKINSLV_VOCAB_VAL_POSE_FULL); + posePart.addVocab32(IKINSLV_VOCAB_VAL_POSE_FULL); else if (pose==IKINCTRL_POSE_XYZ) - posePart.addVocab(IKINSLV_VOCAB_VAL_POSE_XYZ); + posePart.addVocab32(IKINSLV_VOCAB_VAL_POSE_XYZ); } @@ -127,12 +127,12 @@ void CartesianHelper::addPoseOption(Bottle &b, const unsigned int pose) void CartesianHelper::addModeOption(Bottle &b, const bool tracking) { Bottle &modePart=b.addList(); - modePart.addVocab(IKINSLV_VOCAB_OPT_MODE); + modePart.addVocab32(IKINSLV_VOCAB_OPT_MODE); if (tracking) - modePart.addVocab(IKINSLV_VOCAB_VAL_MODE_TRACK); + modePart.addVocab32(IKINSLV_VOCAB_VAL_MODE_TRACK); else - modePart.addVocab(IKINSLV_VOCAB_VAL_MODE_SINGLE); + modePart.addVocab32(IKINSLV_VOCAB_VAL_MODE_SINGLE); } @@ -140,38 +140,38 @@ void CartesianHelper::addModeOption(Bottle &b, const bool tracking) void CartesianHelper::addTokenOption(Bottle &b, const double token) { Bottle &tokenPart=b.addList(); - tokenPart.addVocab(IKINSLV_VOCAB_OPT_TOKEN); - tokenPart.addDouble(token); + tokenPart.addVocab32(IKINSLV_VOCAB_OPT_TOKEN); + tokenPart.addFloat64(token); } /************************************************************************/ Bottle *CartesianHelper::getTargetOption(const Bottle &b) { - return b.find(Vocab::decode(IKINSLV_VOCAB_OPT_XD)).asList(); + return b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_XD)).asList(); } /************************************************************************/ Bottle *CartesianHelper::getEndEffectorPoseOption(const Bottle &b) { - return b.find(Vocab::decode(IKINSLV_VOCAB_OPT_X)).asList(); + return b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_X)).asList(); } /************************************************************************/ Bottle *CartesianHelper::getJointsOption(const Bottle &b) { - return b.find(Vocab::decode(IKINSLV_VOCAB_OPT_Q)).asList(); + return b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_Q)).asList(); } /************************************************************************/ bool CartesianHelper::getTokenOption(const Bottle &b, double *token) { - if (b.check(Vocab::decode(IKINSLV_VOCAB_OPT_TOKEN)) && (token!=NULL)) + if (b.check(Vocab32::decode(IKINSLV_VOCAB_OPT_TOKEN)) && (token!=NULL)) { - *token=b.find(Vocab::decode(IKINSLV_VOCAB_OPT_TOKEN)).asDouble(); + *token=b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_TOKEN)).asFloat64(); return true; } else diff --git a/src/libraries/iKin/src/iKinInv.cpp b/src/libraries/iKin/src/iKinInv.cpp index 3cace2f103..e69d783745 100644 --- a/src/libraries/iKin/src/iKinInv.cpp +++ b/src/libraries/iKin/src/iKinInv.cpp @@ -974,7 +974,7 @@ void MultiRefMinJerkCtrl::setPlantParameters(const Property ¶meters, Bottle ordering; for (unsigned int i=0; i(mjCtrlJoint)->setPlantParameters(parameters,entryTag,ordering); } diff --git a/src/libraries/iKin/src/iKinSlv.cpp b/src/libraries/iKin/src/iKinSlv.cpp index 0bfa93f18d..bc7f56d91c 100644 --- a/src/libraries/iKin/src/iKinSlv.cpp +++ b/src/libraries/iKin/src/iKinSlv.cpp @@ -129,7 +129,7 @@ bool InputPort::handleTarget(Bottle *b) lock_guard lck(mtx); size_t len=std::min(b->size(),maxLen); for (size_t i=0; iget(i).asDouble(); + xd[i]=b->get(i).asFloat64(); return isNew=true; } else @@ -147,7 +147,7 @@ bool InputPort::handleDOF(Bottle *b) mtx.lock(); dof.resize(b->size()); for (int i=0; isize(); i++) - dof[i]=b->get(i).asInt(); + dof[i]=b->get(i).asInt32(); mtx.unlock(); slv->unlock(); @@ -207,10 +207,10 @@ bool InputPort::handleMode(const int newMode) /************************************************************************/ void InputPort::onRead(Bottle &b) { - bool xdOptIn =b.check(Vocab::decode(IKINSLV_VOCAB_OPT_XD)); - bool dofOptIn =b.check(Vocab::decode(IKINSLV_VOCAB_OPT_DOF)); - bool poseOptIn=b.check(Vocab::decode(IKINSLV_VOCAB_OPT_POSE)); - bool modeOptIn=b.check(Vocab::decode(IKINSLV_VOCAB_OPT_MODE)); + bool xdOptIn =b.check(Vocab32::decode(IKINSLV_VOCAB_OPT_XD)); + bool dofOptIn =b.check(Vocab32::decode(IKINSLV_VOCAB_OPT_DOF)); + bool poseOptIn=b.check(Vocab32::decode(IKINSLV_VOCAB_OPT_POSE)); + bool modeOptIn=b.check(Vocab32::decode(IKINSLV_VOCAB_OPT_MODE)); if (xdOptIn) { @@ -221,22 +221,22 @@ void InputPort::onRead(Bottle &b) } if (modeOptIn) - if (!handleMode(b.find(Vocab::decode(IKINSLV_VOCAB_OPT_MODE)).asVocab())) + if (!handleMode(b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_MODE)).asVocab32())) yWarning("%s: got incomplete %s command",slv->slvName.c_str(), - Vocab::decode(IKINSLV_VOCAB_OPT_MODE).c_str()); + Vocab32::decode(IKINSLV_VOCAB_OPT_MODE).c_str()); if (dofOptIn) - if (!handleDOF(b.find(Vocab::decode(IKINSLV_VOCAB_OPT_DOF)).asList())) + if (!handleDOF(b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_DOF)).asList())) yWarning("%s: expected %s data",slv->slvName.c_str(), - Vocab::decode(IKINSLV_VOCAB_OPT_DOF).c_str()); + Vocab32::decode(IKINSLV_VOCAB_OPT_DOF).c_str()); if (poseOptIn) - if (!handlePose(b.find(Vocab::decode(IKINSLV_VOCAB_OPT_POSE)).asVocab())) + if (!handlePose(b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_POSE)).asVocab32())) yWarning("%s: got incomplete %s command",slv->slvName.c_str(), - Vocab::decode(IKINSLV_VOCAB_OPT_POSE).c_str()); + Vocab32::decode(IKINSLV_VOCAB_OPT_POSE).c_str()); - if (slv->handleJointsRestPosition(b.find(Vocab::decode(IKINSLV_VOCAB_OPT_REST_POS)).asList()) || - slv->handleJointsRestWeights(b.find(Vocab::decode(IKINSLV_VOCAB_OPT_REST_WEIGHTS)).asList())) + if (slv->handleJointsRestPosition(b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_REST_POS)).asList()) || + slv->handleJointsRestWeights(b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_REST_WEIGHTS)).asList())) { slv->lock(); slv->prepareJointsRestTask(); @@ -246,13 +246,13 @@ void InputPort::onRead(Bottle &b) // shall be the last handling if (xdOptIn) { - if (!handleTarget(b.find(Vocab::decode(IKINSLV_VOCAB_OPT_XD)).asList())) + if (!handleTarget(b.find(Vocab32::decode(IKINSLV_VOCAB_OPT_XD)).asList())) yWarning("%s: expected %s data",slv->slvName.c_str(), - Vocab::decode(IKINSLV_VOCAB_OPT_XD).c_str()); + Vocab32::decode(IKINSLV_VOCAB_OPT_XD).c_str()); } else yWarning("%s: missing %s data; it shall be present", - slv->slvName.c_str(),Vocab::decode(IKINSLV_VOCAB_OPT_XD).c_str()); + slv->slvName.c_str(),Vocab32::decode(IKINSLV_VOCAB_OPT_XD).c_str()); } @@ -507,7 +507,7 @@ void CartesianSolver::postDOFHandling() void CartesianSolver::fillDOFInfo(Bottle &reply) { for (unsigned int i=0; ichn->getN(); i++) - reply.addInt(int(!(*prt->chn)[i].isBlocked())); + reply.addInt32(int(!(*prt->chn)[i].isBlocked())); } @@ -516,10 +516,10 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { if (command.size()) { - int vcb=command.get(0).asVocab(); + int vcb=command.get(0).asVocab32(); if (!configured && vcb!=IKINSLV_VOCAB_CMD_CFG) - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); else switch (vcb) { //----------------- @@ -527,17 +527,17 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { if (command.size()>1) { - switch (command.get(1).asVocab()) + switch (command.get(1).asVocab32()) { //----------------- case IKINSLV_VOCAB_OPT_POSE: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); if (ctrlPose==IKINCTRL_POSE_FULL) - reply.addVocab(IKINSLV_VOCAB_VAL_POSE_FULL); + reply.addVocab32(IKINSLV_VOCAB_VAL_POSE_FULL); else - reply.addVocab(IKINSLV_VOCAB_VAL_POSE_XYZ); + reply.addVocab32(IKINSLV_VOCAB_VAL_POSE_XYZ); break; } @@ -545,13 +545,13 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_PRIO: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); string priority=slv->get_posePriority(); if (priority=="position") - reply.addVocab(IKINSLV_VOCAB_VAL_PRIO_XYZ); + reply.addVocab32(IKINSLV_VOCAB_VAL_PRIO_XYZ); else - reply.addVocab(IKINSLV_VOCAB_VAL_PRIO_ANG); + reply.addVocab32(IKINSLV_VOCAB_VAL_PRIO_ANG); break; } @@ -559,12 +559,12 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_MODE: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); if (inPort->get_contMode()) - reply.addVocab(IKINSLV_VOCAB_VAL_MODE_TRACK); + reply.addVocab32(IKINSLV_VOCAB_VAL_MODE_TRACK); else - reply.addVocab(IKINSLV_VOCAB_VAL_MODE_SINGLE); + reply.addVocab32(IKINSLV_VOCAB_VAL_MODE_SINGLE); break; } @@ -574,19 +574,19 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { if (command.size()>2) { - int axis=command.get(2).asInt(); + int axis=command.get(2).asInt32(); if (axis<(int)prt->chn->getN()) { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); - reply.addDouble(swLimits(axis,0)); - reply.addDouble(swLimits(axis,1)); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); + reply.addFloat64(swLimits(axis,0)); + reply.addFloat64(swLimits(axis,1)); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -594,12 +594,12 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_VERB: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); if (verbosity) - reply.addVocab(IKINSLV_VOCAB_VAL_ON); + reply.addVocab32(IKINSLV_VOCAB_VAL_ON); else - reply.addVocab(IKINSLV_VOCAB_VAL_OFF); + reply.addVocab32(IKINSLV_VOCAB_VAL_OFF); break; } @@ -607,7 +607,7 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_DOF: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); Bottle &dofPart=reply.addList(); fillDOFInfo(dofPart); break; @@ -616,7 +616,7 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_REST_POS: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); handleJointsRestPosition(NULL,&reply); break; } @@ -624,7 +624,7 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_REST_WEIGHTS: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); handleJointsRestWeights(NULL,&reply); break; } @@ -632,17 +632,17 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_TASK2: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); Bottle &payLoad=reply.addList(); - payLoad.addInt(slv->get2ndTaskChain().getN()); + payLoad.addInt32(slv->get2ndTaskChain().getN()); Bottle &posPart=payLoad.addList(); for (size_t i=0; igetTol()); + tol.addFloat64(slv->getTol()); Bottle &constr_tol=payLoad.addList(); constr_tol.addString("constr_tol"); - constr_tol.addDouble(slv->getConstrTol()); + constr_tol.addFloat64(slv->getConstrTol()); Bottle &maxIter=payLoad.addList(); maxIter.addString("max_iter"); - maxIter.addInt(slv->getMaxIter()); + maxIter.addInt32(slv->getMaxIter()); break; } //----------------- default: - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -684,15 +684,15 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { if (command.size()>2) { - switch (command.get(1).asVocab()) + switch (command.get(1).asVocab32()) { //----------------- case IKINSLV_VOCAB_OPT_POSE: { - if (inPort->handlePose(command.get(2).asVocab())) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + if (inPort->handlePose(command.get(2).asVocab32())) + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -700,19 +700,19 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_PRIO: { - int type=command.get(2).asVocab(); + int type=command.get(2).asVocab32(); if (type==IKINSLV_VOCAB_VAL_PRIO_XYZ) { slv->set_posePriority("position"); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); } else if (type==IKINSLV_VOCAB_VAL_PRIO_ANG) { slv->set_posePriority("orientation"); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -720,10 +720,10 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_MODE: { - if (inPort->handleMode(command.get(2).asVocab())) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + if (inPort->handleMode(command.get(2).asVocab32())) + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -733,17 +733,17 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { if (command.size()>4) { - int axis=command.get(2).asInt(); - double min=command.get(3).asDouble(); - double max=command.get(4).asDouble(); + int axis=command.get(2).asInt32(); + double min=command.get(3).asFloat64(); + double max=command.get(4).asFloat64(); if (setLimits(axis,min,max)) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -751,17 +751,17 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_OPT_VERB: { - int sw=command.get(2).asVocab(); + int sw=command.get(2).asVocab32(); if (sw==IKINSLV_VOCAB_VAL_ON) { verbosity=true; - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); } else if (sw==IKINSLV_VOCAB_VAL_OFF) { verbosity=false; - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } break; @@ -774,12 +774,12 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { waitDOFHandling(); // sleep till dof handling is done - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); Bottle &dofPart=reply.addList(); fillDOFInfo(dofPart); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -795,11 +795,11 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) prepareJointsRestTask(); unlock(); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); reply.append(restPart); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -815,11 +815,11 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) prepareJointsRestTask(); unlock(); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); reply.append(restPart); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -833,11 +833,11 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { Vector x(3); for (size_t i=0; iget(i).asDouble(); + x[i]=tipPart->get(i).asFloat64(); Vector o(4); for (size_t i=0; iget(i+x.length()).asDouble(); + o[i]=tipPart->get(i+x.length()).asFloat64(); Matrix HN=axis2dcm(o); HN.setSubcol(x,0,3); @@ -846,12 +846,12 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) prt->chn->setHN(HN); unlock(); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); break; } } - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -862,7 +862,7 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) { if (payLoad->size()>=3) { - int n=payLoad->get(0).asInt(); + int n=payLoad->get(0).asInt32(); Bottle *posPart=payLoad->get(1).asList(); Bottle *weightsPart=payLoad->get(2).asList(); @@ -871,24 +871,24 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) if ((posPart->size()>=3) && (weightsPart->size()>=3)) { for (size_t i=0; iget(i).asDouble(); + xd_2ndTask[i]=posPart->get(i).asFloat64(); for (size_t i=0; iget(i).asDouble(); + w_2ndTask[i]=weightsPart->get(i).asFloat64(); if (n>=0) slv->specify2ndTaskEndEff(n); else slv->get2ndTaskChain().clear(); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); break; } } } } - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -900,37 +900,37 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) int cnt=0; if (payLoad->check("tol")) { - slv->setTol(payLoad->find("tol").asDouble()); + slv->setTol(payLoad->find("tol").asFloat64()); cnt++; } if (payLoad->check("constr_tol")) { - slv->setConstrTol(payLoad->find("constr_tol").asDouble()); + slv->setConstrTol(payLoad->find("constr_tol").asFloat64()); cnt++; } if (payLoad->check("max_iter")) { - slv->setMaxIter(payLoad->find("max_iter").asInt()); + slv->setMaxIter(payLoad->find("max_iter").asInt32()); cnt++; } - reply.addVocab(cnt>0?IKINSLV_VOCAB_REP_ACK:IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(cnt>0?IKINSLV_VOCAB_REP_ACK:IKINSLV_VOCAB_REP_NACK); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } //----------------- default: - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -944,12 +944,12 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) // some integrity checks if (b_xd==NULL) { - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } else if (b_xd->size()<3) // at least the positional part must be given { - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -958,23 +958,23 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) // get the target Vector xd(b_xd->size()); for (size_t i=0; iget(i).asDouble(); + xd[i]=b_xd->get(i).asFloat64(); // accounts for the starting DOF // if different from the actual one if (b_q!=NULL) { size_t len=std::min((size_t)b_q->size(),(size_t)prt->chn->getDOF()); - for (size_t i=0; ichn)(i).setAng(CTRL_DEG2RAD*b_q->get(i).asDouble()); + for (unsigned int i=0; ichn)(i).setAng(CTRL_DEG2RAD*b_q->get(i).asFloat64()); } else getFeedback(); // otherwise get the current configuration // account for the pose - if (command.check(Vocab::decode(IKINSLV_VOCAB_OPT_POSE))) + if (command.check(Vocab32::decode(IKINSLV_VOCAB_OPT_POSE))) { - int pose=command.find(Vocab::decode(IKINSLV_VOCAB_OPT_POSE)).asVocab(); + int pose=command.find(Vocab32::decode(IKINSLV_VOCAB_OPT_POSE)).asVocab32(); if (pose==IKINSLV_VOCAB_VAL_POSE_FULL) slv->set_ctrlPose(IKINCTRL_POSE_FULL); @@ -1007,7 +1007,7 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) _q[i]=CTRL_RAD2DEG*prt->chn->getAng(i); // fill the reply accordingly - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); addVectorOption(reply,IKINSLV_VOCAB_OPT_X,x); addVectorOption(reply,IKINSLV_VOCAB_OPT_Q,_q); @@ -1020,7 +1020,7 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) case IKINSLV_VOCAB_CMD_SUSP: { suspend(); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); break; } @@ -1035,14 +1035,14 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) else resume(); - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); break; } //----------------- case IKINSLV_VOCAB_CMD_STATUS: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); if (isSuspended()) reply.addString("suspended"); else if (isRunning()) @@ -1059,9 +1059,9 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) yInfo("Configuring with options: %s",options.toString().c_str()); if (open(options)) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -1069,56 +1069,56 @@ void CartesianSolver::respond(const Bottle &command, Bottle &reply) //----------------- case IKINSLV_VOCAB_CMD_HELP: { - reply.addVocab(Vocab::encode("many")); + reply.addVocab32("many"); reply.addString("***** commands"); - reply.addVocab(IKINSLV_VOCAB_CMD_GET); - reply.addVocab(IKINSLV_VOCAB_CMD_SET); - reply.addVocab(IKINSLV_VOCAB_CMD_ASK); - reply.addVocab(IKINSLV_VOCAB_CMD_SUSP); - reply.addVocab(IKINSLV_VOCAB_CMD_RUN); - reply.addVocab(IKINSLV_VOCAB_CMD_STATUS); - reply.addVocab(IKINSLV_VOCAB_CMD_CFG); - reply.addVocab(IKINSLV_VOCAB_CMD_HELP); - reply.addVocab(IKINSLV_VOCAB_CMD_QUIT); + reply.addVocab32(IKINSLV_VOCAB_CMD_GET); + reply.addVocab32(IKINSLV_VOCAB_CMD_SET); + reply.addVocab32(IKINSLV_VOCAB_CMD_ASK); + reply.addVocab32(IKINSLV_VOCAB_CMD_SUSP); + reply.addVocab32(IKINSLV_VOCAB_CMD_RUN); + reply.addVocab32(IKINSLV_VOCAB_CMD_STATUS); + reply.addVocab32(IKINSLV_VOCAB_CMD_CFG); + reply.addVocab32(IKINSLV_VOCAB_CMD_HELP); + reply.addVocab32(IKINSLV_VOCAB_CMD_QUIT); reply.addString("***** options"); - reply.addVocab(IKINSLV_VOCAB_OPT_MODE); - reply.addVocab(IKINSLV_VOCAB_OPT_POSE); - reply.addVocab(IKINSLV_VOCAB_OPT_DOF); - reply.addVocab(IKINSLV_VOCAB_OPT_LIM); - reply.addVocab(IKINSLV_VOCAB_OPT_VERB); - reply.addVocab(IKINSLV_VOCAB_OPT_TOKEN); - reply.addVocab(IKINSLV_VOCAB_OPT_REST_POS); - reply.addVocab(IKINSLV_VOCAB_OPT_REST_WEIGHTS); - reply.addVocab(IKINSLV_VOCAB_OPT_TIP_FRAME); - reply.addVocab(IKINSLV_VOCAB_OPT_TASK2); - reply.addVocab(IKINSLV_VOCAB_OPT_XD); - reply.addVocab(IKINSLV_VOCAB_OPT_X); - reply.addVocab(IKINSLV_VOCAB_OPT_Q); + reply.addVocab32(IKINSLV_VOCAB_OPT_MODE); + reply.addVocab32(IKINSLV_VOCAB_OPT_POSE); + reply.addVocab32(IKINSLV_VOCAB_OPT_DOF); + reply.addVocab32(IKINSLV_VOCAB_OPT_LIM); + reply.addVocab32(IKINSLV_VOCAB_OPT_VERB); + reply.addVocab32(IKINSLV_VOCAB_OPT_TOKEN); + reply.addVocab32(IKINSLV_VOCAB_OPT_REST_POS); + reply.addVocab32(IKINSLV_VOCAB_OPT_REST_WEIGHTS); + reply.addVocab32(IKINSLV_VOCAB_OPT_TIP_FRAME); + reply.addVocab32(IKINSLV_VOCAB_OPT_TASK2); + reply.addVocab32(IKINSLV_VOCAB_OPT_XD); + reply.addVocab32(IKINSLV_VOCAB_OPT_X); + reply.addVocab32(IKINSLV_VOCAB_OPT_Q); reply.addString("***** values"); - reply.addVocab(IKINSLV_VOCAB_VAL_POSE_FULL); - reply.addVocab(IKINSLV_VOCAB_VAL_POSE_XYZ); - reply.addVocab(IKINSLV_VOCAB_VAL_MODE_TRACK); - reply.addVocab(IKINSLV_VOCAB_VAL_MODE_SINGLE); - reply.addVocab(IKINSLV_VOCAB_VAL_ON); - reply.addVocab(IKINSLV_VOCAB_VAL_OFF); + reply.addVocab32(IKINSLV_VOCAB_VAL_POSE_FULL); + reply.addVocab32(IKINSLV_VOCAB_VAL_POSE_XYZ); + reply.addVocab32(IKINSLV_VOCAB_VAL_MODE_TRACK); + reply.addVocab32(IKINSLV_VOCAB_VAL_MODE_SINGLE); + reply.addVocab32(IKINSLV_VOCAB_VAL_ON); + reply.addVocab32(IKINSLV_VOCAB_VAL_OFF); break; } //----------------- case IKINSLV_VOCAB_CMD_QUIT: { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); close(); break; } //----------------- default: - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); } @@ -1199,9 +1199,9 @@ bool CartesianSolver::handleJointsRestPosition(const Bottle *options, Bottle *re if (options!=NULL) { size_t len=std::min((size_t)options->size(),restJntPos.length()); - for (size_t i=0; iget(i).asDouble(); + double val=CTRL_DEG2RAD*options->get(i).asFloat64(); double min=(*prt->chn)[i].getMin(); double max=(*prt->chn)[i].getMax(); @@ -1215,7 +1215,7 @@ bool CartesianSolver::handleJointsRestPosition(const Bottle *options, Bottle *re { Bottle &b=reply->addList(); for (size_t i=0; isize(),restWeights.length()); for (size_t i=0; iget(i).asInt(); + double val=options->get(i).asInt32(); restWeights[i]=std::max(val,0.0); } @@ -1243,7 +1243,7 @@ bool CartesianSolver::handleJointsRestWeights(const Bottle *options, Bottle *rep { Bottle &b=reply->addList(); for (size_t i=0; ichn->getN(); @@ -1359,7 +1359,7 @@ bool CartesianSolver::open(Searchable &options) { Vector _dof(v->size()); for (size_t i=0; i<_dof.length(); i++) - _dof[i]=v->get(i).asInt(); + _dof[i]=v->get(i).asInt32(); decodeDOF(_dof); encodeDOF(); @@ -1374,33 +1374,33 @@ bool CartesianSolver::open(Searchable &options) } // parse configuration options - period=options.check("period",Value(CARTSLV_DEFAULT_PER)).asInt(); + period=options.check("period",Value(CARTSLV_DEFAULT_PER)).asInt32(); setPeriod((double)period/1000.0); ctrlPose=IKINCTRL_POSE_FULL; - if (options.check(Vocab::decode(IKINSLV_VOCAB_OPT_POSE))) - if (options.find(Vocab::decode(IKINSLV_VOCAB_OPT_POSE)).asVocab()==IKINSLV_VOCAB_VAL_POSE_XYZ) + if (options.check(Vocab32::decode(IKINSLV_VOCAB_OPT_POSE))) + if (options.find(Vocab32::decode(IKINSLV_VOCAB_OPT_POSE)).asVocab32()==IKINSLV_VOCAB_VAL_POSE_XYZ) ctrlPose=IKINCTRL_POSE_XYZ; bool mode=false; - if (options.check(Vocab::decode(IKINSLV_VOCAB_OPT_MODE))) - if (options.find(Vocab::decode(IKINSLV_VOCAB_OPT_MODE)).asVocab()==IKINSLV_VOCAB_VAL_MODE_TRACK) + if (options.check(Vocab32::decode(IKINSLV_VOCAB_OPT_MODE))) + if (options.find(Vocab32::decode(IKINSLV_VOCAB_OPT_MODE)).asVocab32()==IKINSLV_VOCAB_VAL_MODE_TRACK) mode=true; if (options.check("verbosity")) - if (options.find("verbosity").asVocab()==IKINSLV_VOCAB_VAL_ON) + if (options.find("verbosity").asVocab32()==IKINSLV_VOCAB_VAL_ON) verbosity=true; - double tol=options.check("tol",Value(CARTSLV_DEFAULT_TOL)).asDouble(); - double constr_tol=options.check("constr_tol",Value(CARTSLV_DEFAULT_CONSTR_TOL)).asDouble(); - int maxIter=options.check("maxIter",Value(CARTSLV_DEFAULT_MAXITER)).asInt(); + double tol=options.check("tol",Value(CARTSLV_DEFAULT_TOL)).asFloat64(); + double constr_tol=options.check("constr_tol",Value(CARTSLV_DEFAULT_CONSTR_TOL)).asFloat64(); + int maxIter=options.check("maxIter",Value(CARTSLV_DEFAULT_MAXITER)).asInt32(); // instantiate the optimizer slv=new iKinIpOptMin(*prt->chn,ctrlPose,tol,constr_tol,maxIter); // instantiate solver callback object if required if (options.check("interPoints")) - if (options.find("interPoints").asVocab()==IKINSLV_VOCAB_VAL_ON) + if (options.find("interPoints").asVocab32()==IKINSLV_VOCAB_VAL_ON) clb=new SolverCallback(this); // enable scaling diff --git a/src/libraries/icubmod/bcbBattery/bcbBattery.cpp b/src/libraries/icubmod/bcbBattery/bcbBattery.cpp index c3730ccd60..300a49baef 100644 --- a/src/libraries/icubmod/bcbBattery/bcbBattery.cpp +++ b/src/libraries/icubmod/bcbBattery/bcbBattery.cpp @@ -53,7 +53,7 @@ bool BcbBattery::open(yarp::os::Searchable& config) return false; } - int period=group_general.find("thread_period").asInt(); + int period=group_general.find("thread_period").asInt32(); Property prop; std::string ps = group_serial.toString(); diff --git a/src/libraries/icubmod/bmsBattery/bmsBattery.cpp b/src/libraries/icubmod/bmsBattery/bmsBattery.cpp index 9f23d149e7..61863ce826 100644 --- a/src/libraries/icubmod/bmsBattery/bmsBattery.cpp +++ b/src/libraries/icubmod/bmsBattery/bmsBattery.cpp @@ -39,7 +39,7 @@ bool BmsBattery::open(yarp::os::Searchable& config) return false; } - int period=config.find("thread_period").asInt(); + int period=config.find("thread_period").asInt32(); setPeriod((double)period/1000.0); Property prop; diff --git a/src/libraries/icubmod/canBusAnalogSensor/CanBusAnalogSensor.cpp b/src/libraries/icubmod/canBusAnalogSensor/CanBusAnalogSensor.cpp index 872217efbd..6ae3c83be1 100644 --- a/src/libraries/icubmod/canBusAnalogSensor/CanBusAnalogSensor.cpp +++ b/src/libraries/icubmod/canBusAnalogSensor/CanBusAnalogSensor.cpp @@ -37,7 +37,7 @@ bool CanBusAnalogSensor::open(yarp::os::Searchable& config) return false; } - int period=config.find("period").asInt(); + int period=config.find("period").asInt32(); setPeriod((double)period/1000.0); Property prop; @@ -46,7 +46,7 @@ bool CanBusAnalogSensor::open(yarp::os::Searchable& config) prop.put("physDevice", config.find("physDevice").asString().c_str()); prop.put("canTxTimeout", 500); prop.put("canRxTimeout", 500); - canDeviceNum = config.find("canDeviceNum").asInt(); + canDeviceNum = config.find("canDeviceNum").asInt32(); prop.put("canDeviceNum", canDeviceNum); prop.put("canMyAddress", 0); prop.put("canTxQueueSize", CAN_DRIVER_BUFFER_SIZE); @@ -77,10 +77,10 @@ bool CanBusAnalogSensor::open(yarp::os::Searchable& config) //set the internal configuration //this->isVirtualSensor = false; - this->boardId = config.find("canAddress").asInt(); - this->useCalibration = config.find("useCalibration").asInt(); - //this->SensorFullScale = config.find("fullScale").asInt(); - unsigned int tmpFormat = config.find("format").asInt(); + this->boardId = config.find("canAddress").asInt32(); + this->useCalibration = config.find("useCalibration").asInt32(); + //this->SensorFullScale = config.find("fullScale").asInt32(); + unsigned int tmpFormat = config.find("format").asInt32(); if (tmpFormat == 8) this->dataFormat = ANALOG_FORMAT_8_BIT; else if (tmpFormat == 16) @@ -89,7 +89,7 @@ bool CanBusAnalogSensor::open(yarp::os::Searchable& config) this->dataFormat = ANALOG_FORMAT_ERR; // Parse diagnostic information - if( config.check("diagnostic") && config.find("diagnostic").asInt() == 1) + if( config.check("diagnostic") && config.find("diagnostic").asInt32() == 1) { this->diagnostic = true; } @@ -108,7 +108,7 @@ bool CanBusAnalogSensor::open(yarp::os::Searchable& config) pCanBus->canIdAdd(0x200+(boardId<<4)); //create the data vector: - this->channelsNum = config.find("channels").asInt(); + this->channelsNum = config.find("channels").asInt32(); data.resize(channelsNum); data.zero(); scaleFactor.resize(channelsNum); @@ -180,7 +180,7 @@ bool CanBusAnalogSensor::sensor_start(yarp::os::Searchable& analogConfig) if (analogConfig.check("period")) { - int period=analogConfig.find("period").asInt(); + int period=analogConfig.find("period").asInt32(); CanMessage &msg=outBuffer[0]; msg.setId(id); msg.getData()[0]=0x08; diff --git a/src/libraries/icubmod/canBusInertialMTB/CanBusInertialMTB.cpp b/src/libraries/icubmod/canBusInertialMTB/CanBusInertialMTB.cpp index 1538beb31c..17a24a8ed0 100644 --- a/src/libraries/icubmod/canBusInertialMTB/CanBusInertialMTB.cpp +++ b/src/libraries/icubmod/canBusInertialMTB/CanBusInertialMTB.cpp @@ -55,7 +55,7 @@ bool checkRequiredParamIsInt(yarp::os::Searchable& config, bool correct = config.check(paramName); if( correct ) { - correct = config.find(paramName).isInt(); + correct = config.find(paramName).isInt32(); } if( !correct ) @@ -77,7 +77,7 @@ bool checkRequiredParamIsVectorOfInt(yarp::os::Searchable& config, output_vector.resize(ids.size()); for(int i = 0; i < ids.size(); i++ ) { - output_vector[i] = ids.get(i).asInt(); + output_vector[i] = ids.get(i).asInt32(); } } @@ -147,7 +147,7 @@ bool CanBusInertialMTB::open(yarp::os::Searchable& config) int sensorPeriod = CANBUS_INERTIAL_MTB_DEFAULT_SENSOR_PERIOD; if (config.check("sensorPeriod")) { - int int_sensorPeriod = config.find("sensorPeriod").asInt(); + int int_sensorPeriod = config.find("sensorPeriod").asInt32(); if( int_sensorPeriod < 1 || int_sensorPeriod > 255 ) { yError("CanBusInertialMTB: sensorPeriod is lower than 1 or bigger then 255\n"); @@ -191,7 +191,7 @@ bool CanBusInertialMTB::open(yarp::os::Searchable& config) if (config.check("period")==true) { int period=10; - period=config.find("period").asInt(); + period=config.find("period").asInt32(); setPeriod((double)period/1000.0); } @@ -201,7 +201,7 @@ bool CanBusInertialMTB::open(yarp::os::Searchable& config) prop.put("physDevice", config.find("physDevice").asString().c_str()); prop.put("canTxTimeout", 500); prop.put("canRxTimeout", 500); - prop.put("canDeviceNum", config.find("canDeviceNum").asInt()); + prop.put("canDeviceNum", config.find("canDeviceNum").asInt32()); prop.put("canMyAddress", 0); prop.put("canTxQueueSize", CANBUS_INERTIAL_MTB_CAN_DRIVER_BUFFER_SIZE); prop.put("canRxQueueSize", CANBUS_INERTIAL_MTB_CAN_DRIVER_BUFFER_SIZE); diff --git a/src/libraries/icubmod/canBusMotionControl/CanBusMotionControl.cpp b/src/libraries/icubmod/canBusMotionControl/CanBusMotionControl.cpp index 9d6031df00..c32e5e0e24 100644 --- a/src/libraries/icubmod/canBusMotionControl/CanBusMotionControl.cpp +++ b/src/libraries/icubmod/canBusMotionControl/CanBusMotionControl.cpp @@ -480,7 +480,7 @@ void TBR_CanBackDoor::onRead(Bottle &b) std::lock_guard lck(*backdoor_mutex); //RANDAZ_TODO: parse vector b int len = b.size(); - int commandId = b.get(0).asInt(); + int commandId = b.get(0).asInt32(); int i=0; static double timePrev=Time::now(); @@ -500,33 +500,33 @@ void TBR_CanBackDoor::onRead(Bottle &b) switch (commandId) { case 1: //shoulder torque message - dval[0] = b.get(1).asDouble(); //shoulder 1 pitch - dval[1] = b.get(2).asDouble(); //shoulder 2 roll - dval[2] = b.get(3).asDouble(); //shoulder 3 yaw - dval[3] = b.get(4).asDouble(); //elbow - dval[4] = b.get(5).asDouble(); //wrist pronosupination + dval[0] = b.get(1).asFloat64(); //shoulder 1 pitch + dval[1] = b.get(2).asFloat64(); //shoulder 2 roll + dval[2] = b.get(3).asFloat64(); //shoulder 3 yaw + dval[3] = b.get(4).asFloat64(); //elbow + dval[4] = b.get(5).asFloat64(); //wrist pronosupination dval[5] = 0; break; case 2: //legs torque message - dval[0] = b.get(1).asDouble(); //hip pitch - dval[1] = b.get(2).asDouble(); //hip roll - dval[2] = b.get(3).asDouble(); //hip yaw - dval[3] = b.get(4).asDouble(); //knee - dval[4] = b.get(5).asDouble(); //ankle pitch - dval[5] = b.get(6).asDouble(); //ankle roll + dval[0] = b.get(1).asFloat64(); //hip pitch + dval[1] = b.get(2).asFloat64(); //hip roll + dval[2] = b.get(3).asFloat64(); //hip yaw + dval[3] = b.get(4).asFloat64(); //knee + dval[4] = b.get(5).asFloat64(); //ankle pitch + dval[5] = b.get(6).asFloat64(); //ankle roll break; case 3: - dval[0] = b.get(6).asDouble(); //wrist yaw - dval[1] = b.get(7).asDouble(); //wrist pitch + dval[0] = b.get(6).asFloat64(); //wrist yaw + dval[1] = b.get(7).asFloat64(); //wrist pitch dval[2] = 0; dval[3] = 0; dval[4] = 0; dval[5] = 0; break; case 4: - dval[0] = b.get(1).asDouble(); //torso yaw (respect gravity) - dval[1] = b.get(2).asDouble(); //torso roll (lateral movement) - dval[2] = b.get(3).asDouble(); //torso pitch (front-back movement) + dval[0] = b.get(1).asFloat64(); //torso yaw (respect gravity) + dval[1] = b.get(2).asFloat64(); //torso roll (lateral movement) + dval[2] = b.get(3).asFloat64(); //torso pitch (front-back movement) dval[3] = 0; dval[4] = 0; dval[5] = 0; @@ -1015,7 +1015,7 @@ bool CanBusMotionControlParameters:: setBroadCastMask(Bottle &list, int MASK) { if (list.size()==2) { - if (list.get(1).asInt()==1) + if (list.get(1).asInt32()==1) { for(int j=0;j<_njoints;j++) _broadcast_mask[j]|=(1<<(MASK-1)); @@ -1027,7 +1027,7 @@ bool CanBusMotionControlParameters:: setBroadCastMask(Bottle &list, int MASK) { for(int k=0;k<_njoints;k++) { - if ((list.get(k+1).asInt())==1) + if ((list.get(k+1).asInt32())==1) { int tmp=_axisMap[k];//remap _broadcast_mask[tmp]|=(1<<(MASK-1)); @@ -1048,20 +1048,20 @@ bool CanBusMotionControlParameters::parsePosPidsGroup_OldFormat(Bottle& pidsGrou sprintf(tmp, "Pid%d", j); Bottle &xtmp = pidsGroup.findGroup(tmp); - myPid[j].kp = xtmp.get(1).asDouble(); - myPid[j].kd = xtmp.get(2).asDouble(); - myPid[j].ki = xtmp.get(3).asDouble(); + myPid[j].kp = xtmp.get(1).asFloat64(); + myPid[j].kd = xtmp.get(2).asFloat64(); + myPid[j].ki = xtmp.get(3).asFloat64(); - myPid[j].max_int = xtmp.get(4).asDouble(); - myPid[j].max_output = xtmp.get(5).asDouble(); + myPid[j].max_int = xtmp.get(4).asFloat64(); + myPid[j].max_output = xtmp.get(5).asFloat64(); - myPid[j].scale = xtmp.get(6).asDouble(); - myPid[j].offset = xtmp.get(7).asDouble(); + myPid[j].scale = xtmp.get(6).asFloat64(); + myPid[j].offset = xtmp.get(7).asFloat64(); if (xtmp.size()==10) { - myPid[j].stiction_up_val = xtmp.get(8).asDouble(); - myPid[j].stiction_down_val = xtmp.get(9).asDouble(); + myPid[j].stiction_up_val = xtmp.get(8).asFloat64(); + myPid[j].stiction_down_val = xtmp.get(9).asFloat64(); } } return true; @@ -1076,20 +1076,20 @@ bool CanBusMotionControlParameters::parseTrqPidsGroup_OldFormat(Bottle& pidsGrou sprintf(tmp, "TPid%d", j); Bottle &xtmp = pidsGroup.findGroup(tmp); - myPid[j].kp = xtmp.get(1).asDouble(); - myPid[j].kd = xtmp.get(2).asDouble(); - myPid[j].ki = xtmp.get(3).asDouble(); + myPid[j].kp = xtmp.get(1).asFloat64(); + myPid[j].kd = xtmp.get(2).asFloat64(); + myPid[j].ki = xtmp.get(3).asFloat64(); - myPid[j].max_int = xtmp.get(4).asDouble(); - myPid[j].max_output = xtmp.get(5).asDouble(); + myPid[j].max_int = xtmp.get(4).asFloat64(); + myPid[j].max_output = xtmp.get(5).asFloat64(); - myPid[j].scale = xtmp.get(6).asDouble(); - myPid[j].offset = xtmp.get(7).asDouble(); + myPid[j].scale = xtmp.get(6).asFloat64(); + myPid[j].offset = xtmp.get(7).asFloat64(); if (xtmp.size()==10) { - myPid[j].stiction_up_val = xtmp.get(8).asDouble(); - myPid[j].stiction_down_val = xtmp.get(9).asDouble(); + myPid[j].stiction_up_val = xtmp.get(8).asFloat64(); + myPid[j].stiction_down_val = xtmp.get(9).asFloat64(); } } return true; @@ -1099,21 +1099,21 @@ bool CanBusMotionControlParameters::parsePidsGroup_NewFormat(Bottle& pidsGroup, int j=0; Bottle xtmp; - if (!validate(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].kp = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].kd = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].ki = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "maxOutput", "Pid maxOutput parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].scale = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].offset = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].stiction_up_val = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].stiction_down_val = xtmp.get(j+1).asDouble(); + if (!validate(pidsGroup, xtmp, "kp", "Pid kp parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].kp = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "kd", "Pid kd parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].kd = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "ki", "Pid kp parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].ki = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "maxInt", "Pid maxInt parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "maxOutput", "Pid maxOutput parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "shift", "Pid shift parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].scale = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "ko", "Pid ko parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].offset = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "stictionUp", "Pid stictionUp", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "stictionDwn", "Pid stictionDwn", _njoints+1)) return false; for (j=0; j<_njoints; j++) myPid[j].stiction_down_val = xtmp.get(j+1).asFloat64(); //optional kff xtmp = pidsGroup.findGroup("kff"); if (!xtmp.isNull()) { - for (j=0; j<_njoints; j++) myPid[j].kff = xtmp.get(j+1).asDouble(); + for (j=0; j<_njoints; j++) myPid[j].kff = xtmp.get(j+1).asFloat64(); } else { @@ -1127,8 +1127,8 @@ bool CanBusMotionControlParameters::parseImpedanceGroup_NewFormat(Bottle& pidsGr { int j=0; Bottle xtmp; - if (!validate(pidsGroup, xtmp, "stiffness", "Pid stiffness parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].stiffness = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "damping", "Pid damping parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].damping = xtmp.get(j+1).asDouble(); + if (!validate(pidsGroup, xtmp, "stiffness", "Pid stiffness parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].stiffness = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "damping", "Pid damping parameter", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].damping = xtmp.get(j+1).asFloat64(); return true; } @@ -1137,14 +1137,14 @@ bool CanBusMotionControlParameters::parseDebugGroup_NewFormat(Bottle& pidsGroup, int j=0; Bottle xtmp; - if (!validate(pidsGroup, xtmp, "debug0", "debug0", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[0] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug1", "debug1", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[1] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug2", "debug2", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[2] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug3", "debug3", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[3] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug4", "debug4", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[4] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug5", "debug5", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[5] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug6", "debug6", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[6] = xtmp.get(j+1).asDouble(); - if (!validate(pidsGroup, xtmp, "debug7", "debug7", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[7] = xtmp.get(j+1).asDouble(); + if (!validate(pidsGroup, xtmp, "debug0", "debug0", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[0] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug1", "debug1", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[1] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug2", "debug2", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[2] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug3", "debug3", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[3] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug4", "debug4", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[4] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug5", "debug5", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[5] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug6", "debug6", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[6] = xtmp.get(j+1).asFloat64(); + if (!validate(pidsGroup, xtmp, "debug7", "debug7", _njoints+1)) return false; for (j=0; j<_njoints; j++) vals[j].data[7] = xtmp.get(j+1).asFloat64(); return true; } @@ -1158,7 +1158,7 @@ bool CanBusMotionControlParameters::fromConfig(yarp::os::Searchable &p) std::string dbg_string = p.toString().c_str(); int i; int nj = p.findGroup("GENERAL").check("Joints",Value(1), - "Number of degrees of freedom").asInt(); + "Number of degrees of freedom").asInt32(); alloc(nj); // Check useRawEncoderData = do not use calibration data! @@ -1236,10 +1236,10 @@ bool CanBusMotionControlParameters::fromConfig(yarp::os::Searchable &p) if (canGroup.check("CanForcedDeviceNum")) { - _networkN=canGroup.find("CanForcedDeviceNum").asInt(); + _networkN=canGroup.find("CanForcedDeviceNum").asInt32(); } else - _networkN=canGroup.check("CanDeviceNum",Value(-1), "numeric identifier of device").asInt(); + _networkN=canGroup.check("CanDeviceNum",Value(-1), "numeric identifier of device").asInt32(); // yDebug<_bemfGain[j] = xtmp.get(j+1).asDouble();} + {for (j=0;j_bemfGain[j] = xtmp.get(j+1).asFloat64();} else {for (j=0;j_bemfGain[j] = 0; yWarning ("TORQUE_PIDS: 'kbemf' param missing");} xtmp = trqControlGroup.findGroup("ktau"); if (!xtmp.isNull()) - {for (j=0;j_ktau[j] = xtmp.get(j+1).asDouble();} + {for (j=0;j_ktau[j] = xtmp.get(j+1).asFloat64();} else {for (j=0;j_ktau[j] = 1.0; yWarning ("TORQUE_PIDS: 'ktau' param missing");} xtmp = trqControlGroup.findGroup("filterType"); if (!xtmp.isNull()) - {for (j=0;j_filterType[j] = xtmp.get(j+1).asInt();} + {for (j=0;j_filterType[j] = xtmp.get(j+1).asInt32();} else {for (j=0;j_filterType[j] = 3; yWarning ("TORQUE_PIDS: 'filterType' param missing");} @@ -1621,7 +1621,7 @@ bool CanBusMotionControlParameters::fromConfig(yarp::os::Searchable &p) // motor oveload current if (!validate(limits, xtmp, "motorOverloadCurrents","a list of current limits", nj+1)) return false; - for(i=1;isetDeviceId(deviceid); bool isVirtualSensor=false; - char analogId=analogConfig.find("CanAddress").asInt(); - char analogFormat=analogConfig.find("Format").asInt(); - int analogChannels=analogConfig.find("Channels").asInt(); - int analogCalibration=analogConfig.find("UseCalibration").asInt(); - //int SensorFullScale=analogConfig.find("FullScale").asInt(); + char analogId=analogConfig.find("CanAddress").asInt32(); + char analogFormat=analogConfig.find("Format").asInt32(); + int analogChannels=analogConfig.find("Channels").asInt32(); + int analogCalibration=analogConfig.find("UseCalibration").asInt32(); + //int SensorFullScale=analogConfig.find("FullScale").asInt32(); if (analogConfig.check("PortName")) { isVirtualSensor = true; std::string virtualPortName = analogConfig.find("PortName").asString(); - bool canEchoEnabled = analogConfig.find("CanEcho").asInt(); + bool canEchoEnabled = analogConfig.find("CanEcho").asInt32(); analogSensor->backDoor = new TBR_CanBackDoor(); analogSensor->backDoor->setUp(&res, &_mutex, canEchoEnabled, analogSensor); std::string rn("/"); @@ -2815,7 +2815,7 @@ TBR_AnalogSensor *CanBusMotionControl::instantiateAnalog(yarp::os::Searchable& c if (analogConfig.check("Period")) { - int period=analogConfig.find("Period").asInt(); + int period=analogConfig.find("Period").asInt32(); res.startPacket(); res.startPacket(); @@ -4082,14 +4082,14 @@ bool CanBusMotionControl::setControlModeRaw(const int j, const int mode) ret = true; break; } yarp::os::Time::delay(0.010); - if (timeout >0) yWarning ("setControlModeRaw delay (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), j, yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(mode).c_str()); + if (timeout >0) yWarning ("setControlModeRaw delay (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), j, yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(mode).c_str()); timeout++; } while (timeout < 10); if (timeout>=10) { ret = false; - yError ("100ms Timeout occured in setControlModeRaw (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), j, yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(mode).c_str()); + yError ("100ms Timeout occured in setControlModeRaw (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), j, yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(mode).c_str()); } return ret; @@ -4121,14 +4121,14 @@ bool CanBusMotionControl::setControlModesRaw(const int n_joints, const int *join ret = true; break; } yarp::os::Time::delay(0.010); - if (timeout >0) yWarning ("setControlModesRaw delay (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), joints[i], yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(modes[i]).c_str()); + if (timeout >0) yWarning ("setControlModesRaw delay (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), joints[i], yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(modes[i]).c_str()); timeout++; } while (timeout < 10); if (timeout>=10) { ret = false; - yError ("100ms Timeout occured in setControlModesRaw(M) (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), joints[i], yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(modes[i]).c_str()); + yError ("100ms Timeout occured in setControlModesRaw(M) (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), joints[i], yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(modes[i]).c_str()); } } @@ -4149,12 +4149,12 @@ bool CanBusMotionControl::getRemoteVariableRaw(std::string key, yarp::os::Bottle CanBusResources& res = RES(system_resources); if (key == "filterType") { - Bottle& r = val.addList(); for (int i = 0; i< res.getJoints(); i++) { int tmp = 0; getFilterTypeRaw(i, &tmp); r.addInt(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< res.getJoints(); i++) { int tmp = 0; getFilterTypeRaw(i, &tmp); r.addInt32(tmp); } return true; } if (key == "PWMLimit") { - Bottle& r = val.addList(); for (int i = 0; i< res.getJoints(); i++) { double tmp = 0; getPWMLimitRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< res.getJoints(); i++) { double tmp = 0; getPWMLimitRaw(i, &tmp); r.addFloat64(tmp); } return true; } yWarning("getRemoteVariable(): Unknown variable %s", key.c_str()); @@ -4177,7 +4177,7 @@ bool CanBusMotionControl::setRemoteVariableRaw(std::string key, const yarp::os:: { for (int i = 0; i < r.getJoints(); i++) { - int filter_type = val.get(i).asInt(); + int filter_type = val.get(i).asInt32(); this->setFilterTypeRaw(i, filter_type); } return true; @@ -4186,7 +4186,7 @@ bool CanBusMotionControl::setRemoteVariableRaw(std::string key, const yarp::os:: { for (int i = 0; i < r.getJoints(); i++) { - double limit = val.get(i).asDouble(); + double limit = val.get(i).asFloat64(); this->setPWMLimitRaw(i, (int)(limit)); } return true; @@ -4252,14 +4252,14 @@ bool CanBusMotionControl::setControlModesRaw(int *modes) ret = true; break; } yarp::os::Time::delay(0.010); - if (timeout >0) yWarning ("setControlModesRaw delay (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), i, yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(modes[i]).c_str()); + if (timeout >0) yWarning ("setControlModesRaw delay (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), i, yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(modes[i]).c_str()); timeout++; } while (timeout < 10); if (timeout>=10) { ret = false; - yError ("100ms Timeout occured in setControlModesRaw (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), i, yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(modes[i]).c_str()); + yError ("100ms Timeout occured in setControlModesRaw (%s j:%d), current mode: %s, requested: %s", networkName.c_str(), i, yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(modes[i]).c_str()); } } diff --git a/src/libraries/icubmod/canBusSkin/CanBusSkin.cpp b/src/libraries/icubmod/canBusSkin/CanBusSkin.cpp index fe6cffff03..b167ce0363 100644 --- a/src/libraries/icubmod/canBusSkin/CanBusSkin.cpp +++ b/src/libraries/icubmod/canBusSkin/CanBusSkin.cpp @@ -58,15 +58,15 @@ bool CanBusSkin::open(yarp::os::Searchable& config) } - _canBusNum = config.find("canDeviceNum").asInt(); + _canBusNum = config.find("canDeviceNum").asInt32(); char name[80]; sprintf(name, "canSkin on bus %d", _canBusNum); _cfgReader.setName(name); - int period=config.find("period").asInt(); + int period=config.find("period").asInt32(); setPeriod((double)period/1000.0); - netID = config.find("canDeviceNum").asInt(); + netID = config.find("canDeviceNum").asInt32(); Bottle ids=config.findGroup("skinCanIds").tail(); @@ -78,7 +78,7 @@ bool CanBusSkin::open(yarp::os::Searchable& config) for (int i=0; iisVirtualSensor = false; - this->boardId = config.find("canAddress").asInt(); - this->canId = config.find("canDeviceNum").asInt(); - this->channelsNum = config.find("channels").asInt(); - this->useCalibration = (config.find("useCalibration").asInt()==1); - unsigned int tmpFormat = config.find("format").asInt(); + this->boardId = config.find("canAddress").asInt32(); + this->canId = config.find("canDeviceNum").asInt32(); + this->channelsNum = config.find("channels").asInt32(); + this->useCalibration = (config.find("useCalibration").asInt32()==1); + unsigned int tmpFormat = config.find("format").asInt32(); if (tmpFormat == 8) this->dataFormat = ANALOG_FORMAT_8_BIT; else if (tmpFormat == 16) @@ -98,13 +98,13 @@ bool CanBusVirtualAnalogSensor::open(yarp::os::Searchable& config) pCanBus->canIdAdd(0x200+(boardId<<4)); //create the data vector: - int chan=config.find("channels").asInt(); + int chan=config.find("channels").asInt32(); data.resize(channelsNum); Bottle fullScaleTmp = config.findGroup("fullScale"); this->scaleFactor.resize(channelsNum); for (unsigned int i=0; iscaleFactor[i] = tmp; } @@ -247,7 +247,7 @@ bool CanBusVirtualAnalogSensor::sensor_start(yarp::os::Searchable& analogConfig) if (analogConfig.check("period")) { - int period=analogConfig.find("period").asInt(); + int period=analogConfig.find("period").asInt32(); CanMessage &msg=outBuffer[0]; msg.setId(id); msg.getData()[0]=0x08; diff --git a/src/libraries/icubmod/cartesianController/ClientCartesianController.cpp b/src/libraries/icubmod/cartesianController/ClientCartesianController.cpp index ec3ef8c647..c1e979c89d 100644 --- a/src/libraries/icubmod/cartesianController/ClientCartesianController.cpp +++ b/src/libraries/icubmod/cartesianController/ClientCartesianController.cpp @@ -105,7 +105,7 @@ bool ClientCartesianController::open(Searchable &config) carrier=config.check("carrier",Value("udp")).asString(); if (config.check("timeout")) - timeout=config.find("timeout").asDouble(); + timeout=config.find("timeout").asFloat64(); portCmd.open(local+"/command:o"); portState.open(local+"/state:i"); @@ -120,7 +120,7 @@ bool ClientCartesianController::open(Searchable &config) getInfoHelper(info); if (info.check("server_version")) { - double server_version=info.find("server_version").asDouble(); + double server_version=info.find("server_version").asFloat64(); if (server_version!=CARTCTRL_CLIENT_VER) { yError("version mismatch => server(%g) != client(%g); please update accordingly", @@ -148,8 +148,8 @@ bool ClientCartesianController::open(Searchable &config) { Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_ISSOLVERON); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_ISSOLVERON); if (!portRpc.write(command,reply)) { @@ -158,9 +158,9 @@ bool ClientCartesianController::open(Searchable &config) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) if (reply.size()>1) - if (reply.get(1).asVocab()==IKINCARTCTRL_VOCAB_VAL_TRUE) + if (reply.get(1).asVocab32()==IKINCARTCTRL_VOCAB_VAL_TRUE) return connected=true; yError("unable to connect to solver!"); @@ -209,10 +209,10 @@ bool ClientCartesianController::setTrackingMode(const bool f) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_MODE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_MODE); - command.addVocab(f?IKINCARTCTRL_VOCAB_VAL_MODE_TRACK:IKINCARTCTRL_VOCAB_VAL_MODE_SINGLE); + command.addVocab32(f?IKINCARTCTRL_VOCAB_VAL_MODE_TRACK:IKINCARTCTRL_VOCAB_VAL_MODE_SINGLE); if (!portRpc.write(command,reply)) { @@ -220,7 +220,7 @@ bool ClientCartesianController::setTrackingMode(const bool f) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -231,8 +231,8 @@ bool ClientCartesianController::getTrackingMode(bool *f) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_MODE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_MODE); if (!portRpc.write(command,reply)) { @@ -240,9 +240,9 @@ bool ClientCartesianController::getTrackingMode(bool *f) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { - int mode=reply.get(1).asVocab(); + int mode=reply.get(1).asVocab32(); if (mode==IKINCARTCTRL_VOCAB_VAL_MODE_TRACK) *f=true; @@ -265,10 +265,10 @@ bool ClientCartesianController::setReferenceMode(const bool f) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REFERENCE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REFERENCE); - command.addVocab(f?IKINCARTCTRL_VOCAB_VAL_TRUE:IKINCARTCTRL_VOCAB_VAL_FALSE); + command.addVocab32(f?IKINCARTCTRL_VOCAB_VAL_TRUE:IKINCARTCTRL_VOCAB_VAL_FALSE); if (!portRpc.write(command,reply)) { @@ -276,7 +276,7 @@ bool ClientCartesianController::setReferenceMode(const bool f) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -287,8 +287,8 @@ bool ClientCartesianController::getReferenceMode(bool *f) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REFERENCE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REFERENCE); if (!portRpc.write(command,reply)) { @@ -296,9 +296,9 @@ bool ClientCartesianController::getReferenceMode(bool *f) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { - int mode=reply.get(1).asVocab(); + int mode=reply.get(1).asVocab32(); if (mode==IKINCARTCTRL_VOCAB_VAL_TRUE) *f=true; @@ -321,8 +321,8 @@ bool ClientCartesianController::setPosePriority(const string &p) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_PRIO); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_PRIO); command.addString(p); if (!portRpc.write(command,reply)) @@ -331,7 +331,7 @@ bool ClientCartesianController::setPosePriority(const string &p) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -342,8 +342,8 @@ bool ClientCartesianController::getPosePriority(string &p) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_PRIO); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_PRIO); if (!portRpc.write(command,reply)) { @@ -351,7 +351,7 @@ bool ClientCartesianController::getPosePriority(string &p) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { p=reply.get(1).asString(); return true; @@ -401,9 +401,9 @@ bool ClientCartesianController::getPose(const int axis, Vector &x, Vector &o, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_POSE); - command.addInt(axis); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_POSE); + command.addInt32(axis); if (!portRpc.write(command,reply)) { @@ -411,7 +411,7 @@ bool ClientCartesianController::getPose(const int axis, Vector &x, Vector &o, return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *posePart=reply.get(1).asList()) { @@ -419,17 +419,17 @@ bool ClientCartesianController::getPose(const int axis, Vector &x, Vector &o, o.resize(posePart->size()-x.length()); for (size_t i=0; iget(i).asDouble(); + x[i]=posePart->get(i).asFloat64(); for (size_t i=0; iget(x.length()+i).asDouble(); + o[i]=posePart->get(x.length()+i).asFloat64(); if ((reply.size()>2) && (stamp!=NULL)) { if (Bottle *stampPart=reply.get(2).asList()) { - Stamp tmpStamp(stampPart->get(0).asInt(), - stampPart->get(1).asDouble()); + Stamp tmpStamp(stampPart->get(0).asInt32(), + stampPart->get(1).asFloat64()); *stamp=tmpStamp; } @@ -453,16 +453,16 @@ bool ClientCartesianController::goToPose(const Vector &xd, const Vector &od, Bottle &command=portCmd.prepare(); command.clear(); - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GO); - command.addVocab(IKINCARTCTRL_VOCAB_VAL_POSE_FULL); - command.addDouble(t); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GO); + command.addVocab32(IKINCARTCTRL_VOCAB_VAL_POSE_FULL); + command.addFloat64(t); Bottle &xdesPart=command.addList(); for (int i=0; i<3; i++) - xdesPart.addDouble(xd[i]); + xdesPart.addFloat64(xd[i]); for (int i=0; i<4; i++) - xdesPart.addDouble(od[i]); + xdesPart.addFloat64(od[i]); // send command portCmd.writeStrict(); @@ -479,13 +479,13 @@ bool ClientCartesianController::goToPosition(const Vector &xd, const double t) Bottle &command=portCmd.prepare(); command.clear(); - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GO); - command.addVocab(IKINCARTCTRL_VOCAB_VAL_POSE_XYZ); - command.addDouble(t); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GO); + command.addVocab32(IKINCARTCTRL_VOCAB_VAL_POSE_XYZ); + command.addFloat64(t); Bottle &xdesPart=command.addList(); for (int i=0; i<3; i++) - xdesPart.addDouble(xd[i]); + xdesPart.addFloat64(xd[i]); // send command portCmd.writeStrict(); @@ -501,16 +501,16 @@ bool ClientCartesianController::goToPoseSync(const Vector &xd, const Vector &od, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GO); - command.addVocab(IKINCARTCTRL_VOCAB_VAL_POSE_FULL); - command.addDouble(t); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GO); + command.addVocab32(IKINCARTCTRL_VOCAB_VAL_POSE_FULL); + command.addFloat64(t); Bottle &xdesPart=command.addList(); for (int i=0; i<3; i++) - xdesPart.addDouble(xd[i]); + xdesPart.addFloat64(xd[i]); for (int i=0; i<4; i++) - xdesPart.addDouble(od[i]); + xdesPart.addFloat64(od[i]); if (!portRpc.write(command,reply)) { @@ -518,7 +518,7 @@ bool ClientCartesianController::goToPoseSync(const Vector &xd, const Vector &od, return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -529,13 +529,13 @@ bool ClientCartesianController::goToPositionSync(const Vector &xd, const double return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GO); - command.addVocab(IKINCARTCTRL_VOCAB_VAL_POSE_XYZ); - command.addDouble(t); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GO); + command.addVocab32(IKINCARTCTRL_VOCAB_VAL_POSE_XYZ); + command.addFloat64(t); Bottle &xdesPart=command.addList(); for (int i=0; i<3; i++) - xdesPart.addDouble(xd[i]); + xdesPart.addFloat64(xd[i]); if (!portRpc.write(command,reply)) { @@ -543,7 +543,7 @@ bool ClientCartesianController::goToPositionSync(const Vector &xd, const double return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -555,8 +555,8 @@ bool ClientCartesianController::getDesired(Vector &xdhat, Vector &odhat, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_DES); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_DES); if (!portRpc.write(command,reply)) { @@ -584,7 +584,7 @@ bool ClientCartesianController::askForPose(const Vector &xd, const Vector &od, for (size_t i=0; isize()); for (size_t i=0; iget(i).asDouble(); + curDof[i]=dofPart->get(i).asFloat64(); return true; } @@ -715,12 +715,12 @@ bool ClientCartesianController::setDOF(const Vector &newDof, Vector &curDof) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_DOF); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_DOF); Bottle &dofPart=command.addList(); for (size_t i=0; isize()); for (size_t i=0; iget(i).asDouble(); + curDof[i]=dofPart->get(i).asFloat64(); return true; } @@ -752,8 +752,8 @@ bool ClientCartesianController::getRestPos(Vector &curRestPos) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REST_POS); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REST_POS); if (!portRpc.write(command,reply)) { @@ -761,14 +761,14 @@ bool ClientCartesianController::getRestPos(Vector &curRestPos) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *restPart=reply.get(1).asList()) { curRestPos.resize(restPart->size()); for (size_t i=0; iget(i).asDouble(); + curRestPos[i]=restPart->get(i).asFloat64(); return true; } @@ -786,8 +786,8 @@ bool ClientCartesianController::setRestPos(const Vector &newRestPos, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REST_POS); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REST_POS); command.addList().read(newRestPos); if (!portRpc.write(command,reply)) @@ -796,13 +796,13 @@ bool ClientCartesianController::setRestPos(const Vector &newRestPos, return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *restPart=reply.get(1).asList()) { curRestPos.resize(restPart->size()); for (size_t i=0; iget(i).asDouble(); + curRestPos[i]=restPart->get(i).asFloat64(); return true; } } @@ -818,8 +818,8 @@ bool ClientCartesianController::getRestWeights(Vector &curRestWeights) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REST_WEIGHTS); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REST_WEIGHTS); if (!portRpc.write(command,reply)) { @@ -827,14 +827,14 @@ bool ClientCartesianController::getRestWeights(Vector &curRestWeights) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *restPart=reply.get(1).asList()) { curRestWeights.resize(restPart->size()); for (size_t i=0; iget(i).asDouble(); + curRestWeights[i]=restPart->get(i).asFloat64(); return true; } @@ -852,8 +852,8 @@ bool ClientCartesianController::setRestWeights(const Vector &newRestWeights, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REST_WEIGHTS); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REST_WEIGHTS); command.addList().read(newRestWeights); if (!portRpc.write(command,reply)) @@ -862,13 +862,13 @@ bool ClientCartesianController::setRestWeights(const Vector &newRestWeights, return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *restPart=reply.get(1).asList()) { curRestWeights.resize(restPart->size()); for (size_t i=0; iget(i).asDouble(); + curRestWeights[i]=restPart->get(i).asFloat64(); return true; } } @@ -885,9 +885,9 @@ bool ClientCartesianController::getLimits(const int axis, double *min, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_LIM); - command.addInt(axis); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_LIM); + command.addInt32(axis); if (!portRpc.write(command,reply)) { @@ -895,12 +895,12 @@ bool ClientCartesianController::getLimits(const int axis, double *min, return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>2) { - *min=reply.get(1).asDouble(); - *max=reply.get(2).asDouble(); + *min=reply.get(1).asFloat64(); + *max=reply.get(2).asFloat64(); return true; } } @@ -917,11 +917,11 @@ bool ClientCartesianController::setLimits(const int axis, const double min, return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_LIM); - command.addInt(axis); - command.addDouble(min); - command.addDouble(max); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_LIM); + command.addInt32(axis); + command.addFloat64(min); + command.addFloat64(max); if (!portRpc.write(command,reply)) { @@ -929,7 +929,7 @@ bool ClientCartesianController::setLimits(const int axis, const double min, return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -940,8 +940,8 @@ bool ClientCartesianController::getTrajTime(double *t) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TIME); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TIME); if (!portRpc.write(command,reply)) { @@ -949,11 +949,11 @@ bool ClientCartesianController::getTrajTime(double *t) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>1) { - *t=reply.get(1).asDouble(); + *t=reply.get(1).asFloat64(); return true; } } @@ -969,9 +969,9 @@ bool ClientCartesianController::setTrajTime(const double t) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TIME); - command.addDouble(t); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TIME); + command.addFloat64(t); if (!portRpc.write(command,reply)) { @@ -979,7 +979,7 @@ bool ClientCartesianController::setTrajTime(const double t) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -990,8 +990,8 @@ bool ClientCartesianController::getInTargetTol(double *tol) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TOL); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TOL); if (!portRpc.write(command,reply)) { @@ -999,11 +999,11 @@ bool ClientCartesianController::getInTargetTol(double *tol) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>1) { - *tol=reply.get(1).asDouble(); + *tol=reply.get(1).asFloat64(); return true; } } @@ -1019,9 +1019,9 @@ bool ClientCartesianController::setInTargetTol(const double tol) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TOL); - command.addDouble(tol); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TOL); + command.addFloat64(tol); if (!portRpc.write(command,reply)) { @@ -1029,7 +1029,7 @@ bool ClientCartesianController::setInTargetTol(const double tol) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -1040,8 +1040,8 @@ bool ClientCartesianController::getJointsVelocities(Vector &qdot) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_QDOT); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_QDOT); if (!portRpc.write(command,reply)) { @@ -1049,14 +1049,14 @@ bool ClientCartesianController::getJointsVelocities(Vector &qdot) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *qdotPart=reply.get(1).asList()) { qdot.resize(qdotPart->size()); for (size_t i=0; iget(i).asDouble(); + qdot[i]=qdotPart->get(i).asFloat64(); return true; } @@ -1073,8 +1073,8 @@ bool ClientCartesianController::getTaskVelocities(Vector &xdot, Vector &odot) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_XDOT); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_XDOT); if (!portRpc.write(command,reply)) { @@ -1082,7 +1082,7 @@ bool ClientCartesianController::getTaskVelocities(Vector &xdot, Vector &odot) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *xdotPart=reply.get(1).asList()) { @@ -1090,10 +1090,10 @@ bool ClientCartesianController::getTaskVelocities(Vector &xdot, Vector &odot) odot.resize(xdotPart->size()-xdot.length()); for (size_t i=0; iget(i).asDouble(); + xdot[i]=xdotPart->get(i).asFloat64(); for (size_t i=0; iget(xdot.length()+i).asDouble(); + odot[i]=xdotPart->get(xdot.length()+i).asFloat64(); return true; } @@ -1113,14 +1113,14 @@ bool ClientCartesianController::setTaskVelocities(const Vector &xdot, Bottle &command=portCmd.prepare(); command.clear(); - command.addVocab(IKINCARTCTRL_VOCAB_CMD_TASKVEL); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_TASKVEL); Bottle &xdotPart=command.addList(); for (int i=0; i<3; i++) - xdotPart.addDouble(xdot[i]); + xdotPart.addFloat64(xdot[i]); for (int i=0; i<4; i++) - xdotPart.addDouble(odot[i]); + xdotPart.addFloat64(odot[i]); // send command portCmd.writeStrict(); @@ -1135,15 +1135,15 @@ bool ClientCartesianController::attachTipFrame(const Vector &x, const Vector &o) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TIP_FRAME); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TIP_FRAME); Bottle &tipPart=command.addList(); for (int i=0; i<3; i++) - tipPart.addDouble(x[i]); + tipPart.addFloat64(x[i]); for (int i=0; i<4; i++) - tipPart.addDouble(o[i]); + tipPart.addFloat64(o[i]); if (!portRpc.write(command,reply)) { @@ -1151,7 +1151,7 @@ bool ClientCartesianController::attachTipFrame(const Vector &x, const Vector &o) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { // mandatory refresh of the local pose (blocking) if (Vector *v=portState.read(true)) @@ -1175,8 +1175,8 @@ bool ClientCartesianController::getTipFrame(Vector &x, Vector &o) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TIP_FRAME); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TIP_FRAME); if (!portRpc.write(command,reply)) { @@ -1184,7 +1184,7 @@ bool ClientCartesianController::getTipFrame(Vector &x, Vector &o) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (Bottle *tipPart=reply.get(1).asList()) { @@ -1192,10 +1192,10 @@ bool ClientCartesianController::getTipFrame(Vector &x, Vector &o) o.resize(tipPart->size()-x.length()); for (size_t i=0; iget(i).asDouble(); + x[i]=tipPart->get(i).asFloat64(); for (size_t i=0; iget(x.length()+i).asDouble(); + o[i]=tipPart->get(x.length()+i).asFloat64(); return true; } @@ -1219,8 +1219,8 @@ bool ClientCartesianController::checkMotionDone(bool *f) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_MOTIONDONE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_MOTIONDONE); if (!portRpc.write(command,reply)) { @@ -1228,11 +1228,11 @@ bool ClientCartesianController::checkMotionDone(bool *f) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>1) { - int flag=reply.get(1).asVocab(); + int flag=reply.get(1).asVocab32(); if (flag==IKINCARTCTRL_VOCAB_VAL_TRUE) *f=true; @@ -1273,7 +1273,7 @@ bool ClientCartesianController::stopControl() return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_STOP); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_STOP); if (!portRpc.write(command,reply)) { @@ -1281,7 +1281,7 @@ bool ClientCartesianController::stopControl() return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -1292,7 +1292,7 @@ bool ClientCartesianController::storeContext(int *id) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_STORE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_STORE); if (!portRpc.write(command,reply)) { @@ -1300,11 +1300,11 @@ bool ClientCartesianController::storeContext(int *id) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>1) { - contextIdList.insert(*id=reply.get(1).asInt()); + contextIdList.insert(*id=reply.get(1).asInt32()); return true; } } @@ -1320,8 +1320,8 @@ bool ClientCartesianController::restoreContext(const int id) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_RESTORE); - command.addInt(id); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_RESTORE); + command.addInt32(id); if (!portRpc.write(command,reply)) { @@ -1329,7 +1329,7 @@ bool ClientCartesianController::restoreContext(const int id) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -1340,8 +1340,8 @@ bool ClientCartesianController::deleteContext(const int id) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_DELETE); - command.addList().addInt(id); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_DELETE); + command.addList().addInt32(id); if (!portRpc.write(command,reply)) { @@ -1349,7 +1349,7 @@ bool ClientCartesianController::deleteContext(const int id) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { contextIdList.erase(id); return true; @@ -1366,10 +1366,10 @@ bool ClientCartesianController::deleteContexts() return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_DELETE); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_DELETE); Bottle &ids=command.addList(); for (set::iterator itr=contextIdList.begin(); itr!=contextIdList.end(); itr++) - ids.addInt(*itr); + ids.addInt32(*itr); if (!portRpc.write(command,reply)) { @@ -1379,7 +1379,7 @@ bool ClientCartesianController::deleteContexts() contextIdList.clear(); - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -1387,8 +1387,8 @@ bool ClientCartesianController::deleteContexts() bool ClientCartesianController::getInfoHelper(Bottle &info) { Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_INFO); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_INFO); if (!portRpc.write(command,reply)) { @@ -1396,7 +1396,7 @@ bool ClientCartesianController::getInfoHelper(Bottle &info) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>1) { @@ -1425,8 +1425,8 @@ bool ClientCartesianController::getInfo(Bottle &info) void ClientCartesianController::eventHandling(Bottle &event) { string type=event.get(0).asString(); - double time=event.get(1).asDouble(); - double checkPoint=(type=="motion-ongoing")?event.get(2).asDouble():-1.0; + double time=event.get(1).asFloat64(); + double checkPoint=(type=="motion-ongoing")?event.get(2).asFloat64():-1.0; map::iterator itr; // rise the all-events callback @@ -1485,10 +1485,10 @@ bool ClientCartesianController::registerEvent(CartesianEvent &event) double checkPoint=event.cartesianEventParameters.motionOngoingCheckPoint; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_EVENT); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_REGISTER); - command.addVocab(IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING); - command.addDouble(checkPoint); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_EVENT); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_REGISTER); + command.addVocab32(IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING); + command.addFloat64(checkPoint); if (!portRpc.write(command,reply)) { @@ -1496,7 +1496,7 @@ bool ClientCartesianController::registerEvent(CartesianEvent &event) return false; } - if (reply.get(0).asVocab()!=IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()!=IKINCARTCTRL_VOCAB_REP_ACK) return false; ostringstream ss; @@ -1521,10 +1521,10 @@ bool ClientCartesianController::unregisterEvent(CartesianEvent &event) double checkPoint=event.cartesianEventParameters.motionOngoingCheckPoint; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_EVENT); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_UNREGISTER); - command.addVocab(IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING); - command.addDouble(checkPoint); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_EVENT); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_UNREGISTER); + command.addVocab32(IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING); + command.addFloat64(checkPoint); if (!portRpc.write(command,reply)) { @@ -1532,7 +1532,7 @@ bool ClientCartesianController::unregisterEvent(CartesianEvent &event) return false; } - if (reply.get(0).asVocab()!=IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()!=IKINCARTCTRL_VOCAB_REP_ACK) return false; ostringstream ss; @@ -1552,8 +1552,8 @@ bool ClientCartesianController::tweakSet(const Bottle &options) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_SET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TWEAK); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_SET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TWEAK); command.addList()=options; if (!portRpc.write(command,reply)) @@ -1562,7 +1562,7 @@ bool ClientCartesianController::tweakSet(const Bottle &options) return false; } - return (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK); + return (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK); } @@ -1573,8 +1573,8 @@ bool ClientCartesianController::tweakGet(Bottle &options) return false; Bottle command, reply; - command.addVocab(IKINCARTCTRL_VOCAB_CMD_GET); - command.addVocab(IKINCARTCTRL_VOCAB_OPT_TWEAK); + command.addVocab32(IKINCARTCTRL_VOCAB_CMD_GET); + command.addVocab32(IKINCARTCTRL_VOCAB_OPT_TWEAK); if (!portRpc.write(command,reply)) { @@ -1582,7 +1582,7 @@ bool ClientCartesianController::tweakGet(Bottle &options) return false; } - if (reply.get(0).asVocab()==IKINCARTCTRL_VOCAB_REP_ACK) + if (reply.get(0).asVocab32()==IKINCARTCTRL_VOCAB_REP_ACK) { if (reply.size()>1) { diff --git a/src/libraries/icubmod/cartesianController/CommonCartesianController.h b/src/libraries/icubmod/cartesianController/CommonCartesianController.h index be352c6f2c..143329909a 100644 --- a/src/libraries/icubmod/cartesianController/CommonCartesianController.h +++ b/src/libraries/icubmod/cartesianController/CommonCartesianController.h @@ -21,49 +21,49 @@ #include -#define IKINCARTCTRL_VOCAB_CMD_GET yarp::os::createVocab('g','e','t') -#define IKINCARTCTRL_VOCAB_CMD_SET yarp::os::createVocab('s','e','t') -#define IKINCARTCTRL_VOCAB_CMD_ASK yarp::os::createVocab('a','s','k') -#define IKINCARTCTRL_VOCAB_CMD_STORE yarp::os::createVocab('s','t','o','r') -#define IKINCARTCTRL_VOCAB_CMD_RESTORE yarp::os::createVocab('r','e','s','t') -#define IKINCARTCTRL_VOCAB_CMD_DELETE yarp::os::createVocab('d','e','l') -#define IKINCARTCTRL_VOCAB_CMD_GO yarp::os::createVocab('g','o') -#define IKINCARTCTRL_VOCAB_CMD_TASKVEL yarp::os::createVocab('t','v','e','l') -#define IKINCARTCTRL_VOCAB_CMD_STOP yarp::os::createVocab('s','t','o','p') -#define IKINCARTCTRL_VOCAB_CMD_EVENT yarp::os::createVocab('e','v','e','n') -#define IKINCARTCTRL_VOCAB_OPT_MODE yarp::os::createVocab('m','o','d','e') -#define IKINCARTCTRL_VOCAB_OPT_REFERENCE yarp::os::createVocab('r','e','f','e') -#define IKINCARTCTRL_VOCAB_OPT_PRIO yarp::os::createVocab('p','r','i','o') -#define IKINCARTCTRL_VOCAB_OPT_TIME yarp::os::createVocab('t','i','m','e') -#define IKINCARTCTRL_VOCAB_OPT_TOL yarp::os::createVocab('t','o','l') -#define IKINCARTCTRL_VOCAB_OPT_DOF yarp::os::createVocab('d','o','f') -#define IKINCARTCTRL_VOCAB_OPT_REST_POS yarp::os::createVocab('r','e','s','p') -#define IKINCARTCTRL_VOCAB_OPT_REST_WEIGHTS yarp::os::createVocab('r','e','s','w') -#define IKINCARTCTRL_VOCAB_OPT_DES yarp::os::createVocab('d','e','s') -#define IKINCARTCTRL_VOCAB_OPT_LIM yarp::os::createVocab('l','i','m') -#define IKINCARTCTRL_VOCAB_OPT_XD yarp::os::createVocab('x','d') -#define IKINCARTCTRL_VOCAB_OPT_X yarp::os::createVocab('x') -#define IKINCARTCTRL_VOCAB_OPT_Q yarp::os::createVocab('q') -#define IKINCARTCTRL_VOCAB_OPT_XDOT yarp::os::createVocab('x','d','o','t') -#define IKINCARTCTRL_VOCAB_OPT_QDOT yarp::os::createVocab('q','d','o','t') -#define IKINCARTCTRL_VOCAB_OPT_TIP_FRAME yarp::os::createVocab('t','i','p') -#define IKINCARTCTRL_VOCAB_OPT_MOTIONDONE yarp::os::createVocab('d','o','n','e') -#define IKINCARTCTRL_VOCAB_OPT_ISSOLVERON yarp::os::createVocab('i','s','o','n') -#define IKINCARTCTRL_VOCAB_OPT_POSE yarp::os::createVocab('p','o','s','e') -#define IKINCARTCTRL_VOCAB_OPT_INFO yarp::os::createVocab('i','n','f','o') -#define IKINCARTCTRL_VOCAB_OPT_TWEAK yarp::os::createVocab('t','w','e','a') -#define IKINCARTCTRL_VOCAB_OPT_REGISTER yarp::os::createVocab('r','e','g','i') -#define IKINCARTCTRL_VOCAB_OPT_UNREGISTER yarp::os::createVocab('u','n','r','e') -#define IKINCARTCTRL_VOCAB_OPT_LIST yarp::os::createVocab('l','i','s','t') -#define IKINCARTCTRL_VOCAB_VAL_POSE_FULL yarp::os::createVocab('f','u','l','l') -#define IKINCARTCTRL_VOCAB_VAL_POSE_XYZ yarp::os::createVocab('x','y','z') -#define IKINCARTCTRL_VOCAB_VAL_MODE_TRACK yarp::os::createVocab('c','o','n','t') -#define IKINCARTCTRL_VOCAB_VAL_MODE_SINGLE yarp::os::createVocab('s','h','o','t') -#define IKINCARTCTRL_VOCAB_VAL_TRUE yarp::os::createVocab('t','r','u','e') -#define IKINCARTCTRL_VOCAB_VAL_FALSE yarp::os::createVocab('f','a','l','s') -#define IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING yarp::os::createVocab('o','g','o','i') -#define IKINCARTCTRL_VOCAB_REP_ACK yarp::os::createVocab('a','c','k') -#define IKINCARTCTRL_VOCAB_REP_NACK yarp::os::createVocab('n','a','c','k') +#define IKINCARTCTRL_VOCAB_CMD_GET yarp::os::createVocab32('g','e','t') +#define IKINCARTCTRL_VOCAB_CMD_SET yarp::os::createVocab32('s','e','t') +#define IKINCARTCTRL_VOCAB_CMD_ASK yarp::os::createVocab32('a','s','k') +#define IKINCARTCTRL_VOCAB_CMD_STORE yarp::os::createVocab32('s','t','o','r') +#define IKINCARTCTRL_VOCAB_CMD_RESTORE yarp::os::createVocab32('r','e','s','t') +#define IKINCARTCTRL_VOCAB_CMD_DELETE yarp::os::createVocab32('d','e','l') +#define IKINCARTCTRL_VOCAB_CMD_GO yarp::os::createVocab32('g','o') +#define IKINCARTCTRL_VOCAB_CMD_TASKVEL yarp::os::createVocab32('t','v','e','l') +#define IKINCARTCTRL_VOCAB_CMD_STOP yarp::os::createVocab32('s','t','o','p') +#define IKINCARTCTRL_VOCAB_CMD_EVENT yarp::os::createVocab32('e','v','e','n') +#define IKINCARTCTRL_VOCAB_OPT_MODE yarp::os::createVocab32('m','o','d','e') +#define IKINCARTCTRL_VOCAB_OPT_REFERENCE yarp::os::createVocab32('r','e','f','e') +#define IKINCARTCTRL_VOCAB_OPT_PRIO yarp::os::createVocab32('p','r','i','o') +#define IKINCARTCTRL_VOCAB_OPT_TIME yarp::os::createVocab32('t','i','m','e') +#define IKINCARTCTRL_VOCAB_OPT_TOL yarp::os::createVocab32('t','o','l') +#define IKINCARTCTRL_VOCAB_OPT_DOF yarp::os::createVocab32('d','o','f') +#define IKINCARTCTRL_VOCAB_OPT_REST_POS yarp::os::createVocab32('r','e','s','p') +#define IKINCARTCTRL_VOCAB_OPT_REST_WEIGHTS yarp::os::createVocab32('r','e','s','w') +#define IKINCARTCTRL_VOCAB_OPT_DES yarp::os::createVocab32('d','e','s') +#define IKINCARTCTRL_VOCAB_OPT_LIM yarp::os::createVocab32('l','i','m') +#define IKINCARTCTRL_VOCAB_OPT_XD yarp::os::createVocab32('x','d') +#define IKINCARTCTRL_VOCAB_OPT_X yarp::os::createVocab32('x') +#define IKINCARTCTRL_VOCAB_OPT_Q yarp::os::createVocab32('q') +#define IKINCARTCTRL_VOCAB_OPT_XDOT yarp::os::createVocab32('x','d','o','t') +#define IKINCARTCTRL_VOCAB_OPT_QDOT yarp::os::createVocab32('q','d','o','t') +#define IKINCARTCTRL_VOCAB_OPT_TIP_FRAME yarp::os::createVocab32('t','i','p') +#define IKINCARTCTRL_VOCAB_OPT_MOTIONDONE yarp::os::createVocab32('d','o','n','e') +#define IKINCARTCTRL_VOCAB_OPT_ISSOLVERON yarp::os::createVocab32('i','s','o','n') +#define IKINCARTCTRL_VOCAB_OPT_POSE yarp::os::createVocab32('p','o','s','e') +#define IKINCARTCTRL_VOCAB_OPT_INFO yarp::os::createVocab32('i','n','f','o') +#define IKINCARTCTRL_VOCAB_OPT_TWEAK yarp::os::createVocab32('t','w','e','a') +#define IKINCARTCTRL_VOCAB_OPT_REGISTER yarp::os::createVocab32('r','e','g','i') +#define IKINCARTCTRL_VOCAB_OPT_UNREGISTER yarp::os::createVocab32('u','n','r','e') +#define IKINCARTCTRL_VOCAB_OPT_LIST yarp::os::createVocab32('l','i','s','t') +#define IKINCARTCTRL_VOCAB_VAL_POSE_FULL yarp::os::createVocab32('f','u','l','l') +#define IKINCARTCTRL_VOCAB_VAL_POSE_XYZ yarp::os::createVocab32('x','y','z') +#define IKINCARTCTRL_VOCAB_VAL_MODE_TRACK yarp::os::createVocab32('c','o','n','t') +#define IKINCARTCTRL_VOCAB_VAL_MODE_SINGLE yarp::os::createVocab32('s','h','o','t') +#define IKINCARTCTRL_VOCAB_VAL_TRUE yarp::os::createVocab32('t','r','u','e') +#define IKINCARTCTRL_VOCAB_VAL_FALSE yarp::os::createVocab32('f','a','l','s') +#define IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING yarp::os::createVocab32('o','g','o','i') +#define IKINCARTCTRL_VOCAB_REP_ACK yarp::os::createVocab32('a','c','k') +#define IKINCARTCTRL_VOCAB_REP_NACK yarp::os::createVocab32('n','a','c','k') #endif diff --git a/src/libraries/icubmod/cartesianController/ServerCartesianController.cpp b/src/libraries/icubmod/cartesianController/ServerCartesianController.cpp index 83a85ab560..9e354e03bb 100644 --- a/src/libraries/icubmod/cartesianController/ServerCartesianController.cpp +++ b/src/libraries/icubmod/cartesianController/ServerCartesianController.cpp @@ -83,10 +83,10 @@ void CartesianCtrlCommandPort::onRead(Bottle &command) { if (command.size()) { - if ((command.get(0).asVocab()==IKINCARTCTRL_VOCAB_CMD_GO) && (command.size()>3)) + if ((command.get(0).asVocab32()==IKINCARTCTRL_VOCAB_CMD_GO) && (command.size()>3)) { - int pose=command.get(1).asVocab(); - double t=command.get(2).asDouble(); + int pose=command.get(1).asVocab32(); + double t=command.get(2).asFloat64(); Bottle *v=command.get(3).asList(); if (pose==IKINCARTCTRL_VOCAB_VAL_POSE_FULL) @@ -95,10 +95,10 @@ void CartesianCtrlCommandPort::onRead(Bottle &command) Vector od(v->size()-xd.length()); for (size_t i=0; iget(i).asDouble(); + xd[i]=v->get(i).asFloat64(); for (size_t i=0; iget(xd.length()+i).asDouble(); + od[i]=v->get(xd.length()+i).asFloat64(); server->goToPose(xd,od,t); } @@ -107,12 +107,12 @@ void CartesianCtrlCommandPort::onRead(Bottle &command) Vector xd(v->size()); for (int i=0; isize(); i++) - xd[i]=v->get(i).asDouble(); + xd[i]=v->get(i).asFloat64(); server->goToPosition(xd,t); } } - else if ((command.get(0).asVocab()==IKINCARTCTRL_VOCAB_CMD_TASKVEL) && (command.size()>1)) + else if ((command.get(0).asVocab32()==IKINCARTCTRL_VOCAB_CMD_TASKVEL) && (command.size()>1)) { Bottle *v=command.get(1).asList(); @@ -120,10 +120,10 @@ void CartesianCtrlCommandPort::onRead(Bottle &command) Vector odot(v->size()-xdot.length()); for (size_t i=0; iget(i).asDouble(); + xdot[i]=v->get(i).asFloat64(); for (size_t i=0; iget(xdot.length()+i).asDouble(); + odot[i]=v->get(xdot.length()+i).asFloat64(); server->setTaskVelocities(xdot,odot); } @@ -289,13 +289,13 @@ void ServerCartesianController::closePorts() bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { if (command.size()) - switch (command.get(0).asVocab()) + switch (command.get(0).asVocab32()) { //----------------- case IKINCARTCTRL_VOCAB_CMD_STOP: { stopControl(); - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); break; } @@ -304,13 +304,13 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { if (command.size()>3) { - int pose=command.get(1).asVocab(); - double t=command.get(2).asDouble(); + int pose=command.get(1).asVocab32(); + double t=command.get(2).asFloat64(); Bottle *v=command.get(3).asList(); Vector xd(v->size()); for (int i=0; isize(); i++) - xd[i]=v->get(i).asDouble(); + xd[i]=v->get(i).asFloat64(); bool ret=false; @@ -334,13 +334,13 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) unique_lock lck(mtx_syncEvent); cv_syncEvent.wait(lck); - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -354,7 +354,7 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) if (!portSlvRpc.write(slvCommand,reply)) { yError("%s: unable to get reply from solver!",ctrlName.c_str()); - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } break; @@ -366,11 +366,11 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) int id; if (storeContext(&id)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); - reply.addInt(id); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addInt32(id); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -380,11 +380,11 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { if (command.size()>1) { - int id=command.get(1).asInt(); + int id=command.get(1).asInt32(); if (restoreContext(id)) - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } break; @@ -397,9 +397,9 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { Bottle *ids=command.get(1).asList(); if (deleteContexts(ids)) - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } break; @@ -409,7 +409,7 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) case IKINSLV_VOCAB_CMD_GET: { if (command.size()>1) - switch (command.get(1).asVocab()) + switch (command.get(1).asVocab32()) { //----------------- case IKINCARTCTRL_VOCAB_OPT_MODE: @@ -417,15 +417,15 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) bool flag; if (getTrackingMode(&flag)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); if (flag) - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_MODE_TRACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_MODE_TRACK); else - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_MODE_SINGLE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_MODE_SINGLE); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -436,15 +436,15 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) bool flag; if (getReferenceMode(&flag)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); if (flag) - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_TRUE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_TRUE); else - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_FALSE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_FALSE); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -455,11 +455,11 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) string priority; if (getPosePriority(priority)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); reply.addString(priority); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -470,11 +470,11 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) double time; if (getTrajTime(&time)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); - reply.addDouble(time); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addFloat64(time); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -485,11 +485,11 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) double tol; if (getInTargetTol(&tol)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); - reply.addDouble(tol); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addFloat64(tol); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -500,15 +500,15 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) bool flag; if (checkMotionDone(&flag)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); if (flag) - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_TRUE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_TRUE); else - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_FALSE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_FALSE); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -516,12 +516,12 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) //----------------- case IKINCARTCTRL_VOCAB_OPT_ISSOLVERON: { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); if (connected) - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_TRUE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_TRUE); else - reply.addVocab(IKINCARTCTRL_VOCAB_VAL_FALSE); + reply.addVocab32(IKINCARTCTRL_VOCAB_VAL_FALSE); break; } @@ -531,20 +531,20 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { if (command.size()>2) { - int axis=command.get(2).asInt(); + int axis=command.get(2).asInt32(); double min, max; if (getLimits(axis,&min,&max)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); - reply.addDouble(min); - reply.addDouble(max); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addFloat64(min); + reply.addFloat64(max); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -555,14 +555,14 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) Vector curDof; if (getDOF(curDof)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); Bottle &dofPart=reply.addList(); for (size_t i=0; igetN()); int cnt=0; @@ -625,11 +625,11 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) Vector qdot; if (getJointsVelocities(qdot)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); reply.addList().read(qdot); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -640,17 +640,17 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) Vector xdot, odot; if (getTaskVelocities(xdot,odot)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); Bottle &xdotPart=reply.addList(); for (size_t i=0; i2) { - int axis=command.get(2).asInt(); + int axis=command.get(2).asInt32(); Vector x,o; Stamp stamp; if (getPose(axis,x,o,&stamp)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); Bottle &posePart=reply.addList(); for (size_t i=0; i2) - switch (command.get(1).asVocab()) + switch (command.get(1).asVocab32()) { //----------------- case IKINCARTCTRL_VOCAB_OPT_MODE: { - int mode=command.get(2).asVocab(); + int mode=command.get(2).asVocab32(); bool ret=false; if (mode==IKINCARTCTRL_VOCAB_VAL_MODE_TRACK) @@ -767,9 +767,9 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) ret=setTrackingMode(false); if (ret) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -777,7 +777,7 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) //----------------- case IKINCARTCTRL_VOCAB_OPT_REFERENCE: { - int mode=command.get(2).asVocab(); + int mode=command.get(2).asVocab32(); bool ret=false; if (mode==IKINCARTCTRL_VOCAB_VAL_TRUE) @@ -786,9 +786,9 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) ret=setReferenceMode(false); if (ret) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -798,9 +798,9 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { string priority=command.get(2).asString(); if (setPosePriority(priority)) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -808,10 +808,10 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) //----------------- case IKINCARTCTRL_VOCAB_OPT_TIME: { - if (setTrajTime(command.get(2).asDouble())) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + if (setTrajTime(command.get(2).asFloat64())) + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -819,10 +819,10 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) //----------------- case IKINCARTCTRL_VOCAB_OPT_TOL: { - if (setInTargetTol(command.get(2).asDouble())) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + if (setInTargetTol(command.get(2).asFloat64())) + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } @@ -832,17 +832,17 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) { if (command.size()>4) { - int axis=command.get(2).asInt(); - double min=command.get(3).asDouble(); - double max=command.get(4).asDouble(); + int axis=command.get(2).asInt32(); + double min=command.get(3).asFloat64(); + double max=command.get(4).asFloat64(); if (setLimits(axis,min,max)) - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -856,21 +856,21 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) Vector curDof; for (int i=0; isize(); i++) - newDof[i]=b->get(i).asDouble(); + newDof[i]=b->get(i).asFloat64(); if (setDOF(newDof,curDof)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); Bottle &dofPart=reply.addList(); for (size_t i=0; isize(); i++) - newRestPos[i]=b->get(i).asDouble(); + newRestPos[i]=b->get(i).asFloat64(); if (setRestPos(newRestPos,curRestPos)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); reply.addList().read(curRestPos); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -909,18 +909,18 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) Vector curRestWeights; for (int i=0; isize(); i++) - newRestWeights[i]=b->get(i).asDouble(); + newRestWeights[i]=b->get(i).asFloat64(); if (setRestWeights(newRestWeights,curRestWeights)) { - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); reply.addList().read(curRestWeights); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -936,21 +936,21 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) Vector o(b->size()-x.length()); for (size_t i=0; iget(i).asDouble(); + x[i]=b->get(i).asFloat64(); for (size_t i=0; iget(i+x.length()).asDouble(); + o[i]=b->get(i+x.length()).asFloat64(); if (attachTipFrame(x,o)) - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -961,22 +961,22 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) if (Bottle *options=command.get(2).asList()) { if (tweakSet(*options)) - reply.addVocab(IKINCARTCTRL_VOCAB_REP_ACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_ACK); else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } //----------------- default: - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } @@ -985,77 +985,77 @@ bool ServerCartesianController::respond(const Bottle &command, Bottle &reply) case IKINCARTCTRL_VOCAB_CMD_EVENT: { if (command.size()>2) - switch (command.get(1).asVocab()) + switch (command.get(1).asVocab32()) { //----------------- case IKINCARTCTRL_VOCAB_OPT_REGISTER: { - int mode=command.get(2).asVocab(); + int mode=command.get(2).asVocab32(); if ((mode==IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING) && (command.size()>3)) { - double checkPoint=command.get(3).asDouble(); + double checkPoint=command.get(3).asFloat64(); if (registerMotionOngoingEvent(checkPoint)) { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); break; } } - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } //----------------- case IKINCARTCTRL_VOCAB_OPT_UNREGISTER: { - int mode=command.get(2).asVocab(); + int mode=command.get(2).asVocab32(); if ((mode==IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING) && (command.size()>3)) { - double checkPoint=command.get(3).asDouble(); + double checkPoint=command.get(3).asFloat64(); if (unregisterMotionOngoingEvent(checkPoint)) { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); break; } } - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } //----------------- case IKINCARTCTRL_VOCAB_OPT_LIST: { - int mode=command.get(2).asVocab(); + int mode=command.get(2).asVocab32(); if (mode==IKINCARTCTRL_VOCAB_VAL_EVENT_ONGOING) { - reply.addVocab(IKINSLV_VOCAB_REP_ACK); + reply.addVocab32(IKINSLV_VOCAB_REP_ACK); reply.addList()=listMotionOngoingEvents(); } else - reply.addVocab(IKINSLV_VOCAB_REP_NACK); + reply.addVocab32(IKINSLV_VOCAB_REP_NACK); break; } //----------------- default: - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); break; } //----------------- default: - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); } else - reply.addVocab(IKINCARTCTRL_VOCAB_REP_NACK); + reply.addVocab32(IKINCARTCTRL_VOCAB_REP_NACK); return true; } @@ -1222,7 +1222,7 @@ bool ServerCartesianController::getNewTarget() bool isNew=false; Vector _xdes, _qdes; - if (b1->check(Vocab::decode(IKINSLV_VOCAB_OPT_X))) + if (b1->check(Vocab32::decode(IKINSLV_VOCAB_OPT_X))) { Bottle *b2=getEndEffectorPoseOption(*b1); int l1=(int)b2->size(); @@ -1231,13 +1231,13 @@ bool ServerCartesianController::getNewTarget() _xdes.resize(len); for (int i=0; iget(i).asDouble(); + _xdes[i]=b2->get(i).asFloat64(); if (!(_xdes==xdes)) isNew=true; } - if (b1->check(Vocab::decode(IKINSLV_VOCAB_OPT_Q))) + if (b1->check(Vocab32::decode(IKINSLV_VOCAB_OPT_Q))) { Bottle *b2=getJointsOption(*b1); int l1=(int)b2->size(); @@ -1246,7 +1246,7 @@ bool ServerCartesianController::getNewTarget() _qdes.resize(len); for (int i=0; iget(i).asDouble(); + _qdes[i]=CTRL_DEG2RAD*b2->get(i).asFloat64(); if (_qdes.length()!=ctrl->get_dim()) { @@ -1374,7 +1374,7 @@ Bottle ServerCartesianController::sendCtrlCmdMultipleJointsPosition() ostringstream ss; ss<velocityMove(joint,0.0); - info.addDouble(0.0); + info.addFloat64(0.0); } } @@ -1832,7 +1832,7 @@ bool ServerCartesianController::open(Searchable &config) if (optGeneral.check("NumberOfDrivers")) { - numDrv=optGeneral.find("NumberOfDrivers").asInt(); + numDrv=optGeneral.find("NumberOfDrivers").asInt32(); if (numDrv<=0) { yError("NumberOfDrivers shall be positive"); @@ -1857,10 +1857,10 @@ bool ServerCartesianController::open(Searchable &config) } if (optGeneral.check("ControllerPeriod")) - setPeriod((double)optGeneral.find("ControllerPeriod").asInt()/1000.0); + setPeriod((double)optGeneral.find("ControllerPeriod").asInt32()/1000.0); taskRefVelPeriodFactor=optGeneral.check("TaskRefVelPeriodFactor", - Value(CARTCTRL_DEFAULT_TASKVEL_PERFACTOR)).asInt(); + Value(CARTCTRL_DEFAULT_TASKVEL_PERFACTOR)).asInt32(); posDirectEnabled=optGeneral.check("PositionControl", Value(CARTCTRL_DEFAULT_POSCTRL)).asString()=="on"; @@ -1930,7 +1930,7 @@ bool ServerCartesianController::open(Searchable &config) for (int j=0; jsize(); j++) { - desc.minAbsVels[j]=pMinAbsVelsBottle->get(j).asDouble(); + desc.minAbsVels[j]=pMinAbsVelsBottle->get(j).asFloat64(); if (desc.minAbsVels[j]<0.0) desc.minAbsVels[j]=-desc.minAbsVels[j]; @@ -2288,8 +2288,8 @@ bool ServerCartesianController::connectToSolver() // keep solver and controller status aligned at start-up Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_DOF); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_DOF); // send command to solver and wait for reply if (!portSlvRpc.write(command,reply)) @@ -2303,7 +2303,7 @@ bool ServerCartesianController::connectToSolver() Bottle *rxDofPart=reply.get(1).asList(); for (int i=0; isize(); i++) { - if (rxDofPart->get(i).asInt()!=0) + if (rxDofPart->get(i).asInt32()!=0) { chainState->releaseLink(i); chainPlan->releaseLink(i); @@ -2372,15 +2372,15 @@ bool ServerCartesianController::setTrackingModeHelper(const bool f) if (connected) { Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_MODE); - command.addVocab(f?IKINSLV_VOCAB_VAL_MODE_TRACK:IKINSLV_VOCAB_VAL_MODE_SINGLE); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_MODE); + command.addVocab32(f?IKINSLV_VOCAB_VAL_MODE_TRACK:IKINSLV_VOCAB_VAL_MODE_SINGLE); // send command to solver and wait for reply bool ret=false; if (!portSlvRpc.write(command,reply)) yError("%s: unable to get reply from solver!",ctrlName.c_str()); - else if (reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK) + else if (reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK) { trackingMode=f; ret=true; @@ -2449,13 +2449,13 @@ bool ServerCartesianController::setPosePriority(const string &p) lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_PRIO); - command.addVocab(p=="position"?IKINSLV_VOCAB_VAL_PRIO_XYZ:IKINSLV_VOCAB_VAL_PRIO_ANG); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_PRIO); + command.addVocab32(p=="position"?IKINSLV_VOCAB_VAL_PRIO_XYZ:IKINSLV_VOCAB_VAL_PRIO_ANG); // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) - ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK); + ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK); else yError("%s: unable to get reply from solver!",ctrlName.c_str()); } @@ -2471,14 +2471,14 @@ bool ServerCartesianController::getPosePriority(string &p) if (connected) { Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_PRIO); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_PRIO); // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) { - if (ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK)) - p=(reply.get(1).asVocab()==IKINSLV_VOCAB_VAL_PRIO_XYZ)? + if (ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK)) + p=(reply.get(1).asVocab32()==IKINSLV_VOCAB_VAL_PRIO_XYZ)? "position":"orientation"; } else @@ -2655,7 +2655,7 @@ bool ServerCartesianController::askForPose(const Vector &xd, const Vector &od, for (size_t i=0; i lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_ASK); + command.addVocab32(IKINSLV_VOCAB_CMD_ASK); addVectorOption(command,IKINSLV_VOCAB_OPT_XD,xd); addPoseOption(command,IKINCTRL_POSE_XYZ); @@ -2740,7 +2740,7 @@ bool ServerCartesianController::askForPosition(const Vector &q0, const Vector &x lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_ASK); + command.addVocab32(IKINSLV_VOCAB_CMD_ASK); addVectorOption(command,IKINSLV_VOCAB_OPT_XD,xd); addVectorOption(command,IKINSLV_VOCAB_OPT_Q,q0); addPoseOption(command,IKINCTRL_POSE_XYZ); @@ -2782,11 +2782,11 @@ bool ServerCartesianController::setDOF(const Vector &newDof, Vector &curDof) lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_DOF); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_DOF); Bottle &txDofPart=command.addList(); for (size_t i=0; isize()); for (int i=0; isize(); i++) { - curDof[i]=rxDofPart->get(i).asInt(); + curDof[i]=rxDofPart->get(i).asInt32(); if (curDof[i]!=0.0) { chainState->releaseLink(i); @@ -2833,8 +2833,8 @@ bool ServerCartesianController::getRestPos(Vector &curRestPos) lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_REST_POS); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_REST_POS); // send command to solver and wait for reply bool ret=false; @@ -2843,7 +2843,7 @@ bool ServerCartesianController::getRestPos(Vector &curRestPos) Bottle *rxRestPart=reply.get(1).asList(); curRestPos.resize(rxRestPart->size()); for (int i=0; isize(); i++) - curRestPos[i]=rxRestPart->get(i).asDouble(); + curRestPos[i]=rxRestPart->get(i).asFloat64(); ret=true; } @@ -2866,8 +2866,8 @@ bool ServerCartesianController::setRestPos(const Vector &newRestPos, lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_REST_POS); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_REST_POS); command.addList().read(newRestPos); // send command to solver and wait for reply @@ -2877,7 +2877,7 @@ bool ServerCartesianController::setRestPos(const Vector &newRestPos, Bottle *rxRestPart=reply.get(1).asList(); curRestPos.resize(rxRestPart->size()); for (int i=0; isize(); i++) - curRestPos[i]=rxRestPart->get(i).asDouble(); + curRestPos[i]=rxRestPart->get(i).asFloat64(); ret=true; } @@ -2899,8 +2899,8 @@ bool ServerCartesianController::getRestWeights(Vector &curRestWeights) lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_REST_WEIGHTS); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_REST_WEIGHTS); // send command to solver and wait for reply bool ret=false; @@ -2909,7 +2909,7 @@ bool ServerCartesianController::getRestWeights(Vector &curRestWeights) Bottle *rxRestPart=reply.get(1).asList(); curRestWeights.resize(rxRestPart->size()); for (int i=0; isize(); i++) - curRestWeights[i]=rxRestPart->get(i).asDouble(); + curRestWeights[i]=rxRestPart->get(i).asFloat64(); ret=true; } @@ -2932,8 +2932,8 @@ bool ServerCartesianController::setRestWeights(const Vector &newRestWeights, lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_REST_WEIGHTS); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_REST_WEIGHTS); command.addList().read(newRestWeights); // send command to solver and wait for reply @@ -2943,7 +2943,7 @@ bool ServerCartesianController::setRestWeights(const Vector &newRestWeights, Bottle *rxRestPart=reply.get(1).asList(); curRestWeights.resize(rxRestPart->size()); for (int i=0; isize(); i++) - curRestWeights[i]=rxRestPart->get(i).asDouble(); + curRestWeights[i]=rxRestPart->get(i).asFloat64(); ret=true; } @@ -2968,17 +2968,17 @@ bool ServerCartesianController::getLimits(const int axis, double *min, if (axis<(int)chainState->getN()) { Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_LIM); - command.addInt(axis); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_LIM); + command.addInt32(axis); // send command to solver and wait for reply if (!portSlvRpc.write(command,reply)) yError("%s: unable to get reply from solver!",ctrlName.c_str()); - else if (reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK) + else if (reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK) { - *min=reply.get(1).asDouble(); - *max=reply.get(2).asDouble(); + *min=reply.get(1).asFloat64(); + *max=reply.get(2).asFloat64(); ret=true; } } @@ -2998,15 +2998,15 @@ bool ServerCartesianController::setLimits(const int axis, const double min, lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_LIM); - command.addInt(axis); - command.addDouble(min); - command.addDouble(max); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_LIM); + command.addInt32(axis); + command.addFloat64(min); + command.addFloat64(max); // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) - ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK); + ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK); else yError("%s: unable to get reply from solver!",ctrlName.c_str()); } @@ -3207,21 +3207,21 @@ bool ServerCartesianController::attachTipFrame(const Vector &x, const Vector &o) lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_TIP_FRAME); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_TIP_FRAME); Bottle &txTipPart=command.addList(); for (int i=0; i<3; i++) - txTipPart.addDouble(x[i]); + txTipPart.addFloat64(x[i]); for (int i=0; i<4; i++) - txTipPart.addDouble(o[i]); + txTipPart.addFloat64(o[i]); // send command to solver and wait for reply bool ret=false; if (portSlvRpc.write(command,reply)) { - if (ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK)) + if (ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK)) { Matrix HN=axis2dcm(o); HN(0,3)=x[0]; @@ -3465,7 +3465,7 @@ bool ServerCartesianController::deleteContexts(Bottle *contextIdList) for (int i=0; isize(); i++) { - int id=contextIdList->get(i).asInt(); + int id=contextIdList->get(i).asInt32(); map::iterator itr=contextMap.find(id); if (itr!=contextMap.end()) contextMap.erase(itr); @@ -3487,7 +3487,7 @@ bool ServerCartesianController::getInfo(Bottle &info) Bottle &serverVer=info.addList(); serverVer.addString("server_version"); - serverVer.addDouble(CARTCTRL_SERVER_VER); + serverVer.addFloat64(CARTCTRL_SERVER_VER); string kinPartStr(kinPart); string type=limbState->getType(); @@ -3499,7 +3499,7 @@ bool ServerCartesianController::getInfo(Bottle &info) Bottle &partVer=info.addList(); partVer.addString(kinPartStr+"_version"); - partVer.addDouble(hwVer); + partVer.addFloat64(hwVer); Bottle &partType=info.addList(); partType.addString(kinPartStr+"_type"); @@ -3534,9 +3534,9 @@ void ServerCartesianController::notifyEvent(const string &event, ev.clear(); ev.addString(event); - ev.addDouble(time); + ev.addFloat64(time); if (checkPoint>=0.0) - ev.addDouble(checkPoint); + ev.addFloat64(checkPoint); eventInfo.update(time); portEvent.setEnvelope(eventInfo); @@ -3698,7 +3698,7 @@ Bottle ServerCartesianController::listMotionOngoingEvents() lock_guard lck(mtx); for (multiset::iterator itr=motionOngoingEvents.begin(); itr!=motionOngoingEvents.end(); itr++) - events.addDouble(*itr); + events.addFloat64(*itr); return events; } @@ -3711,13 +3711,13 @@ bool ServerCartesianController::getTask2ndOptions(Value &v) if (connected) { Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_TASK2); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_TASK2); // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) { - if (ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK)) + if (ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK)) v=reply.get(1); } else @@ -3737,13 +3737,13 @@ bool ServerCartesianController::setTask2ndOptions(const Value &v) lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_TASK2); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_TASK2); command.add(v); // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) - ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK); + ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK); else yError("%s: unable to get reply from solver!",ctrlName.c_str()); } @@ -3759,13 +3759,13 @@ bool ServerCartesianController::getSolverConvergenceOptions(Bottle &options) if (connected) { Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_GET); - command.addVocab(IKINSLV_VOCAB_OPT_CONVERGENCE); + command.addVocab32(IKINSLV_VOCAB_CMD_GET); + command.addVocab32(IKINSLV_VOCAB_OPT_CONVERGENCE); // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) { - if (ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK)) + if (ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK)) options=*reply.get(1).asList(); } else @@ -3785,13 +3785,13 @@ bool ServerCartesianController::setSolverConvergenceOptions(const Bottle &option lock_guard lck(mtx); Bottle command, reply; - command.addVocab(IKINSLV_VOCAB_CMD_SET); - command.addVocab(IKINSLV_VOCAB_OPT_CONVERGENCE); + command.addVocab32(IKINSLV_VOCAB_CMD_SET); + command.addVocab32(IKINSLV_VOCAB_OPT_CONVERGENCE); command.addList()=options; // send command to solver and wait for reply if (portSlvRpc.write(command,reply)) - ret=(reply.get(0).asVocab()==IKINSLV_VOCAB_REP_ACK); + ret=(reply.get(0).asVocab32()==IKINSLV_VOCAB_REP_ACK); else yError("%s: unable to get reply from solver!",ctrlName.c_str()); } @@ -3807,7 +3807,7 @@ bool ServerCartesianController::tweakSet(const Bottle &options) // straightness if (options.check("straightness")) - ctrl->set_gamma(options.find("straightness").asDouble()); + ctrl->set_gamma(options.find("straightness").asFloat64()); // secondary task if (options.check("task_2")) @@ -3835,7 +3835,7 @@ bool ServerCartesianController::tweakGet(Bottle &options) // straightness Bottle &straightness=options.addList(); straightness.addString("straightness"); - straightness.addDouble(ctrl->get_gamma()); + straightness.addFloat64(ctrl->get_gamma()); // secondary task Value v; diff --git a/src/libraries/icubmod/cartesianController/SmithPredictor.cpp b/src/libraries/icubmod/cartesianController/SmithPredictor.cpp index 929b83eef7..a2df38f995 100644 --- a/src/libraries/icubmod/cartesianController/SmithPredictor.cpp +++ b/src/libraries/icubmod/cartesianController/SmithPredictor.cpp @@ -82,7 +82,7 @@ void SmithPredictor::configure(const Property &options, iKinChain &chain) for (unsigned int i=0; i); - double Ts=options.check("Ts",Value(0.01)).asDouble(); + double Ts=options.check("Ts",Value(0.01)).asFloat64(); Vector y0(chain.getDOF()); Matrix lim(chain.getDOF(),2); @@ -106,20 +106,20 @@ void SmithPredictor::configure(const Property &options, iKinChain &chain) if (Bottle *params=options.find(entry_str).asList()) { if (params->check("Kp")) - Kp[i]=params->find("Kp").asDouble(); + Kp[i]=params->find("Kp").asFloat64(); if (params->check("Tz")) - Tz[i]=params->find("Tz").asDouble(); + Tz[i]=params->find("Tz").asFloat64(); if (params->check("Tw")) - Tw[i]=params->find("Tw").asDouble(); + Tw[i]=params->find("Tw").asFloat64(); if (params->check("Zeta")) - Zeta[i]=params->find("Zeta").asDouble(); + Zeta[i]=params->find("Zeta").asFloat64(); if (params->check("Td")) { - int depth=(int)ceil(params->find("Td").asDouble()/Ts); + int depth=(int)ceil(params->find("Td").asFloat64()/Ts); tappedDelays[i]->assign(depth,y0[i]); } } diff --git a/src/libraries/icubmod/cfw2Can/Cfw2Can.cpp b/src/libraries/icubmod/cfw2Can/Cfw2Can.cpp index 0e1e5abba7..d379413d6e 100644 --- a/src/libraries/icubmod/cfw2Can/Cfw2Can.cpp +++ b/src/libraries/icubmod/cfw2Can/Cfw2Can.cpp @@ -112,14 +112,14 @@ bool Cfw2Can::open(yarp::os::Searchable &par) int txTimeout=0; int rxTimeout=0; - netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); - if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); + netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); + if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); - txTimeout=par.check("CanTxTimeout", Value(0), "timeout on transmission [ms]").asInt(); - if (txTimeout == 0) txTimeout=par.check("canTxTimeout", Value(0), "timeout on transmission [ms]").asInt(); + txTimeout=par.check("CanTxTimeout", Value(0), "timeout on transmission [ms]").asInt32(); + if (txTimeout == 0) txTimeout=par.check("canTxTimeout", Value(0), "timeout on transmission [ms]").asInt32(); - rxTimeout=par.check("CanRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt() ; - if (rxTimeout == 0) rxTimeout=par.check("canRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt() ; + rxTimeout=par.check("CanRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt32() ; + if (rxTimeout == 0) rxTimeout=par.check("canRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt32() ; int res = cfwCanOpen (netId, txQueueSize, rxQueueSize, txTimeout, rxTimeout, handle); if (res != 0) diff --git a/src/libraries/icubmod/dragonfly2/common/DragonflyDeviceDriver2.cpp b/src/libraries/icubmod/dragonfly2/common/DragonflyDeviceDriver2.cpp index 03056cc225..d922d4cd79 100644 --- a/src/libraries/icubmod/dragonfly2/common/DragonflyDeviceDriver2.cpp +++ b/src/libraries/icubmod/dragonfly2/common/DragonflyDeviceDriver2.cpp @@ -79,13 +79,13 @@ bool DragonflyDeviceDriver2::open(yarp::os::Searchable& config) { if(config.check("pixelType")) { - if(config.find(("pixelType")).asVocab()==VOCAB_PIXEL_MONO) + if(config.find(("pixelType")).asVocab32()==VOCAB_PIXEL_MONO) raw=true; - else if((config.find(("pixelType")).asVocab()==VOCAB_PIXEL_RGB)) + else if((config.find(("pixelType")).asVocab32()==VOCAB_PIXEL_RGB)) raw=false; else { - yError()<<"DragonflyDeviceDriver2: invalid pixelType:"< parameter is deprecated, use --guid <64_bit_global_unique_identifier> instead\n"); - idCamera=config.find("d").asInt(); + idCamera=config.find("d").asInt32(); } if (idCamera<0 || idCamera>=m_nNumCameras) @@ -621,7 +621,7 @@ bool CFWCamera_DR2_2::Create(yarp::os::Searchable& config) yarp::os::Bottle& white_balance=config.findGroup("white_balance"); if (!white_balance.isNull()) { - setWhiteBalance(white_balance.get(2).asDouble(),white_balance.get(1).asDouble()); + setWhiteBalance(white_balance.get(2).asFloat64(),white_balance.get(1).asFloat64()); } setHue(checkDouble(config,"hue")); setSaturation(checkDouble(config,"saturation")); @@ -2283,7 +2283,7 @@ int CFWCamera_DR2_2::checkInt(yarp::os::Searchable& config,const char* key) { if (config.check(key)) { - return config.find(key).asInt(); + return config.find(key).asInt32(); } return 0; @@ -2293,7 +2293,7 @@ double CFWCamera_DR2_2::checkDouble(yarp::os::Searchable& config,const char* key { if (config.check(key)) { - return config.find(key).asDouble(); + return config.find(key).asFloat64(); } return -1.0; diff --git a/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.cpp b/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.cpp index c40a233c06..d1cb5b2577 100644 --- a/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.cpp +++ b/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.cpp @@ -232,7 +232,7 @@ bool CFWCamera_DR2_2::Create(yarp::os::Searchable& config) if (config.check("d")) { //yWarning("WARNING: --d parameter is deprecated, use --guid <64_bit_global_unique_identifier> instead\n"); - //idCamera=config.find("d").asInt(); + //idCamera=config.find("d").asInt32(); if (idCamera<0 || idCamera>=m_nNumCameras) { @@ -420,7 +420,7 @@ bool CFWCamera_DR2_2::Create(yarp::os::Searchable& config) yarp::os::Bottle& white_balance=config.findGroup("white_balance"); if (!white_balance.isNull()) { - setWhiteBalance(white_balance.get(2).asDouble(),white_balance.get(1).asDouble()); + setWhiteBalance(white_balance.get(2).asFloat64(),white_balance.get(1).asFloat64()); } setHue(checkDouble(config,"hue")); setSaturation(checkDouble(config,"saturation")); diff --git a/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.h b/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.h index bc448018f7..7b016a186c 100644 --- a/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.h +++ b/src/libraries/icubmod/dragonfly2/winnt/FirewireCameraDC1394-DR2_2.h @@ -143,7 +143,7 @@ class CFWCamera_DR2_2 : public yarp::dev::IFrameGrabberControlsDC1394 { if (config.check(key)) { - return config.find(key).asInt(); + return config.find(key).asInt32(); } return 0; @@ -153,7 +153,7 @@ class CFWCamera_DR2_2 : public yarp::dev::IFrameGrabberControlsDC1394 { if (config.check(key)) { - return config.find(key).asDouble(); + return config.find(key).asFloat64(); } return -1.0; diff --git a/src/libraries/icubmod/embObjAnalog/embObjAnalogSensor.cpp b/src/libraries/icubmod/embObjAnalog/embObjAnalogSensor.cpp index af8d6a5df4..9087d29e58 100755 --- a/src/libraries/icubmod/embObjAnalog/embObjAnalogSensor.cpp +++ b/src/libraries/icubmod/embObjAnalog/embObjAnalogSensor.cpp @@ -36,6 +36,7 @@ #include "EoProtocolAS.h" #include +#include #ifdef WIN32 #pragma warning(once:4355) @@ -93,7 +94,7 @@ bool embObjAnalogSensor::fromConfig(yarp::os::Searchable &_config) } else { - _period = xtmp.get(1).asInt(); + _period = xtmp.get(1).asInt32(); yDebug() << "embObjAnalogSensor::fromConfig() detects embObjAnalogSensor Using value of" << _period; } @@ -107,7 +108,7 @@ bool embObjAnalogSensor::fromConfig(yarp::os::Searchable &_config) } else { - _channels = xtmp.get(1).asInt(); + _channels = xtmp.get(1).asInt32(); } #if 0 @@ -118,7 +119,7 @@ bool embObjAnalogSensor::fromConfig(yarp::os::Searchable &_config) } else { - _numofsensors = xtmp.get(1).asInt(); + _numofsensors = xtmp.get(1).asInt32(); } #endif @@ -160,7 +161,7 @@ bool embObjAnalogSensor::fromConfig(yarp::os::Searchable &_config) } else { - format = xtmp.get(1).asInt(); + format = xtmp.get(1).asInt32(); } if((_channels==NUMCHANNEL_STRAIN) && (format==FORMATDATA_STRAIN)) @@ -219,7 +220,7 @@ bool embObjAnalogSensor::fromConfig(yarp::os::Searchable &_config) } else { - _useCalibration = xtmp.get(1).asInt(); + _useCalibration = xtmp.get(1).asInt32(); } } @@ -251,10 +252,10 @@ embObjAnalogSensor::embObjAnalogSensor(): analogdata(0) opened = false; - std::string tmp = NetworkBase::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - verbosewhenok = (bool)NetType::toInt(tmp); + verbosewhenok = (bool)yarp::conf::numeric::from_string(tmp, 0U); } else { diff --git a/src/libraries/icubmod/embObjInertials/embObjInertials.cpp b/src/libraries/icubmod/embObjInertials/embObjInertials.cpp index f6e979a903..ba43dc3bc2 100755 --- a/src/libraries/icubmod/embObjInertials/embObjInertials.cpp +++ b/src/libraries/icubmod/embObjInertials/embObjInertials.cpp @@ -36,6 +36,7 @@ #include "EoProtocolAS.h" #include +#include #ifdef WIN32 #pragma warning(once:4355) @@ -347,10 +348,10 @@ embObjInertials::embObjInertials() opened = false; - std::string tmp = NetworkBase::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - verbosewhenok = (bool)NetType::toInt(tmp); + verbosewhenok = (bool)(yarp::conf::numeric::from_string(tmp, 0U)); } else { diff --git a/src/libraries/icubmod/embObjLib/embObjGeneralDevPrivData.cpp b/src/libraries/icubmod/embObjLib/embObjGeneralDevPrivData.cpp index 796b6d2015..0e3cff073d 100644 --- a/src/libraries/icubmod/embObjLib/embObjGeneralDevPrivData.cpp +++ b/src/libraries/icubmod/embObjLib/embObjGeneralDevPrivData.cpp @@ -20,10 +20,10 @@ yarp::dev::embObjDevPrivData::embObjDevPrivData(std::string name):deviceNameType res = nullptr; behFlags.opened = false; - std::string tmp = yarp::conf::environment::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - behFlags.verbosewhenok = (bool)NetType::toInt(tmp); + behFlags.verbosewhenok = (bool)(yarp::conf::numeric::from_string(tmp, 0U)); } else { diff --git a/src/libraries/icubmod/embObjLib/ethParser.cpp b/src/libraries/icubmod/embObjLib/ethParser.cpp index effbf00d8c..4ee31c190f 100755 --- a/src/libraries/icubmod/embObjLib/ethParser.cpp +++ b/src/libraries/icubmod/embObjLib/ethParser.cpp @@ -127,7 +127,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, pc104Data &pc104data) } Bottle paramIPaddress(groupPC104.find("PC104IpAddress").asString()); - uint16_t port = groupPC104.find("PC104IpPort").asInt(); // .get(1).asInt(); + uint16_t port = groupPC104.find("PC104IpPort").asInt32(); // .get(1).asInt32(); char strIP[64] = {0}; @@ -148,7 +148,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, pc104Data &pc104data) // txrate if(cfgtotal.findGroup("PC104").check("PC104TXrate")) { - int value = cfgtotal.findGroup("PC104").find("PC104TXrate").asInt(); + int value = cfgtotal.findGroup("PC104").find("PC104TXrate").asInt32(); if(value > 0) { pc104data.txrate = value; @@ -162,7 +162,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, pc104Data &pc104data) // rxrate if(cfgtotal.findGroup("PC104").check("PC104RXrate")) { - int value = cfgtotal.findGroup("PC104").find("PC104RXrate").asInt(); + int value = cfgtotal.findGroup("PC104").find("PC104RXrate").asInt32(); if(value > 0) { pc104data.rxrate = value; @@ -230,7 +230,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) // IpPort: if(true == groupEthBoardProps.check("IpPort")) { - boarddata.properties.ipv4addressing.port = groupEthBoardProps.find("IpPort").asInt();; + boarddata.properties.ipv4addressing.port = groupEthBoardProps.find("IpPort").asInt32();; } else { @@ -279,7 +279,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) // maxSizeRXpacket: if(true == groupEthBoardProps.check("maxSizeRXpacket")) { - boarddata.properties.maxSizeRXpacket = groupEthBoardProps.find("maxSizeRXpacket").asInt(); + boarddata.properties.maxSizeRXpacket = groupEthBoardProps.find("maxSizeRXpacket").asInt32(); //yDebug() << "eth::parser::read() has detected capacityofTXpacket =" << boarddata.properties.maxSizeRXpacket << "for BOARD w/ IP" << boarddata.properties.ipv4string; } else @@ -291,7 +291,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) // maxSizeROP: if(true == groupEthBoardProps.check("maxSizeROP")) { - boarddata.properties.maxSizeROP = groupEthBoardProps.find("maxSizeROP").asInt(); + boarddata.properties.maxSizeROP = groupEthBoardProps.find("maxSizeROP").asInt32(); //yDebug() << "eth::parser::read() has detected maxSizeOfROP =" << boarddata.properties.maxSizeROP << "for BOARD w/ IP" << boarddata.properties.ipv4string; } else @@ -336,7 +336,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardSettings_RunningMode.check("period")) { - int tmp = groupEthBoardSettings_RunningMode.find("period").asInt(); + int tmp = groupEthBoardSettings_RunningMode.find("period").asInt32(); if(1000 != tmp) { @@ -348,7 +348,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardSettings_RunningMode.check("maxTimeOfRXactivity")) { - int tmp = groupEthBoardSettings_RunningMode.find("maxTimeOfRXactivity").asInt(); + int tmp = groupEthBoardSettings_RunningMode.find("maxTimeOfRXactivity").asInt32(); if((tmp < 5) || (tmp > 990)) { @@ -361,7 +361,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardSettings_RunningMode.check("maxTimeOfDOactivity")) { - int tmp = groupEthBoardSettings_RunningMode.find("maxTimeOfDOactivity").asInt(); + int tmp = groupEthBoardSettings_RunningMode.find("maxTimeOfDOactivity").asInt32(); if((tmp < 5) || (tmp > 990)) { @@ -374,7 +374,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardSettings_RunningMode.check("maxTimeOfTXactivity")) { - int tmp = groupEthBoardSettings_RunningMode.find("maxTimeOfTXactivity").asInt(); + int tmp = groupEthBoardSettings_RunningMode.find("maxTimeOfTXactivity").asInt32(); if((tmp < 5) || (tmp > 990)) { @@ -388,7 +388,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardSettings_RunningMode.check("TXrateOfRegularROPs")) { - int tmp = groupEthBoardSettings_RunningMode.find("TXrateOfRegularROPs").asInt(); + int tmp = groupEthBoardSettings_RunningMode.find("TXrateOfRegularROPs").asInt32(); if(tmp <=0) { @@ -452,7 +452,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardActions_Monitor.check("timeout")) { - double presenceTimeout = groupEthBoardActions_Monitor.find("timeout").asDouble(); + double presenceTimeout = groupEthBoardActions_Monitor.find("timeout").asFloat64(); if(presenceTimeout <= 0) { @@ -472,7 +472,7 @@ bool eth::parser::read(yarp::os::Searchable &cfgtotal, boardData &boarddata) if(true == groupEthBoardActions_Monitor.check("periodOfMissingReport")) { - double reportMissingPeriod = groupEthBoardActions_Monitor.find("periodOfMissingReport").asDouble(); + double reportMissingPeriod = groupEthBoardActions_Monitor.find("periodOfMissingReport").asFloat64(); if(reportMissingPeriod <= 0) { diff --git a/src/libraries/icubmod/embObjLib/ethReceiver.cpp b/src/libraries/icubmod/embObjLib/ethReceiver.cpp index f95896d1ad..936145fbe6 100644 --- a/src/libraries/icubmod/embObjLib/ethReceiver.cpp +++ b/src/libraries/icubmod/embObjLib/ethReceiver.cpp @@ -68,10 +68,10 @@ EthReceiver::EthReceiver(int raterx): PeriodicThread((double)raterx/1000.0) yDebug() << "EthReceiver is a PeriodicThread with rxrate =" << rateofthread << "ms"; // ok, and now i get it from xml file ... if i find it. -// std::string tmp = NetworkBase::getEnvironment("ETHSTAT_PRINT_INTERVAL"); +// std::string tmp = yarp::conf::environment::get_string("ETHSTAT_PRINT_INTERVAL"); // if (tmp != "") // { -// statPrintInterval = (double)NetType::toInt(tmp); +// statPrintInterval = (double)yarp::conf::numeric::from_string(tmp, 0.); // } // else // { @@ -111,9 +111,9 @@ bool EthReceiver::config(ACE_SOCK_Dgram *pSocket, TheEthManager* _ethManager) int len = sizeof(mysize); // the user can change buffer size by environment variable ETHRECEIVER_BUFFER_SIZE - std::string _dgram_buffer_size = yarp::conf::environment::getEnvironment("ETHRECEIVER_BUFFER_SIZE"); + std::string _dgram_buffer_size = yarp::conf::environment::get_string("ETHRECEIVER_BUFFER_SIZE"); if (_dgram_buffer_size!="") - mysize = NetType::toInt(_dgram_buffer_size); + mysize = yarp::conf::numeric::from_string(_dgram_buffer_size, 0); retval = ACE_OS::setsockopt (sockfd, SOL_SOCKET, SO_RCVBUF, (char *)&mysize, sizeof(mysize)); if (retval != 0) diff --git a/src/libraries/icubmod/embObjLib/ethResource.cpp b/src/libraries/icubmod/embObjLib/ethResource.cpp index 7747bd5e91..1843aeef0a 100755 --- a/src/libraries/icubmod/embObjLib/ethResource.cpp +++ b/src/libraries/icubmod/embObjLib/ethResource.cpp @@ -65,10 +65,10 @@ EthResource::EthResource() c_string_handler[i] = NULL; } - std::string tmp = yarp::conf::environment::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - verbosewhenok = (bool)NetType::toInt(tmp); + verbosewhenok = (bool)(yarp::conf::numeric::from_string(tmp, 0U)); } else { diff --git a/src/libraries/icubmod/embObjLib/serviceParser.cpp b/src/libraries/icubmod/embObjLib/serviceParser.cpp index 95e1d9981e..a6e38dbd87 100755 --- a/src/libraries/icubmod/embObjLib/serviceParser.cpp +++ b/src/libraries/icubmod/embObjLib/serviceParser.cpp @@ -690,12 +690,12 @@ bool ServiceParser::check_analog(Searchable &config, eOmn_serv_type_t type) servCanBoard_t item; convert(b_PROPERTIES_CANBOARDS_type.get(i+1).asString(), item.type, formaterror); - convert(b_PROPERTIES_CANBOARDS_PROTOCOL_major.get(i+1).asInt(), item.protocol.major, formaterror); - convert(b_PROPERTIES_CANBOARDS_PROTOCOL_minor.get(i+1).asInt(), item.protocol.minor, formaterror); + convert(b_PROPERTIES_CANBOARDS_PROTOCOL_major.get(i+1).asInt32(), item.protocol.major, formaterror); + convert(b_PROPERTIES_CANBOARDS_PROTOCOL_minor.get(i+1).asInt32(), item.protocol.minor, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_major.get(i+1).asInt(), item.firmware.major, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_minor.get(i+1).asInt(), item.firmware.minor, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_build.get(i+1).asInt(), item.firmware.build, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_major.get(i+1).asInt32(), item.firmware.major, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_minor.get(i+1).asInt32(), item.firmware.minor, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_build.get(i+1).asInt32(), item.firmware.build, formaterror); as_service.properties.canboards.push_back(item); } @@ -836,7 +836,7 @@ bool ServiceParser::check_analog(Searchable &config, eOmn_serv_type_t type) return false; } - convert(b_SETTINGS_acquisitionRate.get(1).asInt(), as_service.settings.acquisitionrate, formaterror); + convert(b_SETTINGS_acquisitionRate.get(1).asInt32(), as_service.settings.acquisitionrate, formaterror); as_service.settings.enabledsensors.resize(0); @@ -1062,12 +1062,12 @@ bool ServiceParser::check_skin(Searchable &config) sk_service.properties.canboard.clear(); convert(b_PROPERTIES_CANBOARDS_type.get(1).asString(), sk_service.properties.canboard.type, formaterror); - convert(b_PROPERTIES_CANBOARDS_PROTOCOL_major.get(1).asInt(), sk_service.properties.canboard.protocol.major, formaterror); - convert(b_PROPERTIES_CANBOARDS_PROTOCOL_minor.get(1).asInt(), sk_service.properties.canboard.protocol.minor, formaterror); + convert(b_PROPERTIES_CANBOARDS_PROTOCOL_major.get(1).asInt32(), sk_service.properties.canboard.protocol.major, formaterror); + convert(b_PROPERTIES_CANBOARDS_PROTOCOL_minor.get(1).asInt32(), sk_service.properties.canboard.protocol.minor, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_major.get(1).asInt(), sk_service.properties.canboard.firmware.major, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_minor.get(1).asInt(), sk_service.properties.canboard.firmware.minor, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_build.get(1).asInt(), sk_service.properties.canboard.firmware.build, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_major.get(1).asInt32(), sk_service.properties.canboard.firmware.major, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_minor.get(1).asInt32(), sk_service.properties.canboard.firmware.minor, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_build.get(1).asInt32(), sk_service.properties.canboard.firmware.build, formaterror); @@ -1215,7 +1215,7 @@ bool ServiceParser::check_skin(Searchable &config) return false; } - convert(b_SETTINGS_acquisitionRate.get(1).asInt(), sk_service.settings.acquisitionrate, formaterror); + convert(b_SETTINGS_acquisitionRate.get(1).asInt32(), sk_service.settings.acquisitionrate, formaterror); sk_service.settings.enabledsensors.resize(0); @@ -1453,7 +1453,7 @@ bool ServiceParser::parseService(Searchable &config, servConfigFTsensor_t &ftcon } else { - ftconfig.temperatureAcquisitionrate = b_SETTINGS_temp.get(1).asInt(); + ftconfig.temperatureAcquisitionrate = b_SETTINGS_temp.get(1).asInt32(); //TODO: chek that the acquisition rate is inside a reasonable range } @@ -2870,12 +2870,12 @@ bool ServiceParser::check_motion(Searchable &config) servCanBoard_t item; convert(b_PROPERTIES_CANBOARDS_type.get(i+1).asString(), item.type, formaterror); - convert(b_PROPERTIES_CANBOARDS_PROTOCOL_major.get(i+1).asInt(), item.protocol.major, formaterror); - convert(b_PROPERTIES_CANBOARDS_PROTOCOL_minor.get(i+1).asInt(), item.protocol.minor, formaterror); + convert(b_PROPERTIES_CANBOARDS_PROTOCOL_major.get(i+1).asInt32(), item.protocol.major, formaterror); + convert(b_PROPERTIES_CANBOARDS_PROTOCOL_minor.get(i+1).asInt32(), item.protocol.minor, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_major.get(i+1).asInt(), item.firmware.major, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_minor.get(i+1).asInt(), item.firmware.minor, formaterror); - convert(b_PROPERTIES_CANBOARDS_FIRMWARE_build.get(i+1).asInt(), item.firmware.build, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_major.get(i+1).asInt32(), item.firmware.major, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_minor.get(i+1).asInt32(), item.firmware.minor, formaterror); + convert(b_PROPERTIES_CANBOARDS_FIRMWARE_build.get(i+1).asInt32(), item.firmware.build, formaterror); mc_service.properties.canboards.push_back(item); } @@ -3017,11 +3017,11 @@ bool ServiceParser::check_motion(Searchable &config) // 1. get values for SHIFTS uint8_t value = 0; - if(true == convert(b_PROPERTIES_MC4_SHIFTS_velocity.get(1).asInt(), value, formaterror)) + if(true == convert(b_PROPERTIES_MC4_SHIFTS_velocity.get(1).asInt32(), value, formaterror)) { mc_service.properties.mc4shifts.velocity = value; } - if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimJointVelocity.get(1).asInt(), value, formaterror)) + if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimJointVelocity.get(1).asInt32(), value, formaterror)) { if(value > 15) { @@ -3030,7 +3030,7 @@ bool ServiceParser::check_motion(Searchable &config) } mc_service.properties.mc4shifts.estimJointVelocity = value; } - if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimJointAcceleration.get(1).asInt(), value, formaterror)) + if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimJointAcceleration.get(1).asInt32(), value, formaterror)) { if(value > 15) { @@ -3039,7 +3039,7 @@ bool ServiceParser::check_motion(Searchable &config) } mc_service.properties.mc4shifts.estimJointAcceleration = value; } - if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimMotorVelocity.get(1).asInt(), value, formaterror)) + if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimMotorVelocity.get(1).asInt32(), value, formaterror)) { if(value > 15) { @@ -3048,7 +3048,7 @@ bool ServiceParser::check_motion(Searchable &config) } mc_service.properties.mc4shifts.estimMotorVelocity = value; } - if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimMotorAcceleration.get(1).asInt(), value, formaterror)) + if(true == convert(b_PROPERTIES_MC4_SHIFTS_estimMotorAcceleration.get(1).asInt32(), value, formaterror)) { if(value > 15) { @@ -3457,9 +3457,9 @@ bool ServiceParser::check_motion(Searchable &config) } enc1.desc.pos = encposition; - enc1.resolution = b_PROPERTIES_JOINTMAPPING_ENCODER1_resolution.get(i+1).asInt(); + enc1.resolution = b_PROPERTIES_JOINTMAPPING_ENCODER1_resolution.get(i+1).asInt32(); - enc1.tolerance = b_PROPERTIES_JOINTMAPPING_ENCODER1_tolerance.get(i+1).asDouble(); + enc1.tolerance = b_PROPERTIES_JOINTMAPPING_ENCODER1_tolerance.get(i+1).asFloat64(); @@ -3511,8 +3511,8 @@ bool ServiceParser::check_motion(Searchable &config) enc2.desc.pos = encposition; - enc2.resolution = b_PROPERTIES_JOINTMAPPING_ENCODER2_resolution.get(i+1).asInt(); - enc2.tolerance = b_PROPERTIES_JOINTMAPPING_ENCODER2_tolerance.get(i+1).asDouble(); + enc2.resolution = b_PROPERTIES_JOINTMAPPING_ENCODER2_resolution.get(i+1).asInt32(); + enc2.tolerance = b_PROPERTIES_JOINTMAPPING_ENCODER2_tolerance.get(i+1).asFloat64(); // ok, we push act, enc1, enc2 @@ -3547,13 +3547,13 @@ bool ServiceParser::check_motion(Searchable &config) { yWarning() << "ServiceParser::check_motion() has detected an illegal format for SERVICE.PROPERTIES.DIAGNOSTICS.mode. Using {eOmn_serv_diagn_mode_NONE, 0}"; } - else if(!b_PROPERTIES_DIAGNOSTICS_par16.get(1).isInt()) + else if(!b_PROPERTIES_DIAGNOSTICS_par16.get(1).isInt32()) { yWarning() << "ServiceParser::check_motion() has detected an illegal format for SERVICE.PROPERTIES.DIAGNOSTICS.par16. Using {eOmn_serv_diagn_mode_NONE, 0}"; } else { - par16 = b_PROPERTIES_DIAGNOSTICS_par16.get(1).asInt(); + par16 = b_PROPERTIES_DIAGNOSTICS_par16.get(1).asInt32(); } mc_service.diagconfig.mode = dm; diff --git a/src/libraries/icubmod/embObjMais/embObjMais.cpp b/src/libraries/icubmod/embObjMais/embObjMais.cpp index e6ac78fc0c..67ceb08221 100755 --- a/src/libraries/icubmod/embObjMais/embObjMais.cpp +++ b/src/libraries/icubmod/embObjMais/embObjMais.cpp @@ -107,7 +107,7 @@ bool embObjMais::fromConfig(yarp::os::Searchable &_config) } else { - _period = xtmp.get(1).asInt(); + _period = xtmp.get(1).asInt32(); yDebug() << "embObjMais::fromConfig() detects embObjMais Using value of" << _period; } @@ -137,10 +137,10 @@ embObjMais::embObjMais() analogdata.resize(0); - std::string tmp = yarp::conf::environment::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - verbosewhenok = (bool)NetType::toInt(tmp); + verbosewhenok = (bool)(yarp::conf::numeric::from_string(tmp, 0U)); } else { diff --git a/src/libraries/icubmod/embObjMotionControl/embObjMotionControl.cpp b/src/libraries/icubmod/embObjMotionControl/embObjMotionControl.cpp index 599243c265..15e2d93ece 100644 --- a/src/libraries/icubmod/embObjMotionControl/embObjMotionControl.cpp +++ b/src/libraries/icubmod/embObjMotionControl/embObjMotionControl.cpp @@ -253,10 +253,10 @@ embObjMotionControl::embObjMotionControl() : behFlags.useRawEncoderData = false; behFlags.pwmIsLimited = false; - std::string tmp = yarp::conf::environment::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - behFlags.verbosewhenok = (bool)NetType::toInt(tmp); + behFlags.verbosewhenok = (bool)yarp::conf::numeric::from_string(tmp, 0U); } else { @@ -493,7 +493,7 @@ int embObjMotionControl::fromConfig_NumOfJoints(yarp::os::Searchable &config) // // Read Configuration params from file // - int jn = config.findGroup("GENERAL").check("Joints", Value(1), "Number of degrees of freedom").asInt(); + int jn = config.findGroup("GENERAL").check("Joints", Value(1), "Number of degrees of freedom").asInt32(); return(jn); } @@ -1531,7 +1531,7 @@ bool embObjMotionControl::update(eOprotID32_t id32, double timestamp, void *rxda output.clear(); //output.addString("[yt, amo, reg, pos]"); // but we must get the joint and the motor as well output.addString("[yt, amo, reg, pos]"); - output.addDouble(timestamp); + output.addFloat64(timestamp); output.addInt32(debug32[0]); output.addInt32(debug32[1]); output.addInt32(jcore.measures.meas_position); @@ -2588,14 +2588,14 @@ bool embObjMotionControl::setControlModeRaw(const int j, const int _mode) if(!controlModeCommandConvert_yarp2embObj(_mode, controlmodecommand) ) { - yError() << "SetControlMode: received unknown control mode for " << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(_mode); + yError() << "SetControlMode: received unknown control mode for " << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(_mode); return false; } eOprotID32_t protid = eoprot_ID_get(eoprot_endpoint_motioncontrol, eoprot_entity_mc_joint, j, eoprot_tag_mc_joint_cmmnds_controlmode); if(false == res->setRemoteValue(protid, &controlmodecommand) ) { - yError() << "setControlModeRaw failed for " << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(_mode); + yError() << "setControlModeRaw failed for " << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(_mode); return false; } @@ -2604,7 +2604,7 @@ bool embObjMotionControl::setControlModeRaw(const int j, const int _mode) if(false == ret) { - yError() << "In embObjMotionControl::setControlModeRaw(j=" << j << ", mode=" << yarp::os::Vocab::decode(_mode).c_str() << ") for " << getBoardInfo() << " has failed checkRemoteControlModeStatus()"; + yError() << "In embObjMotionControl::setControlModeRaw(j=" << j << ", mode=" << yarp::os::Vocab32::decode(_mode).c_str() << ") for " << getBoardInfo() << " has failed checkRemoteControlModeStatus()"; } return ret; @@ -2623,7 +2623,7 @@ bool embObjMotionControl::setControlModesRaw(const int n_joint, const int *joint if(!controlModeCommandConvert_yarp2embObj(modes[i], controlmodecommand) ) { - yError() << "SetControlModesRaw(): received unknown control mode for " << getBoardInfo() << " joint " << joints[i] << " mode " << Vocab::decode(modes[i]); + yError() << "SetControlModesRaw(): received unknown control mode for " << getBoardInfo() << " joint " << joints[i] << " mode " << Vocab32::decode(modes[i]); return false; } @@ -2631,7 +2631,7 @@ bool embObjMotionControl::setControlModesRaw(const int n_joint, const int *joint eOprotID32_t protid = eoprot_ID_get(eoprot_endpoint_motioncontrol, eoprot_entity_mc_joint, joints[i], eoprot_tag_mc_joint_cmmnds_controlmode); if(false == res->setRemoteValue(protid, &controlmodecommand) ) { - yError() << "setControlModesRaw() could not send set for " << getBoardInfo() << " joint " << joints[i] << " mode " << Vocab::decode(modes[i]); + yError() << "setControlModesRaw() could not send set for " << getBoardInfo() << " joint " << joints[i] << " mode " << Vocab32::decode(modes[i]); return false; } @@ -2639,7 +2639,7 @@ bool embObjMotionControl::setControlModesRaw(const int n_joint, const int *joint bool tmpresult = checkRemoteControlModeStatus(joints[i], modes[i]); if(false == tmpresult) { - yError() << "setControlModesRaw(const int n_joint, const int *joints, int *modes) could not check with checkRemoteControlModeStatus() for " << getBoardInfo() << " joint " << joints[i] << " mode " << Vocab::decode(modes[i]); + yError() << "setControlModesRaw(const int n_joint, const int *joints, int *modes) could not check with checkRemoteControlModeStatus() for " << getBoardInfo() << " joint " << joints[i] << " mode " << Vocab32::decode(modes[i]); } ret = ret && tmpresult; @@ -2665,21 +2665,21 @@ bool embObjMotionControl::setControlModesRaw(int *modes) if(!controlModeCommandConvert_yarp2embObj(modes[i], controlmodecommand) ) { - yError() << "SetControlMode: received unknown control mode for" << getBoardInfo() << " joint " << i << " mode " << Vocab::decode(modes[i]); + yError() << "SetControlMode: received unknown control mode for" << getBoardInfo() << " joint " << i << " mode " << Vocab32::decode(modes[i]); return false; } eOprotID32_t protid = eoprot_ID_get(eoprot_endpoint_motioncontrol, eoprot_entity_mc_joint, i, eoprot_tag_mc_joint_cmmnds_controlmode); if(false == res->setRemoteValue(protid, &controlmodecommand) ) { - yError() << "setControlModesRaw failed for " << getBoardInfo() << " joint " << i << " mode " << Vocab::decode(modes[i]); + yError() << "setControlModesRaw failed for " << getBoardInfo() << " joint " << i << " mode " << Vocab32::decode(modes[i]); return false; } bool tmpresult = checkRemoteControlModeStatus(i, modes[i]); if(false == tmpresult) { - yError() << "setControlModesRaw(int *modes) could not check with checkRemoteControlModeStatus() for" << getBoardInfo() << " joint " << i << " mode " << Vocab::decode(modes[i]); + yError() << "setControlModesRaw(int *modes) could not check with checkRemoteControlModeStatus() for" << getBoardInfo() << " joint " << i << " mode " << Vocab32::decode(modes[i]); } ret = ret && tmpresult; @@ -3330,89 +3330,89 @@ bool embObjMotionControl::getRemoteVariableRaw(std::string key, yarp::os::Bottle { // matrixJ2M is stored as row major in the eomc_couplingInfo_t, // and kinematic_mj is returned as a row major serialization as well - ret.addDouble(_couplingInfo.matrixJ2M[4 * r + c]); + ret.addFloat64(_couplingInfo.matrixJ2M[4 * r + c]); } } } else { - ret.addDouble(0.0); + ret.addFloat64(0.0); } return true; } else if (key == "encoders") { - Bottle& r = val.addList(); for (int i = 0; i < _njoints; i++) { r.addDouble(_measureConverter->posA2E(1.0, i)); } + Bottle& r = val.addList(); for (int i = 0; i < _njoints; i++) { r.addFloat64(_measureConverter->posA2E(1.0, i)); } return true; } else if (key == "rotorEncoderResolution") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorEncoderResolutionRaw(i, tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorEncoderResolutionRaw(i, tmp); r.addFloat64(tmp); } return true; } else if (key == "jointEncoderResolution") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getJointEncoderResolutionRaw(i, tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getJointEncoderResolutionRaw(i, tmp); r.addFloat64(tmp); } return true; } else if (key == "gearbox_M2J") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp=0; getGearboxRatioRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp=0; getGearboxRatioRaw(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "gearbox_E2J") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp=0; getGerabox_E2J(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp=0; getGerabox_E2J(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "hasHallSensor") { - Bottle& r = val.addList(); for (int i = 0; i < _njoints; i++) { int tmp = 0; getHasHallSensorRaw(i, tmp); r.addInt(tmp); } + Bottle& r = val.addList(); for (int i = 0; i < _njoints; i++) { int tmp = 0; getHasHallSensorRaw(i, tmp); r.addInt32(tmp); } return true; } else if (key == "hasTempSensor") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getHasTempSensorsRaw(i, tmp); r.addInt(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getHasTempSensorsRaw(i, tmp); r.addInt32(tmp); } return true; } else if (key == "hasRotorEncoder") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getHasRotorEncoderRaw(i, tmp); r.addInt(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getHasRotorEncoderRaw(i, tmp); r.addInt32(tmp); } return true; } else if (key == "hasRotorEncoderIndex") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getHasRotorEncoderIndexRaw(i, tmp); r.addInt(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getHasRotorEncoderIndexRaw(i, tmp); r.addInt32(tmp); } return true; } else if (key == "rotorIndexOffset") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorIndexOffsetRaw(i, tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorIndexOffsetRaw(i, tmp); r.addFloat64(tmp); } return true; } else if (key == "motorPoles") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getMotorPolesRaw(i, tmp); r.addInt(tmp); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int tmp = 0; getMotorPolesRaw(i, tmp); r.addInt32(tmp); } return true; } else if (key == "pidCurrentKp") { - Bottle& r = val.addList(); for (int i = 0; i < _njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addDouble(p.kp); } + Bottle& r = val.addList(); for (int i = 0; i < _njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addFloat64(p.kp); } return true; } else if (key == "pidCurrentKi") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addDouble(p.ki); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addFloat64(p.ki); } return true; } else if (key == "pidCurrentShift") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addDouble(p.scale); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addFloat64(p.scale); } return true; } else if (key == "pidCurrentOutput") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addDouble(p.max_output); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { Pid p; getPidRaw(PidControlTypeEnum::VOCAB_PIDTYPE_CURRENT, i, &p); r.addFloat64(p.max_output); } return true; } else if (key == "jointEncoderType") @@ -3450,7 +3450,7 @@ bool embObjMotionControl::getRemoteVariableRaw(std::string key, yarp::os::Bottle } else if (key == "torqueControlFilterType") { - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int t; getTorqueControlFilterType(i, t); r.addDouble(t); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { int t; getTorqueControlFilterType(i, t); r.addFloat64(t); } return true; } else if (key == "torqueControlEnabled") @@ -3459,75 +3459,75 @@ bool embObjMotionControl::getRemoteVariableRaw(std::string key, yarp::os::Bottle Bottle& r = val.addList(); for(int i = 0; i<_njoints; i++) { - r.addInt((int)_trq_pids[i].enabled ); + r.addInt32((int)_trq_pids[i].enabled ); } return true; } else if (key == "PWMLimit") { - Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getPWMLimitRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getPWMLimitRaw(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "motOverloadCurr") { - Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getMaxCurrentRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getMaxCurrentRaw(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "motNominalCurr") { - Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getNominalCurrentRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getNominalCurrentRaw(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "motPeakCurr") { - Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getPeakCurrentRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getPeakCurrentRaw(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "PowerSuppVoltage") { - Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getPowerSupplyVoltageRaw(i, &tmp); r.addDouble(tmp); } + Bottle& r = val.addList(); for (int i = 0; i< _njoints; i++) { double tmp = 0; getPowerSupplyVoltageRaw(i, &tmp); r.addFloat64(tmp); } return true; } else if (key == "rotorMax") { double tmp1, tmp2; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorLimitsRaw(i, &tmp1, &tmp2); r.addDouble(tmp2); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorLimitsRaw(i, &tmp1, &tmp2); r.addFloat64(tmp2); } return true; } else if (key == "rotorMin") { double tmp1, tmp2; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorLimitsRaw(i, &tmp1, &tmp2); r.addDouble(tmp1); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getRotorLimitsRaw(i, &tmp1, &tmp2); r.addFloat64(tmp1); } return true; } else if (key == "jointMax") { double tmp1, tmp2; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getLimitsRaw(i, &tmp1, &tmp2); r.addDouble(tmp2); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getLimitsRaw(i, &tmp1, &tmp2); r.addFloat64(tmp2); } return true; } else if (key == "jointMin") { double tmp1, tmp2; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getLimitsRaw(i, &tmp1, &tmp2); r.addDouble(tmp1); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getLimitsRaw(i, &tmp1, &tmp2); r.addFloat64(tmp1); } return true; } else if (key == "jointEncTolerance") { double tmp1; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getJointEncTolerance(i, &tmp1); r.addDouble(tmp1); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getJointEncTolerance(i, &tmp1); r.addFloat64(tmp1); } return true; } else if (key == "motorEncTolerance") { double tmp1; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getMotorEncTolerance(i, &tmp1); r.addDouble(tmp1); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getMotorEncTolerance(i, &tmp1); r.addFloat64(tmp1); } return true; } else if (key == "jointDeadZone") { double tmp1; - Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getJointDeadZoneRaw(i, tmp1); r.addDouble(tmp1); } + Bottle& r = val.addList(); for (int i = 0; i<_njoints; i++) { double tmp = 0; getJointDeadZoneRaw(i, tmp1); r.addFloat64(tmp1); } return true; } else if (key == "readonly_position_PIDraw") @@ -3620,17 +3620,17 @@ bool embObjMotionControl::setRemoteVariableRaw(std::string key, const yarp::os:: } // else if (key == "rotor") // { -// for (int i = 0; i < _njoints; i++) _rotorEncoderRes[i] = val.get(i).asInt();//this operation has none effect on motor controlelr, so i remove it +// for (int i = 0; i < _njoints; i++) _rotorEncoderRes[i] = val.get(i).asInt32();//this operation has none effect on motor controlelr, so i remove it // return true; // } // else if (key == "gearbox_M2J") // { -// for (int i = 0; i < _njoints; i++) _gearbox_M2J[i] = val.get(i).asDouble();//this operation has none effect on motor controlelr, so i remove it +// for (int i = 0; i < _njoints; i++) _gearbox_M2J[i] = val.get(i).asFloat64();//this operation has none effect on motor controlelr, so i remove it // return true; // } else if (key == "PWMLimit") { - for (int i = 0; i < _njoints; i++) setPWMLimitRaw(i, val.get(i).asDouble()); + for (int i = 0; i < _njoints; i++) setPWMLimitRaw(i, val.get(i).asFloat64()); return true; } //disabled for used safety @@ -3641,7 +3641,7 @@ bool embObjMotionControl::setRemoteVariableRaw(std::string key, const yarp::os:: for (int i = 0; i < _njoints; i++) { getLimitsRaw(i, &min, &max); - setLimitsRaw(i, min, val.get(i).asDouble()); + setLimitsRaw(i, min, val.get(i).asFloat64()); } return true; } @@ -3651,7 +3651,7 @@ bool embObjMotionControl::setRemoteVariableRaw(std::string key, const yarp::os:: for (int i = 0; i < _njoints; i++) { getLimitsRaw(i, &min, &max); - setLimitsRaw(i, val.get(i).asDouble(), max); + setLimitsRaw(i, val.get(i).asFloat64(), max); } } #endif @@ -4373,20 +4373,20 @@ bool embObjMotionControl::setInteractionModeRaw(int j, yarp::dev::InteractionMod eOenum08_t interactionmodecommand = 0; - // yDebug() << "received setInteractionModeRaw command (SINGLE) for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(_mode); + // yDebug() << "received setInteractionModeRaw command (SINGLE) for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(_mode); if (_mode == VOCAB_IM_COMPLIANT && _trq_pids[j].enabled == false) {yError()<<"Torque control is disabled. Check your configuration parameters"; return false;} if(!interactionModeCommandConvert_yarp2embObj(_mode, interactionmodecommand) ) { - yError() << "setInteractionModeRaw: received unknown mode for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(_mode); + yError() << "setInteractionModeRaw: received unknown mode for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(_mode); } eOprotID32_t protid = eoprot_ID_get(eoprot_endpoint_motioncontrol, eoprot_entity_mc_joint, j, eoprot_tag_mc_joint_cmmnds_interactionmode); if(false == res->setRemoteValue(protid, &interactionmodecommand) ) { - yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(_mode); + yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(_mode); return false; } @@ -4399,7 +4399,7 @@ bool embObjMotionControl::setInteractionModeRaw(int j, yarp::dev::InteractionMod if((false == ret) || (interactionmodecommand != interactionmodestatus)) { - yError() << "check of embObjMotionControl::setInteractionModeRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(_mode); + yError() << "check of embObjMotionControl::setInteractionModeRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(_mode); return false; } #endif @@ -4420,14 +4420,14 @@ bool embObjMotionControl::setInteractionModesRaw(int n_joints, int *joints, yarp if(!interactionModeCommandConvert_yarp2embObj(modes[j], interactionmodecommand) ) { - yError() << "embObjMotionControl::setInteractionModesRaw(): received unknown interactionMode for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(modes[j]) << " " << modes[j]; + yError() << "embObjMotionControl::setInteractionModesRaw(): received unknown interactionMode for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(modes[j]) << " " << modes[j]; return false; } eOprotID32_t protid = eoprot_ID_get(eoprot_endpoint_motioncontrol, eoprot_entity_mc_joint, j, eoprot_tag_mc_joint_cmmnds_interactionmode); if(false == res->setRemoteValue(protid, &interactionmodecommand) ) { - yError() << "embObjMotionControl::setInteractionModesRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(modes[j]); + yError() << "embObjMotionControl::setInteractionModesRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(modes[j]); return false; } @@ -4442,17 +4442,17 @@ bool embObjMotionControl::setInteractionModesRaw(int n_joints, int *joints, yarp { if(false == ret) { - yError() << "check of embObjMotionControl::setInteractionModesRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(modes[j]); + yError() << "check of embObjMotionControl::setInteractionModesRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(modes[j]); return false; } int tmp; if(interactionModeStatusConvert_embObj2yarp(interactionmodestatus, tmp) ) yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " because of interactionMode mismatching \n\tSet " \ - << Vocab::decode(modes[j]) << " Got " << Vocab::decode(tmp); + << Vocab32::decode(modes[j]) << " Got " << Vocab32::decode(tmp); else yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " because of interactionMode mismatching \n\tSet " \ - << Vocab::decode(modes[j]) << " Got an unknown value!"; + << Vocab32::decode(modes[j]) << " Got an unknown value!"; return false; } #endif @@ -4477,14 +4477,14 @@ bool embObjMotionControl::setInteractionModesRaw(yarp::dev::InteractionModeEnum* if(!interactionModeCommandConvert_yarp2embObj(modes[j], interactionmodecommand) ) { - yError() << "setInteractionModeRaw: received unknown interactionMode for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(modes[j]); + yError() << "setInteractionModeRaw: received unknown interactionMode for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(modes[j]); return false; } eOprotID32_t protid = eoprot_ID_get(eoprot_endpoint_motioncontrol, eoprot_entity_mc_joint, j, eoprot_tag_mc_joint_cmmnds_interactionmode); if(false == res->setRemoteValue(protid, &interactionmodecommand) ) { - yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(modes[j]); + yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(modes[j]); return false; } @@ -4499,17 +4499,17 @@ bool embObjMotionControl::setInteractionModesRaw(yarp::dev::InteractionModeEnum* { if(false == ret) { - yError() << "check of embObjMotionControl::setInteractionModesRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab::decode(modes[j]); + yError() << "check of embObjMotionControl::setInteractionModesRaw() failed for" << getBoardInfo() << " joint " << j << " mode " << Vocab32::decode(modes[j]); return false; } int tmp; if(interactionModeStatusConvert_embObj2yarp(interactionmodestatus, tmp) ) yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " because of interactionMode mismatching \n\tSet " \ - << Vocab::decode(modes[j]) << " Got " << Vocab::decode(tmp); + << Vocab32::decode(modes[j]) << " Got " << Vocab32::decode(tmp); else yError() << "setInteractionModeRaw failed for" << getBoardInfo() << " joint " << j << " because of interactionMode mismatching \n\tSet " \ - << Vocab::decode(modes[j]) << " Got an unknown value!"; + << Vocab32::decode(modes[j]) << " Got an unknown value!"; return false; } #endif @@ -4840,7 +4840,7 @@ bool embObjMotionControl::checkRemoteControlModeStatus(int joint, int target_mod ret = askRemoteValue(id32, &temp, size); if(ret == false) { - yError ("An error occurred inside embObjMotionControl::checkRemoteControlModeStatus(j=%d, targetmode=%s) for BOARD %s IP %s", joint, yarp::os::Vocab::decode(target_mode).c_str(), res->getProperties().boardnameString.c_str(), res->getProperties().ipv4addrString.c_str()); + yError ("An error occurred inside embObjMotionControl::checkRemoteControlModeStatus(j=%d, targetmode=%s) for BOARD %s IP %s", joint, yarp::os::Vocab32::decode(target_mode).c_str(), res->getProperties().boardnameString.c_str(), res->getProperties().ipv4addrString.c_str()); break; } int current_mode = controlModeStatusConvert_embObj2yarp(temp); @@ -4864,19 +4864,19 @@ bool embObjMotionControl::checkRemoteControlModeStatus(int joint, int target_mod if((yarp::os::Time::now()-timeofstart) > timeout) { ret = false; - yError ("A %f sec timeout occured in embObjMotionControl::checkRemoteControlModeStatus(), BOARD %s IP %s, joint %d, current mode: %s, requested: %s", timeout, res->getProperties().boardnameString.c_str(), res->getProperties().ipv4addrString.c_str(), joint, yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(target_mode).c_str()); + yError ("A %f sec timeout occured in embObjMotionControl::checkRemoteControlModeStatus(), BOARD %s IP %s, joint %d, current mode: %s, requested: %s", timeout, res->getProperties().boardnameString.c_str(), res->getProperties().ipv4addrString.c_str(), joint, yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(target_mode).c_str()); break; } if(attempt > 0) { // i print the warning only after at least one retry. - yWarning ("embObjMotionControl::checkRemoteControlModeStatus() has done %d attempts and will retry again after a %f sec delay. (BOARD %s IP %s, joint %d) -> current mode = %s, requested = %s", attempt+1, delaybetweenqueries, res->getProperties().boardnameString.c_str() , res->getProperties().ipv4addrString.c_str(), joint, yarp::os::Vocab::decode(current_mode).c_str(), yarp::os::Vocab::decode(target_mode).c_str()); + yWarning ("embObjMotionControl::checkRemoteControlModeStatus() has done %d attempts and will retry again after a %f sec delay. (BOARD %s IP %s, joint %d) -> current mode = %s, requested = %s", attempt+1, delaybetweenqueries, res->getProperties().boardnameString.c_str() , res->getProperties().ipv4addrString.c_str(), joint, yarp::os::Vocab32::decode(current_mode).c_str(), yarp::os::Vocab32::decode(target_mode).c_str()); } SystemClock::delaySystem(delaybetweenqueries); } if(false == ret) { - yError("failure of embObjMotionControl::checkRemoteControlModeStatus(j=%d, targetmode=%s) for BOARD %s IP %s after %d attempts and %f seconds", joint, yarp::os::Vocab::decode(target_mode).c_str(), res->getProperties().boardnameString.c_str(), res->getProperties().ipv4addrString.c_str(), attempt, yarp::os::Time::now()-timeofstart); + yError("failure of embObjMotionControl::checkRemoteControlModeStatus(j=%d, targetmode=%s) for BOARD %s IP %s after %d attempts and %f seconds", joint, yarp::os::Vocab32::decode(target_mode).c_str(), res->getProperties().boardnameString.c_str(), res->getProperties().ipv4addrString.c_str(), attempt, yarp::os::Time::now()-timeofstart); } diff --git a/src/libraries/icubmod/embObjMotionControl/eomcParser.cpp b/src/libraries/icubmod/embObjMotionControl/eomcParser.cpp index 6d1289e8c5..2f436546e7 100644 --- a/src/libraries/icubmod/embObjMotionControl/eomcParser.cpp +++ b/src/libraries/icubmod/embObjMotionControl/eomcParser.cpp @@ -791,25 +791,25 @@ bool Parser::parsePidsGroup2FOC(Bottle& pidsGroup, Pid myPid[]) Bottle xtmp; if (!extractGroup(pidsGroup, xtmp, "kff", "kff parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].kff = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].kff = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "kp", "kp parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].kp = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].kp = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "kd", "kd parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].kd = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].kd = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "maxOutput", "maxOutput parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "ki", "ki parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].ki = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].ki = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "maxInt", "maxInt parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "shift", "shift parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].scale = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].scale = xtmp.get(j + 1).asFloat64(); return true; } @@ -827,16 +827,16 @@ bool Parser::parsePidsGroupSimple(Bottle& pidsGroup, Pid myPid[]) Bottle xtmp; if (!extractGroup(pidsGroup, xtmp, "kff", "kff parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].kff = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].kff = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "kp", "kp parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].kp = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].kp = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "kd", "kd parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].kd = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].kd = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "maxOutput", "maxOutput parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j + 1).asFloat64(); return true; } @@ -862,16 +862,16 @@ bool Parser::parsePidsGroupExtended(Bottle& pidsGroup, Pid myPid[]) Bottle xtmp; if (!extractGroup(pidsGroup, xtmp, "ki", "ki parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].ki = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].ki = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "maxInt", "maxInt parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "stictionUp", "stictionUp parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].stiction_up_val = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].stiction_up_val = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "stictionDown", "stictionDown parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) myPid[j].stiction_down_val = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) myPid[j].stiction_down_val = xtmp.get(j + 1).asFloat64(); return true; } @@ -894,13 +894,13 @@ bool Parser::parsePidsGroupDeluxe(Bottle& pidsGroup, Pid myPid[]) Bottle xtmp; if (!extractGroup(pidsGroup, xtmp, "kbemf", "kbemf parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) _kbemf[j] = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) _kbemf[j] = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "ktau", "ktau parameter", _njoints)) return false; - for (int j = 0; j<_njoints; j++) _ktau[j] = xtmp.get(j + 1).asDouble(); + for (int j = 0; j<_njoints; j++) _ktau[j] = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, "filterType", "filterType param", _njoints)) return false; - for (int j = 0; j<_njoints; j++) _filterType[j] = xtmp.get(j + 1).asInt(); + for (int j = 0; j<_njoints; j++) _filterType[j] = xtmp.get(j + 1).asInt32(); return true; } @@ -911,36 +911,36 @@ bool Parser::parsePidsGroup(Bottle& pidsGroup, Pid myPid[], string prefix) int j=0; Bottle xtmp; - if (!extractGroup(pidsGroup, xtmp, prefix + string("kp"), "Pid kp parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].kp = xtmp.get(j+1).asDouble(); - if (!extractGroup(pidsGroup, xtmp, prefix + string("kd"), "Pid kd parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].kd = xtmp.get(j+1).asDouble(); - if (!extractGroup(pidsGroup, xtmp, prefix + string("ki"), "Pid ki parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].ki = xtmp.get(j+1).asDouble(); - if (!extractGroup(pidsGroup, xtmp, prefix + string("maxInt"), "Pid maxInt parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j+1).asDouble(); - if (!extractGroup(pidsGroup, xtmp, prefix + string("maxOutput"), "Pid maxOutput parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j+1).asDouble(); + if (!extractGroup(pidsGroup, xtmp, prefix + string("kp"), "Pid kp parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].kp = xtmp.get(j+1).asFloat64(); + if (!extractGroup(pidsGroup, xtmp, prefix + string("kd"), "Pid kd parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].kd = xtmp.get(j+1).asFloat64(); + if (!extractGroup(pidsGroup, xtmp, prefix + string("ki"), "Pid ki parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].ki = xtmp.get(j+1).asFloat64(); + if (!extractGroup(pidsGroup, xtmp, prefix + string("maxInt"), "Pid maxInt parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].max_int = xtmp.get(j+1).asFloat64(); + if (!extractGroup(pidsGroup, xtmp, prefix + string("maxOutput"), "Pid maxOutput parameter", _njoints)) return false; for (j=0; j<_njoints; j++) myPid[j].max_output = xtmp.get(j+1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, prefix + string("shift"), "Pid shift parameter", _njoints)) for (j = 0; j<_njoints; j++) myPid[j].scale = 0.0; else - for (j=0; j<_njoints; j++) myPid[j].scale = xtmp.get(j+1).asDouble(); + for (j=0; j<_njoints; j++) myPid[j].scale = xtmp.get(j+1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, prefix + string("ko"), "Pid ko parameter", _njoints)) for (j = 0; j<_njoints; j++) myPid[j].offset = 0.0; else - for (j=0; j<_njoints; j++) myPid[j].offset = xtmp.get(j+1).asDouble(); + for (j=0; j<_njoints; j++) myPid[j].offset = xtmp.get(j+1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, prefix + string("stictionUp"), "Pid stictionUp", _njoints)) for (j = 0; j<_njoints; j++) myPid[j].stiction_up_val = 0.0; else - for (j=0; j<_njoints; j++) myPid[j].stiction_up_val = xtmp.get(j+1).asDouble(); + for (j=0; j<_njoints; j++) myPid[j].stiction_up_val = xtmp.get(j+1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, prefix + string("stictionDwn"), "Pid stictionDwn", _njoints)) for (j=0; j<_njoints; j++) myPid[j].stiction_down_val = 0.0; else - for (j = 0; j<_njoints; j++) myPid[j].stiction_down_val = xtmp.get(j + 1).asDouble(); + for (j = 0; j<_njoints; j++) myPid[j].stiction_down_val = xtmp.get(j + 1).asFloat64(); if (!extractGroup(pidsGroup, xtmp, prefix + string("kff"), "Pid kff parameter", _njoints)) for (j=0; j<_njoints; j++) myPid[j].kff = 0.0; else - for (j = 0; j<_njoints; j++) myPid[j].kff = xtmp.get(j + 1).asDouble(); + for (j = 0; j<_njoints; j++) myPid[j].kff = xtmp.get(j + 1).asFloat64(); return true; } @@ -1322,7 +1322,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].hasHallSensor = xtmp.get(i).asInt() != 0; + twofocinfo[i - 1].hasHallSensor = xtmp.get(i).asInt32() != 0; } if (!extractGroup(focGroup, xtmp, "HasTempSensor", "HasTempSensor 0/1 ", _njoints)) { @@ -1331,7 +1331,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].hasTempSensor = xtmp.get(i).asInt() != 0; + twofocinfo[i - 1].hasTempSensor = xtmp.get(i).asInt32() != 0; } if (!extractGroup(focGroup, xtmp, "HasRotorEncoder", "HasRotorEncoder 0/1 ", _njoints)) { @@ -1341,7 +1341,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].hasRotorEncoder = xtmp.get(i).asInt() != 0; + twofocinfo[i - 1].hasRotorEncoder = xtmp.get(i).asInt32() != 0; } if (!extractGroup(focGroup, xtmp, "HasRotorEncoderIndex", "HasRotorEncoderIndex 0/1 ", _njoints)) { @@ -1350,7 +1350,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].hasRotorEncoderIndex = xtmp.get(i).asInt() != 0; + twofocinfo[i - 1].hasRotorEncoderIndex = xtmp.get(i).asInt32() != 0; } if (!extractGroup(focGroup, xtmp, "Verbose", "Verbose 0/1 ", _njoints, false)) @@ -1363,7 +1363,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].verbose = xtmp.get(i).asInt() != 0; + twofocinfo[i - 1].verbose = xtmp.get(i).asInt32() != 0; } std::vector AutoCalibration (_njoints); @@ -1377,7 +1377,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - AutoCalibration[i - 1] = xtmp.get(i).asInt(); + AutoCalibration[i - 1] = xtmp.get(i).asInt32(); } @@ -1391,7 +1391,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn { if(AutoCalibration[i-1] == 0) { - twofocinfo[i - 1].rotorIndexOffset = xtmp.get(i).asInt(); + twofocinfo[i - 1].rotorIndexOffset = xtmp.get(i).asInt32(); if (twofocinfo[i - 1].rotorIndexOffset <0 || twofocinfo[i - 1].rotorIndexOffset >359) { yError() << "In " << _boardname << "joint " << i-1 << ": rotorIndexOffset should be in [0,359] range." ; @@ -1425,7 +1425,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].motorPoles = xtmp.get(i).asInt(); + twofocinfo[i - 1].motorPoles = xtmp.get(i).asInt32(); } if (!extractGroup(focGroup, xtmp, "HasSpeedEncoder", "HasSpeedEncoder 0/1 ", _njoints)) @@ -1437,7 +1437,7 @@ bool Parser::parse2FocGroup(yarp::os::Searchable &config, eomc::twofocSpecificIn else { for (i = 1; i < xtmp.size(); i++) - twofocinfo[i - 1].hasSpeedEncoder = xtmp.get(i).asInt() != 0; + twofocinfo[i - 1].hasSpeedEncoder = xtmp.get(i).asInt32() != 0; } return true; @@ -1462,7 +1462,7 @@ bool Parser::parseJointsetCfgGroup(yarp::os::Searchable &config, std::vector _njoints)) { @@ -1514,7 +1514,7 @@ bool Parser::parseJointsetCfgGroup(yarp::os::Searchable &config, std::vector_njoints)) { @@ -1546,14 +1546,14 @@ bool Parser::parseJointsetCfgGroup(yarp::os::Searchable &config, std::vector= _njoints) { yError() << "embObjMC BOARD " << _boardname << "In AxisMap param: joint " << i-1 << "has been mapped to not-existing joint ("<< user_joint <<"). Here there are only "<< _njoints <<"joints"; @@ -1964,7 +1964,7 @@ bool Parser::parseEncoderFactor(yarp::os::Searchable &config, double encoderFact for (i = 1; i < xtmp.size(); i++) { - tmp_A2E = xtmp.get(i).asDouble(); + tmp_A2E = xtmp.get(i).asFloat64(); if (tmp_A2E<0) { yWarning() << "embObjMC BOARD " << _boardname << "Encoder parameter should be positive!"; @@ -1996,7 +1996,7 @@ bool Parser::parsefullscalePWM(yarp::os::Searchable &config, double dutycycleToP for (i = 1; i < xtmp.size(); i++) { - tmpval = xtmp.get(i).asDouble(); + tmpval = xtmp.get(i).asFloat64(); if (tmpval<0) { yError() << "embObjMC BOARD " << _boardname << "fullscalePWM parameter should be positive!"; @@ -2029,7 +2029,7 @@ bool Parser::parseAmpsToSensor(yarp::os::Searchable &config, double ampsToSensor for (i = 1; i < xtmp.size(); i++) { - tmpval = xtmp.get(i).asDouble(); + tmpval = xtmp.get(i).asFloat64(); if (tmpval<0) { yError() << "embObjMC BOARD " << _boardname << "ampsToSensor parameter should be positive!"; @@ -2061,7 +2061,7 @@ bool Parser::parseGearboxValues(yarp::os::Searchable &config, double gearbox_M2J for (i = 1; i < xtmp.size(); i++) { - gearbox_M2J[i-1] = xtmp.get(i).asDouble(); + gearbox_M2J[i-1] = xtmp.get(i).asFloat64(); if (gearbox_M2J[i-1]==0) { yError() << "embObjMC BOARD " << _boardname << "Using a gearbox value = 0 may cause problems! Check your configuration files"; @@ -2079,7 +2079,7 @@ bool Parser::parseGearboxValues(yarp::os::Searchable &config, double gearbox_M2J int test = xtmp.size(); for (i = 1; i < xtmp.size(); i++) { - gearbox_E2J[i-1] = xtmp.get(i).asDouble(); + gearbox_E2J[i-1] = xtmp.get(i).asFloat64(); if (gearbox_E2J[i-1]==0) { yError() << "embObjMC BOARD " << _boardname << "Using a gearbox value = 0 may cause problems! Check your configuration files"; @@ -2121,7 +2121,7 @@ bool Parser::parseDeadzoneValue(yarp::os::Searchable &config, double deadzone[], *found = true; for (i = 1; i < xtmp.size(); i++) { - deadzone[i-1] = xtmp.get(i).asDouble(); + deadzone[i-1] = xtmp.get(i).asFloat64(); } return true; @@ -2145,7 +2145,7 @@ bool Parser::parseMechanicalsFlags(yarp::os::Searchable &config, int useMotorSpe for (i = 1; i < xtmp.size(); i++) { - useMotorSpeedFbk[i-1] = xtmp.get(i).asInt(); + useMotorSpeedFbk[i-1] = xtmp.get(i).asInt32(); } return true; @@ -2180,13 +2180,13 @@ bool Parser::parseImpedanceGroup(yarp::os::Searchable &config,std::vector &matrix, bool &formaterror, double item = 0; // ok, i use the standard converter ... but what if it is not a double format? so far we dont check. - item = bottle.get(i+1).asDouble(); + item = bottle.get(i+1).asFloat64(); matrix.push_back(item); } diff --git a/src/libraries/icubmod/embObjMultiEnc/embObjMultiEnc.cpp b/src/libraries/icubmod/embObjMultiEnc/embObjMultiEnc.cpp index e936d0e957..df223269c2 100755 --- a/src/libraries/icubmod/embObjMultiEnc/embObjMultiEnc.cpp +++ b/src/libraries/icubmod/embObjMultiEnc/embObjMultiEnc.cpp @@ -39,6 +39,7 @@ #include "EoProtocolMC.h" #include +#include #ifdef WIN32 #pragma warning(once:4355) @@ -112,7 +113,7 @@ bool embObjMultiEnc::fromConfig(yarp::os::Searchable &_config) numofjoints = jointsbottle.size() -1; listofjoints.clear(); - for (int i = 1; i < jointsbottle.size(); i++) listofjoints.push_back(jointsbottle.get(i).asInt()); + for (int i = 1; i < jointsbottle.size(); i++) listofjoints.push_back(jointsbottle.get(i).asInt32()); yDebug()<< " embObjMultiEnc List of joints: " << numofjoints; for(int i=0; i +#include #include "EoCommon.h" @@ -61,10 +62,10 @@ EmbObjSkin::EmbObjSkin() : _isDiagnosticPresent(false) _skCfg.numOfPatches = 0; _skCfg.totalCardsNum = 0; - std::string tmp = NetworkBase::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - verbosewhenok = (bool)NetType::toInt(tmp); + verbosewhenok = (bool)(yarp::conf::numeric::from_string(tmp, 0U)); } else { @@ -293,7 +294,7 @@ bool EmbObjSkin::fromConfig(yarp::os::Searchable& config) if (bPatches.check(tmp)) { _skCfg.numOfPatches++; - bPatchList.addInt(i); + bPatchList.addInt32(i); } } @@ -301,7 +302,7 @@ bool EmbObjSkin::fromConfig(yarp::os::Searchable& config) _skCfg. patchInfoList.resize(_skCfg.numOfPatches); for(int j=1; j<_skCfg.numOfPatches+1; j++) { - int id = bPatchList.get(j-1).asInt(); + int id = bPatchList.get(j-1).asInt32(); if((id!=1) && (id!=2)) { yError() << "EmbObjSkin::fromConfig(): in skin BOARD" << res->getProperties().boardnameString << "IP" << res->getProperties().ipv4addrString << "expecting at most 2 patches"; @@ -331,7 +332,7 @@ bool EmbObjSkin::fromConfig(yarp::os::Searchable& config) for(int j=1; j +#include #ifdef WIN32 #pragma warning(once:4355) @@ -88,10 +89,10 @@ embObjStrain::embObjStrain() scaleFactorIsFilled = false; - std::string tmp = NetworkBase::getEnvironment("ETH_VERBOSEWHENOK"); + std::string tmp = yarp::conf::environment::get_string("ETH_VERBOSEWHENOK"); if (tmp != "") { - verbosewhenok = (bool)NetType::toInt(tmp); + verbosewhenok = (bool)(yarp::conf::numeric::from_string(tmp, 0U)); } else { diff --git a/src/libraries/icubmod/esdCan/EsdCan.cpp b/src/libraries/icubmod/esdCan/EsdCan.cpp index d4a8015c99..7d81b711a6 100644 --- a/src/libraries/icubmod/esdCan/EsdCan.cpp +++ b/src/libraries/icubmod/esdCan/EsdCan.cpp @@ -153,20 +153,20 @@ bool EsdCan::open(yarp::os::Searchable &par) int txTimeout=500; int rxTimeout=500; - netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); - if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); + netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); + if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); - txTimeout=par.check("CanTxTimeout", Value(500), "timeout on transmission [ms]").asInt(); - if (txTimeout == 500) txTimeout=par.check("canTxTimeout", Value(500), "timeout on transmission [ms]").asInt(); + txTimeout=par.check("CanTxTimeout", Value(500), "timeout on transmission [ms]").asInt32(); + if (txTimeout == 500) txTimeout=par.check("canTxTimeout", Value(500), "timeout on transmission [ms]").asInt32(); - rxTimeout=par.check("CanRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt() ; - if (rxTimeout == 500) rxTimeout=par.check("canRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt() ; + rxTimeout=par.check("CanRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt32() ; + if (rxTimeout == 500) rxTimeout=par.check("canRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt32() ; - canTxQueue=par.check("CanTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt(); - if (canTxQueue == TX_QUEUE_SIZE) canTxQueue=par.check("canTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt(); + canTxQueue=par.check("CanTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt32(); + if (canTxQueue == TX_QUEUE_SIZE) canTxQueue=par.check("canTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt32(); - canRxQueue=par.check("CanRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt() ; - if (canRxQueue == RX_QUEUE_SIZE) canRxQueue=par.check("canRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt() ; + canRxQueue=par.check("CanRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt32() ; + if (canRxQueue == RX_QUEUE_SIZE) canRxQueue=par.check("canRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt32() ; int mode=0; diff --git a/src/libraries/icubmod/esdSniffer/EsdMessageSniffer.cpp b/src/libraries/icubmod/esdSniffer/EsdMessageSniffer.cpp index 9df8c486f7..3dc8952018 100644 --- a/src/libraries/icubmod/esdSniffer/EsdMessageSniffer.cpp +++ b/src/libraries/icubmod/esdSniffer/EsdMessageSniffer.cpp @@ -436,38 +436,38 @@ bool EsdMessageSniffer::open(yarp::os::Searchable& config) } int i; - int nj = p.findGroup("GENERAL").find("Joints").asInt(); + int nj = p.findGroup("GENERAL").find("Joints").asInt32(); EsdMessageSnifferParameters params(nj); params._njoints = nj; ///// CAN PARAMETERS Bottle &xtmp = p.findGroup("CAN").findGroup("CanDeviceNum"); - params._networkN=xtmp.get(1).asInt(); + params._networkN=xtmp.get(1).asInt32(); xtmp = p.findGroup("CAN").findGroup("CanMyAddress"); - params._my_address=xtmp.get(1).asInt(); + params._my_address=xtmp.get(1).asInt32(); xtmp = p.findGroup("CAN").findGroup("CanPollingInterval"); - params._polling_interval=xtmp.get(1).asInt(); + params._polling_interval=xtmp.get(1).asInt32(); xtmp = p.findGroup("CAN").findGroup("CanTimeout"); - params._timeout=xtmp.get(1).asInt(); + params._timeout=xtmp.get(1).asInt32(); xtmp = p.findGroup("CAN").findGroup("CanAddresses"); - for (i = 1; i < xtmp.size(); i++) params._destinations[i-1] = (unsigned char)(xtmp.get(i).asInt()); + for (i = 1; i < xtmp.size(); i++) params._destinations[i-1] = (unsigned char)(xtmp.get(i).asInt32()); ////// GENERAL xtmp = p.findGroup("GENERAL").findGroup("AxisMap"); ACE_ASSERT (xtmp.size() == nj+1); - for (i = 1; i < xtmp.size(); i++) params._axisMap[i-1] = xtmp.get(i).asInt(); + for (i = 1; i < xtmp.size(); i++) params._axisMap[i-1] = xtmp.get(i).asInt32(); xtmp = p.findGroup("GENERAL").findGroup("Encoder"); ACE_ASSERT (xtmp.size() == nj+1); - for (i = 1; i < xtmp.size(); i++) params._angleToEncoder[i-1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) params._angleToEncoder[i-1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("GENERAL").findGroup("Zeros"); ACE_ASSERT (xtmp.size() == nj+1); - for (i = 1; i < xtmp.size(); i++) params._zeros[i-1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) params._zeros[i-1] = xtmp.get(i).asFloat64(); - if (p.findGroup("GENERAL").find("Verbose").asInt() == 1) + if (p.findGroup("GENERAL").find("Verbose").asInt32() == 1) params._p = ACE_OS::printf; else params._p = NULL; diff --git a/src/libraries/icubmod/fakeCan/fakeCan.cpp b/src/libraries/icubmod/fakeCan/fakeCan.cpp index f8039089d8..412601dcea 100644 --- a/src/libraries/icubmod/fakeCan/fakeCan.cpp +++ b/src/libraries/icubmod/fakeCan/fakeCan.cpp @@ -101,7 +101,7 @@ bool FakeCan::open(yarp::os::Searchable &par) //fprintf(stderr, "%s", par.toString().c_str()); - int njoints=par.findGroup("GENERAL").find("Joints").asInt(); + int njoints=par.findGroup("GENERAL").find("Joints").asInt32(); Bottle &can = par.findGroup("CAN"); Bottle ids=can.findGroup("CanAddresses"); @@ -114,7 +114,7 @@ bool FakeCan::open(yarp::os::Searchable &par) for(int i=1;i<=njoints/2;i++) { FakeBoard *tmp=new FakeBoard; - int id=ids.get(i).asInt(); + int id=ids.get(i).asInt32(); tmp->setId(id); //just as a test tmp->setReplyFifo(&replies); tmp->start(); diff --git a/src/libraries/icubmod/gazeController/ClientGazeController.cpp b/src/libraries/icubmod/gazeController/ClientGazeController.cpp index 9eb375225f..dfc0bd4900 100644 --- a/src/libraries/icubmod/gazeController/ClientGazeController.cpp +++ b/src/libraries/icubmod/gazeController/ClientGazeController.cpp @@ -27,8 +27,8 @@ #define GAZECTRL_CLIENT_VER 1.2 #define GAZECTRL_DEFAULT_TMO 0.1 // [s] -#define GAZECTRL_ACK Vocab::encode("ack") -#define GAZECTRL_NACK Vocab::encode("nack") +#define GAZECTRL_ACK Vocab32::encode("ack") +#define GAZECTRL_NACK Vocab32::encode("nack") using namespace std; using namespace yarp::os; @@ -105,7 +105,7 @@ bool ClientGazeController::open(Searchable &config) carrier=config.check("carrier",Value("udp")).asString(); if (config.check("timeout")) - timeout=config.find("timeout").asDouble(); + timeout=config.find("timeout").asFloat64(); portCmdFp.open(local+"/xd:o"); portCmdAng.open(local+"/angles:o"); @@ -125,7 +125,7 @@ bool ClientGazeController::open(Searchable &config) getInfoHelper(info); if (info.check("server_version")) { - double server_version=info.find("server_version").asDouble(); + double server_version=info.find("server_version").asFloat64(); if (server_version!=GAZECTRL_CLIENT_VER) { yError("version mismatch => server(%g) != client(%g); please update accordingly", @@ -202,7 +202,7 @@ bool ClientGazeController::setTrackingMode(const bool f) Bottle command, reply; command.addString("set"); command.addString("track"); - command.addInt((int)f); + command.addInt32((int)f); if (!portRpc.write(command,reply)) { @@ -210,7 +210,7 @@ bool ClientGazeController::setTrackingMode(const bool f) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -230,9 +230,9 @@ bool ClientGazeController::getTrackingMode(bool *f) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *f=(reply.get(1).asInt()>0); + *f=(reply.get(1).asInt32()>0); return true; } @@ -249,7 +249,7 @@ bool ClientGazeController::setStabilizationMode(const bool f) Bottle command, reply; command.addString("set"); command.addString("stab"); - command.addInt((int)f); + command.addInt32((int)f); if (!portRpc.write(command,reply)) { @@ -257,7 +257,7 @@ bool ClientGazeController::setStabilizationMode(const bool f) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -277,9 +277,9 @@ bool ClientGazeController::getStabilizationMode(bool *f) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *f=(reply.get(1).asInt()>0); + *f=(reply.get(1).asInt32()>0); return true; } @@ -340,9 +340,9 @@ bool ClientGazeController::lookAtFixationPoint(const Vector &fp) Bottle &cmd=portCmdFp.prepare(); cmd.clear(); - cmd.addDouble(fp[0]); - cmd.addDouble(fp[1]); - cmd.addDouble(fp[2]); + cmd.addFloat64(fp[0]); + cmd.addFloat64(fp[1]); + cmd.addFloat64(fp[2]); portCmdFp.writeStrict(); return true; @@ -359,9 +359,9 @@ bool ClientGazeController::lookAtAbsAngles(const Vector &ang) cmd.clear(); cmd.addString("abs"); - cmd.addDouble(ang[0]); - cmd.addDouble(ang[1]); - cmd.addDouble(ang[2]); + cmd.addFloat64(ang[0]); + cmd.addFloat64(ang[1]); + cmd.addFloat64(ang[2]); portCmdAng.writeStrict(); return true; @@ -378,9 +378,9 @@ bool ClientGazeController::lookAtRelAngles(const Vector &ang) cmd.clear(); cmd.addString("rel"); - cmd.addDouble(ang[0]); - cmd.addDouble(ang[1]); - cmd.addDouble(ang[2]); + cmd.addFloat64(ang[0]); + cmd.addFloat64(ang[1]); + cmd.addFloat64(ang[2]); portCmdAng.writeStrict(); return true; @@ -398,9 +398,9 @@ bool ClientGazeController::lookAtMonoPixel(const int camSel, const Vector &px, cmd.clear(); cmd.addString((camSel==0)?"left":"right"); - cmd.addDouble(px[0]); - cmd.addDouble(px[1]); - cmd.addDouble(z); + cmd.addFloat64(px[0]); + cmd.addFloat64(px[1]); + cmd.addFloat64(z); portCmdMono.writeStrict(); return true; @@ -419,10 +419,10 @@ bool ClientGazeController::lookAtMonoPixelWithVergence(const int camSel, cmd.clear(); cmd.addString((camSel==0)?"left":"right"); - cmd.addDouble(px[0]); - cmd.addDouble(px[1]); + cmd.addFloat64(px[0]); + cmd.addFloat64(px[1]); cmd.addString("ver"); - cmd.addDouble(ver); + cmd.addFloat64(ver); portCmdMono.writeStrict(); return true; @@ -438,10 +438,10 @@ bool ClientGazeController::lookAtStereoPixels(const Vector &pxl, const Vector &p Bottle &cmd=portCmdStereo.prepare(); cmd.clear(); - cmd.addDouble(pxl[0]); - cmd.addDouble(pxl[1]); - cmd.addDouble(pxr[0]); - cmd.addDouble(pxr[1]); + cmd.addFloat64(pxl[0]); + cmd.addFloat64(pxl[1]); + cmd.addFloat64(pxr[0]); + cmd.addFloat64(pxr[1]); portCmdStereo.writeStrict(); return true; @@ -458,9 +458,9 @@ bool ClientGazeController::lookAtFixationPointSync(const Vector &fp) command.addString("look"); command.addString("3D"); Bottle &payLoad=command.addList(); - payLoad.addDouble(fp[0]); - payLoad.addDouble(fp[1]); - payLoad.addDouble(fp[2]); + payLoad.addFloat64(fp[0]); + payLoad.addFloat64(fp[1]); + payLoad.addFloat64(fp[2]); if (!portRpc.write(command,reply)) { @@ -468,7 +468,7 @@ bool ClientGazeController::lookAtFixationPointSync(const Vector &fp) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -484,7 +484,7 @@ bool ClientGazeController::lookAtAbsAnglesSync(const Vector &ang) Bottle &payLoad=command.addList(); payLoad.addString("abs"); for (size_t i=0; i1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *t=reply.get(1).asDouble(); + *t=reply.get(1).asFloat64(); return true; } @@ -643,9 +643,9 @@ bool ClientGazeController::getEyesTrajTime(double *t) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *t=reply.get(1).asDouble(); + *t=reply.get(1).asFloat64(); return true; } @@ -669,9 +669,9 @@ bool ClientGazeController::getVORGain(double *gain) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *gain=reply.get(1).asDouble(); + *gain=reply.get(1).asFloat64(); return true; } @@ -695,9 +695,9 @@ bool ClientGazeController::getOCRGain(double *gain) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *gain=reply.get(1).asDouble(); + *gain=reply.get(1).asFloat64(); return true; } @@ -721,9 +721,9 @@ bool ClientGazeController::getSaccadesMode(bool *f) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *f=(reply.get(1).asInt()>0); + *f=(reply.get(1).asInt32()>0); return true; } @@ -747,9 +747,9 @@ bool ClientGazeController::getSaccadesInhibitionPeriod(double *period) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *period=reply.get(1).asDouble(); + *period=reply.get(1).asFloat64(); return true; } @@ -773,9 +773,9 @@ bool ClientGazeController::getSaccadesActivationAngle(double *angle) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *angle=reply.get(1).asDouble(); + *angle=reply.get(1).asFloat64(); return true; } @@ -801,7 +801,7 @@ bool ClientGazeController::getPose(const string &poseSel, Vector &x, Vector &o, return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bPose=reply.get(1).asList()) { @@ -811,17 +811,17 @@ bool ClientGazeController::getPose(const string &poseSel, Vector &x, Vector &o, o.resize(bPose->size()-x.length()); for (size_t i=0; iget(i).asDouble(); + x[i]=bPose->get(i).asFloat64(); for (size_t i=0; iget(x.length()+i).asDouble(); + o[i]=bPose->get(x.length()+i).asFloat64(); if ((reply.size()>2) && (stamp!=NULL)) { if (Bottle *bStamp=reply.get(2).asList()) { - Stamp tmpStamp(bStamp->get(0).asInt(), - bStamp->get(1).asDouble()); + Stamp tmpStamp(bStamp->get(0).asInt32(), + bStamp->get(1).asFloat64()); *stamp=tmpStamp; } @@ -869,9 +869,9 @@ bool ClientGazeController::get2DPixel(const int camSel, const Vector &x, command.addString("2D"); Bottle &bOpt=command.addList(); bOpt.addString((camSel==0)?"left":"right"); - bOpt.addDouble(x[0]); - bOpt.addDouble(x[1]); - bOpt.addDouble(x[2]); + bOpt.addFloat64(x[0]); + bOpt.addFloat64(x[1]); + bOpt.addFloat64(x[2]); if (!portRpc.write(command,reply)) { @@ -879,13 +879,13 @@ bool ClientGazeController::get2DPixel(const int camSel, const Vector &x, return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bPixel=reply.get(1).asList()) { px.resize(bPixel->size()); for (size_t i=0; iget(i).asDouble(); + px[i]=bPixel->get(i).asFloat64(); return true; } @@ -908,9 +908,9 @@ bool ClientGazeController::get3DPoint(const int camSel, const Vector &px, command.addString("mono"); Bottle &bOpt=command.addList(); bOpt.addString((camSel==0)?"left":"right"); - bOpt.addDouble(px[0]); - bOpt.addDouble(px[1]); - bOpt.addDouble(z); + bOpt.addFloat64(px[0]); + bOpt.addFloat64(px[1]); + bOpt.addFloat64(z); if (!portRpc.write(command,reply)) { @@ -918,13 +918,13 @@ bool ClientGazeController::get3DPoint(const int camSel, const Vector &px, return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bPoint=reply.get(1).asList()) { x.resize(bPoint->size()); for (size_t i=0; iget(i).asDouble(); + x[i]=bPoint->get(i).asFloat64(); return true; } @@ -947,12 +947,12 @@ bool ClientGazeController::get3DPointOnPlane(const int camSel, const Vector &px, command.addString("proj"); Bottle &bOpt=command.addList(); bOpt.addString((camSel==0)?"left":"right"); - bOpt.addDouble(px[0]); - bOpt.addDouble(px[1]); - bOpt.addDouble(plane[0]); - bOpt.addDouble(plane[1]); - bOpt.addDouble(plane[2]); - bOpt.addDouble(plane[3]); + bOpt.addFloat64(px[0]); + bOpt.addFloat64(px[1]); + bOpt.addFloat64(plane[0]); + bOpt.addFloat64(plane[1]); + bOpt.addFloat64(plane[2]); + bOpt.addFloat64(plane[3]); if (!portRpc.write(command,reply)) { @@ -960,13 +960,13 @@ bool ClientGazeController::get3DPointOnPlane(const int camSel, const Vector &px, return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bPoint=reply.get(1).asList()) { x.resize(bPoint->size()); for (size_t i=0; iget(i).asDouble(); + x[i]=bPoint->get(i).asFloat64(); return true; } @@ -989,9 +989,9 @@ bool ClientGazeController::get3DPointFromAngles(const int mode, const Vector &an command.addString("ang"); Bottle &bOpt=command.addList(); bOpt.addString((mode==0)?"abs":"rel"); - bOpt.addDouble(ang[0]); - bOpt.addDouble(ang[1]); - bOpt.addDouble(ang[2]); + bOpt.addFloat64(ang[0]); + bOpt.addFloat64(ang[1]); + bOpt.addFloat64(ang[2]); if (!portRpc.write(command,reply)) { @@ -999,13 +999,13 @@ bool ClientGazeController::get3DPointFromAngles(const int mode, const Vector &an return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bPoint=reply.get(1).asList()) { x.resize(bPoint->size()); for (size_t i=0; iget(i).asDouble(); + x[i]=bPoint->get(i).asFloat64(); return true; } @@ -1025,9 +1025,9 @@ bool ClientGazeController::getAnglesFrom3DPoint(const Vector &x, Vector &ang) command.addString("get"); command.addString("ang"); Bottle &bOpt=command.addList(); - bOpt.addDouble(x[0]); - bOpt.addDouble(x[1]); - bOpt.addDouble(x[2]); + bOpt.addFloat64(x[0]); + bOpt.addFloat64(x[1]); + bOpt.addFloat64(x[2]); if (!portRpc.write(command,reply)) { @@ -1035,13 +1035,13 @@ bool ClientGazeController::getAnglesFrom3DPoint(const Vector &x, Vector &ang) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bAng=reply.get(1).asList()) { ang.resize(bAng->size()); for (size_t i=0; iget(i).asDouble(); + ang[i]=bAng->get(i).asFloat64(); return true; } @@ -1063,10 +1063,10 @@ bool ClientGazeController::triangulate3DPoint(const Vector &pxl, const Vector &p command.addString("3D"); command.addString("stereo"); Bottle &bOpt=command.addList(); - bOpt.addDouble(pxl[0]); - bOpt.addDouble(pxl[1]); - bOpt.addDouble(pxr[0]); - bOpt.addDouble(pxr[1]); + bOpt.addFloat64(pxl[0]); + bOpt.addFloat64(pxl[1]); + bOpt.addFloat64(pxr[0]); + bOpt.addFloat64(pxr[1]); if (!portRpc.write(command,reply)) { @@ -1074,13 +1074,13 @@ bool ClientGazeController::triangulate3DPoint(const Vector &pxl, const Vector &p return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bPoint=reply.get(1).asList()) { x.resize(bPoint->size()); for (size_t i=0; iget(i).asDouble(); + x[i]=bPoint->get(i).asFloat64(); return true; } @@ -1106,13 +1106,13 @@ bool ClientGazeController::getJointsDesired(Vector &qdes) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bDes=reply.get(1).asList()) { qdes.resize(bDes->size()); for (size_t i=0; iget(i).asDouble(); + qdes[i]=bDes->get(i).asFloat64(); return true; } @@ -1138,13 +1138,13 @@ bool ClientGazeController::getJointsVelocities(Vector &qdot) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bVel=reply.get(1).asList()) { qdot.resize(bVel->size()); for (size_t i=0; iget(i).asDouble(); + qdot[i]=bVel->get(i).asFloat64(); return true; } @@ -1170,7 +1170,7 @@ bool ClientGazeController::getStereoOptions(Bottle &options) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { if (Bottle *bOpt=reply.get(1).asList()) { @@ -1192,7 +1192,7 @@ bool ClientGazeController::setNeckTrajTime(const double t) Bottle command, reply; command.addString("set"); command.addString("Tneck"); - command.addDouble(t); + command.addFloat64(t); if (!portRpc.write(command,reply)) { @@ -1200,7 +1200,7 @@ bool ClientGazeController::setNeckTrajTime(const double t) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1213,7 +1213,7 @@ bool ClientGazeController::setEyesTrajTime(const double t) Bottle command, reply; command.addString("set"); command.addString("Teyes"); - command.addDouble(t); + command.addFloat64(t); if (!portRpc.write(command,reply)) { @@ -1221,7 +1221,7 @@ bool ClientGazeController::setEyesTrajTime(const double t) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1234,7 +1234,7 @@ bool ClientGazeController::setVORGain(const double gain) Bottle command, reply; command.addString("set"); command.addString("vor"); - command.addDouble(gain); + command.addFloat64(gain); if (!portRpc.write(command,reply)) { @@ -1242,7 +1242,7 @@ bool ClientGazeController::setVORGain(const double gain) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1255,7 +1255,7 @@ bool ClientGazeController::setOCRGain(const double gain) Bottle command, reply; command.addString("set"); command.addString("ocr"); - command.addDouble(gain); + command.addFloat64(gain); if (!portRpc.write(command,reply)) { @@ -1263,7 +1263,7 @@ bool ClientGazeController::setOCRGain(const double gain) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1276,7 +1276,7 @@ bool ClientGazeController::setSaccadesMode(const bool f) Bottle command, reply; command.addString("set"); command.addString("sacc"); - command.addInt((int)f); + command.addInt32((int)f); if (!portRpc.write(command,reply)) { @@ -1284,7 +1284,7 @@ bool ClientGazeController::setSaccadesMode(const bool f) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1297,7 +1297,7 @@ bool ClientGazeController::setSaccadesInhibitionPeriod(const double period) Bottle command, reply; command.addString("set"); command.addString("sinh"); - command.addDouble(period); + command.addFloat64(period); if (!portRpc.write(command,reply)) { @@ -1305,7 +1305,7 @@ bool ClientGazeController::setSaccadesInhibitionPeriod(const double period) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1318,7 +1318,7 @@ bool ClientGazeController::setSaccadesActivationAngle(const double angle) Bottle command, reply; command.addString("set"); command.addString("sact"); - command.addDouble(angle); + command.addFloat64(angle); if (!portRpc.write(command,reply)) { @@ -1326,7 +1326,7 @@ bool ClientGazeController::setSaccadesActivationAngle(const double angle) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1347,7 +1347,7 @@ bool ClientGazeController::setStereoOptions(const Bottle &options) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1361,8 +1361,8 @@ bool ClientGazeController::blockNeckJoint(const string &joint, const double min, Bottle command, reply; command.addString("bind"); command.addString(joint); - command.addDouble(min); - command.addDouble(max); + command.addFloat64(min); + command.addFloat64(max); if (!portRpc.write(command,reply)) { @@ -1370,7 +1370,7 @@ bool ClientGazeController::blockNeckJoint(const string &joint, const double min, return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1402,10 +1402,10 @@ bool ClientGazeController::getNeckJointRange(const string &joint, double *min, return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>2)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>2)) { - *min=reply.get(1).asDouble(); - *max=reply.get(2).asDouble(); + *min=reply.get(1).asFloat64(); + *max=reply.get(2).asFloat64(); return true; } @@ -1429,7 +1429,7 @@ bool ClientGazeController::clearJoint(const string &joint) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1505,7 +1505,7 @@ bool ClientGazeController::blockEyes(const double ver) Bottle command, reply; command.addString("bind"); command.addString("eyes"); - command.addDouble(ver); + command.addFloat64(ver); if (!portRpc.write(command,reply)) { @@ -1513,7 +1513,7 @@ bool ClientGazeController::blockEyes(const double ver) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1565,9 +1565,9 @@ bool ClientGazeController::getBlockedVergence(double *ver) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>2)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>2)) { - *ver=reply.get(1).asDouble(); + *ver=reply.get(1).asFloat64(); return true; } @@ -1619,9 +1619,9 @@ bool ClientGazeController::getNeckAngleUserTolerance(double *angle) return false; } - if ((reply.get(0).asVocab()==GAZECTRL_ACK) && (reply.size()>1)) + if ((reply.get(0).asVocab32()==GAZECTRL_ACK) && (reply.size()>1)) { - *angle=reply.get(1).asDouble(); + *angle=reply.get(1).asFloat64(); return true; } @@ -1638,7 +1638,7 @@ bool ClientGazeController::setNeckAngleUserTolerance(const double angle) Bottle command, reply; command.addString("set"); command.addString("ntol"); - command.addDouble(angle); + command.addFloat64(angle); if (!portRpc.write(command,reply)) { @@ -1646,7 +1646,7 @@ bool ClientGazeController::setNeckAngleUserTolerance(const double angle) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1666,9 +1666,9 @@ bool ClientGazeController::checkMotionDone(bool *f) return false; } - if (reply.get(0).asVocab()==GAZECTRL_ACK) + if (reply.get(0).asVocab32()==GAZECTRL_ACK) { - *f=(reply.get(1).asInt()>0); + *f=(reply.get(1).asInt32()>0); return true; } else @@ -1710,9 +1710,9 @@ bool ClientGazeController::checkSaccadeDone(bool *f) return false; } - if (reply.get(0).asVocab()==GAZECTRL_ACK) + if (reply.get(0).asVocab32()==GAZECTRL_ACK) { - *f=(reply.get(1).asInt()>0); + *f=(reply.get(1).asInt32()>0); return true; } else @@ -1753,7 +1753,7 @@ bool ClientGazeController::stopControl() return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1772,9 +1772,9 @@ bool ClientGazeController::storeContext(int *id) return false; } - if (reply.get(0).asVocab()==GAZECTRL_ACK) + if (reply.get(0).asVocab32()==GAZECTRL_ACK) { - contextIdList.insert(*id=reply.get(1).asInt()); + contextIdList.insert(*id=reply.get(1).asInt32()); return true; } else @@ -1790,7 +1790,7 @@ bool ClientGazeController::restoreContext(const int id) Bottle command, reply; command.addString("rest"); - command.addInt(id); + command.addInt32(id); if (!portRpc.write(command,reply)) { @@ -1798,7 +1798,7 @@ bool ClientGazeController::restoreContext(const int id) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1810,7 +1810,7 @@ bool ClientGazeController::deleteContext(const int id) Bottle command, reply; command.addString("del"); - command.addList().addInt(id); + command.addList().addInt32(id); if (!portRpc.write(command,reply)) { @@ -1818,7 +1818,7 @@ bool ClientGazeController::deleteContext(const int id) return false; } - if (reply.get(0).asVocab()==GAZECTRL_ACK) + if (reply.get(0).asVocab32()==GAZECTRL_ACK) { contextIdList.erase(id); return true; @@ -1841,7 +1841,7 @@ bool ClientGazeController::deleteContexts() command.addString("del"); Bottle &ids=command.addList(); for (set::iterator itr=contextIdList.begin(); itr!=contextIdList.end(); itr++) - ids.addInt(*itr); + ids.addInt32(*itr); if (!portRpc.write(command,reply)) { @@ -1851,7 +1851,7 @@ bool ClientGazeController::deleteContexts() contextIdList.clear(); - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -1868,7 +1868,7 @@ bool ClientGazeController::getInfoHelper(Bottle &info) return false; } - if (reply.get(0).asVocab()==GAZECTRL_ACK) + if (reply.get(0).asVocab32()==GAZECTRL_ACK) { if (reply.size()>1) { @@ -1897,8 +1897,8 @@ bool ClientGazeController::getInfo(Bottle &info) void ClientGazeController::eventHandling(Bottle &event) { string type=event.get(0).asString(); - double time=event.get(1).asDouble(); - double checkPoint=(type=="motion-ongoing")?event.get(2).asDouble():-1.0; + double time=event.get(1).asFloat64(); + double checkPoint=(type=="motion-ongoing")?event.get(2).asFloat64():-1.0; map::iterator itr; // rise the all-events callback @@ -1959,7 +1959,7 @@ bool ClientGazeController::registerEvent(GazeEvent &event) Bottle command, reply; command.addString("register"); command.addString("ongoing"); - command.addDouble(checkPoint); + command.addFloat64(checkPoint); if (!portRpc.write(command,reply)) { @@ -1967,7 +1967,7 @@ bool ClientGazeController::registerEvent(GazeEvent &event) return false; } - if (reply.get(0).asVocab()!=GAZECTRL_ACK) + if (reply.get(0).asVocab32()!=GAZECTRL_ACK) return false; ostringstream ss; @@ -1994,7 +1994,7 @@ bool ClientGazeController::unregisterEvent(GazeEvent &event) Bottle command, reply; command.addString("unregister"); command.addString("ongoing"); - command.addDouble(checkPoint); + command.addFloat64(checkPoint); if (!portRpc.write(command,reply)) { @@ -2002,7 +2002,7 @@ bool ClientGazeController::unregisterEvent(GazeEvent &event) return false; } - if (reply.get(0).asVocab()!=GAZECTRL_ACK) + if (reply.get(0).asVocab32()!=GAZECTRL_ACK) return false; ostringstream ss; @@ -2032,7 +2032,7 @@ bool ClientGazeController::tweakSet(const Bottle &options) return false; } - return (reply.get(0).asVocab()==GAZECTRL_ACK); + return (reply.get(0).asVocab32()==GAZECTRL_ACK); } @@ -2052,7 +2052,7 @@ bool ClientGazeController::tweakGet(Bottle &options) return false; } - if (reply.get(0).asVocab()==GAZECTRL_ACK) + if (reply.get(0).asVocab32()==GAZECTRL_ACK) { if (reply.size()>1) { diff --git a/src/libraries/icubmod/imuFilter/ImuFilter.cpp b/src/libraries/icubmod/imuFilter/ImuFilter.cpp index f26169cf81..2170669060 100644 --- a/src/libraries/icubmod/imuFilter/ImuFilter.cpp +++ b/src/libraries/icubmod/imuFilter/ImuFilter.cpp @@ -122,12 +122,12 @@ bool ImuFilter::open(yarp::os::Searchable& config) string name=config.check("name",Value("imuFilter")).asString(); string robot=config.check("robot",Value("icub")).asString(); - size_t gyro_order=(size_t)config.check("gyro-order",Value(5)).asInt(); - size_t mag_order=(size_t)config.check("mag-order",Value(51)).asInt(); + size_t gyro_order=(size_t)config.check("gyro-order",Value(5)).asInt32(); + size_t mag_order=(size_t)config.check("mag-order",Value(51)).asInt32(); - mag_vel_thres_up=config.check("mag-vel-thres-up",Value(0.04)).asDouble(); - mag_vel_thres_down=config.check("mag-vel-thres-down",Value(0.02)).asDouble(); - bias_gain=config.check("bias-gain",Value(0.001)).asDouble(); + mag_vel_thres_up=config.check("mag-vel-thres-up",Value(0.04)).asFloat64(); + mag_vel_thres_down=config.check("mag-vel-thres-down",Value(0.02)).asFloat64(); + bias_gain=config.check("bias-gain",Value(0.001)).asFloat64(); verbose=config.check("verbose"); gyroFilt.setOrder(gyro_order); @@ -136,7 +136,7 @@ bool ImuFilter::open(yarp::os::Searchable& config) gyroBias.resize(3,0.0); adaptGyroBias=false; - m_period_ms=config.check("period",Value(20)).asInt(); + m_period_ms=config.check("period",Value(20)).asInt32(); if (name.at(0) != '/') name = "/" +name; diff --git a/src/libraries/icubmod/parametricCalibrator/parametricCalibrator.cpp b/src/libraries/icubmod/parametricCalibrator/parametricCalibrator.cpp index 9fb1121183..6bcf702124 100644 --- a/src/libraries/icubmod/parametricCalibrator/parametricCalibrator.cpp +++ b/src/libraries/icubmod/parametricCalibrator/parametricCalibrator.cpp @@ -100,7 +100,7 @@ bool parametricCalibrator::open(yarp::os::Searchable& config) } std::string str; - if (config.findGroup("GENERAL").find("verbose").asInt()) + if (config.findGroup("GENERAL").find("verbose").asInt32()) { str = config.toString().c_str(); yTrace() << deviceName.c_str() << str; @@ -139,12 +139,12 @@ bool parametricCalibrator::open(yarp::os::Searchable& config) int nj = 0; if (p.findGroup("GENERAL").check("joints")) { - nj = p.findGroup("GENERAL").find("joints").asInt(); + nj = p.findGroup("GENERAL").find("joints").asInt32(); } else if (p.findGroup("GENERAL").check("Joints")) { // This is needed to be backward compatibile with old iCubInterface - nj = p.findGroup("GENERAL").find("Joints").asInt(); + nj = p.findGroup("GENERAL").find("Joints").asInt32(); } else { @@ -170,43 +170,43 @@ bool parametricCalibrator::open(yarp::os::Searchable& config) Bottle& xtmp = p.findGroup("CALIBRATION").findGroup("calibration1"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of Calibration1 params " << xtmp.size() << " " << nj; return false; } - for (i = 1; i < xtmp.size(); i++) param1[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) param1[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("CALIBRATION").findGroup("calibration2"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of Calibration2 params"; return false; } - for (i = 1; i < xtmp.size(); i++) param2[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) param2[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("CALIBRATION").findGroup("calibration3"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of Calibration3 params"; return false; } - for (i = 1; i < xtmp.size(); i++) param3[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) param3[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("CALIBRATION").findGroup("calibrationType"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of Calibration3 params"; return false; } - for (i = 1; i < xtmp.size(); i++) type[i - 1] = (unsigned char)xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) type[i - 1] = (unsigned char)xtmp.get(i).asFloat64(); xtmp = p.findGroup("CALIBRATION").findGroup("startupPosition"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of startupPosition params"; return false; } - for (i = 1; i < xtmp.size(); i++) zeroPos[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) zeroPos[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("CALIBRATION").findGroup("startupVelocity"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of startupVelocity params"; return false; } - for (i = 1; i < xtmp.size(); i++) zeroVel[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) zeroVel[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("HOME").findGroup("positionHome"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of PositionHome params"; return false; } - for (i = 1; i < xtmp.size(); i++) homePos[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) homePos[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("HOME").findGroup("velocityHome"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of VelocityHome params"; return false; } - for (i = 1; i < xtmp.size(); i++) homeVel[i - 1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) homeVel[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("CALIBRATION").findGroup("startupMaxPwm"); if (xtmp.size() - 1 != nj) { yError() << deviceName << ": invalid number of startupMaxPwm params"; return false; } - for (i = 1; i < xtmp.size(); i++) maxPWM[i - 1] = xtmp.get(i).asInt(); + for (i = 1; i < xtmp.size(); i++) maxPWM[i - 1] = xtmp.get(i).asInt32(); xtmp = p.findGroup("CALIBRATION").findGroup("startupPosThreshold"); if (xtmp.size()-1!=nj) {yError() << deviceName << ": invalid number of startupPosThreshold params"; return false;} - for (i = 1; i < xtmp.size(); i++) zeroPosThreshold[i-1] = xtmp.get(i).asDouble(); + for (i = 1; i < xtmp.size(); i++) zeroPosThreshold[i-1] = xtmp.get(i).asFloat64(); calibJointsString = p.findGroup("CALIB_ORDER"); int calib_order_size = calibJointsString.size(); @@ -222,7 +222,7 @@ bool parametricCalibrator::open(yarp::os::Searchable& config) for(int j=0; jsize(); j++) { - tmp.push_back(set->get(j).asInt() ); + tmp.push_back(set->get(j).asInt32() ); } joints.push_back(tmp); } @@ -736,7 +736,7 @@ bool parametricCalibrator::checkGoneToZeroThreshold(int j) iPids->getPidOutput(VOCAB_PIDTYPE_POSITION, j, &output); delta = fabs(angj-zeroPos[j]); - yDebug("%s: checkGoneToZeroThreshold: joint: %d curr: %.3f des: %.3f -> delta: %.3f threshold: %.3f output: %.3f mode: %s" ,deviceName.c_str(),j,angj, zeroPos[j],delta, zeroPosThreshold[j], output, yarp::os::Vocab::decode(mode).c_str()); + yDebug("%s: checkGoneToZeroThreshold: joint: %d curr: %.3f des: %.3f -> delta: %.3f threshold: %.3f output: %.3f mode: %s" ,deviceName.c_str(),j,angj, zeroPos[j],delta, zeroPosThreshold[j], output, yarp::os::Vocab32::decode(mode).c_str()); if (delta < zeroPosThreshold[j] && done) { diff --git a/src/libraries/icubmod/parametricCalibratorEth/parametricCalibratorEth.cpp b/src/libraries/icubmod/parametricCalibratorEth/parametricCalibratorEth.cpp index 7d290b184e..ce328eb0c5 100644 --- a/src/libraries/icubmod/parametricCalibratorEth/parametricCalibratorEth.cpp +++ b/src/libraries/icubmod/parametricCalibratorEth/parametricCalibratorEth.cpp @@ -64,7 +64,7 @@ bool parametricCalibratorEth::parseSequenceGroup(yarp::os::Searchable &config, s return false; } - numOfSeq = xtmp.get(1).asInt(); + numOfSeq = xtmp.get(1).asInt32(); // create space in vector of sequences seqList.resize(numOfSeq); @@ -120,8 +120,8 @@ bool parametricCalibratorEth::parseSequenceGroup(yarp::os::Searchable &config, s for (int j = 1; j size(); j++) { - tmp.push_back(set->get(j).asInt() ); + tmp.push_back(set->get(j).asInt32() ); } joints.push_back(tmp); } @@ -941,7 +941,7 @@ bool parametricCalibratorEth::checkGoneToZeroThreshold(int j) delta = fabs(angj-legacyStartupPosition.positions[j]); yDebug("%s: checkGoneToZeroThreshold: joint: %d curr: %.3f des: %.3f -> delta: %.3f threshold: %.3f output: %.3f mode: %s" , \ - deviceName.c_str(), j, angj, legacyStartupPosition.positions[j], delta, startupPosThreshold[j], output, yarp::os::Vocab::decode(mode).c_str()); + deviceName.c_str(), j, angj, legacyStartupPosition.positions[j], delta, startupPosThreshold[j], output, yarp::os::Vocab32::decode(mode).c_str()); if (delta < startupPosThreshold[j] && done) { diff --git a/src/libraries/icubmod/plxCan/PlxCan.cpp b/src/libraries/icubmod/plxCan/PlxCan.cpp index c521544955..0f27a2fec7 100644 --- a/src/libraries/icubmod/plxCan/PlxCan.cpp +++ b/src/libraries/icubmod/plxCan/PlxCan.cpp @@ -106,14 +106,14 @@ bool PlxCan::open(yarp::os::Searchable &par) int txTimeout=0; int rxTimeout=0; - netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); - if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); + netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); + if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); - txTimeout=par.check("CanTxTimeout", Value(0), "timeout on transmission [ms]").asInt(); - if (txTimeout == 0) txTimeout=par.check("canTxTimeout", Value(0), "timeout on transmission [ms]").asInt(); + txTimeout=par.check("CanTxTimeout", Value(0), "timeout on transmission [ms]").asInt32(); + if (txTimeout == 0) txTimeout=par.check("canTxTimeout", Value(0), "timeout on transmission [ms]").asInt32(); - rxTimeout=par.check("CanRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt() ; - if (rxTimeout == 0) rxTimeout=par.check("canRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt() ; + rxTimeout=par.check("CanRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt32() ; + if (rxTimeout == 0) rxTimeout=par.check("canRxTimeout", Value(0), "timeout on receive when calling blocking read [ms]").asInt32() ; int res = plxCanOpen (netId, txQueueSize, rxQueueSize, txTimeout, rxTimeout, handle); if (res != NTCAN_SUCCESS) diff --git a/src/libraries/icubmod/sharedCan/SharedCanBus.cpp b/src/libraries/icubmod/sharedCan/SharedCanBus.cpp index 4b1ef5e14b..8ebf8c2a83 100644 --- a/src/libraries/icubmod/sharedCan/SharedCanBus.cpp +++ b/src/libraries/icubmod/sharedCan/SharedCanBus.cpp @@ -67,7 +67,7 @@ class SharedCanBus : public yarp::os::PeriodicThread if (config.findGroup("CAN").check("sharedCanPeriod")) { - int sharedCanPeriod = config.findGroup("CAN").find("sharedCanPeriod").asInt(); + int sharedCanPeriod = config.findGroup("CAN").find("sharedCanPeriod").asInt32(); int currentCanPeriod = (int)(1000.0 * this->getPeriod()); if (currentCanPeriod != sharedCanPeriod && currentCanPeriod != DEFAULT_THREAD_PERIOD) { @@ -77,7 +77,7 @@ class SharedCanBus : public yarp::os::PeriodicThread if (!config.check("canDeviceNum")) return true; - return mCanDeviceNum==config.find("canDeviceNum").asInt(); + return mCanDeviceNum==config.find("canDeviceNum").asInt32(); } void attachAccessPoint(yarp::dev::CanBusAccessPoint* ap) @@ -263,7 +263,7 @@ class SharedCanBus : public yarp::os::PeriodicThread if (config.check("canRxQueueSize")) { - mBufferSize=config.find("canRxQueueSize").asInt(); + mBufferSize=config.find("canRxQueueSize").asInt32(); } readBufferUnion=theBufferFactory->createBuffer(mBufferSize); @@ -274,7 +274,7 @@ class SharedCanBus : public yarp::os::PeriodicThread if (config.check("canDeviceNum")) { - mCanDeviceNum=config.find("canDeviceNum").asInt(); + mCanDeviceNum=config.find("canDeviceNum").asInt32(); } return started; @@ -360,7 +360,7 @@ class SharedCanBusManager // singleton if (config.findGroup("CAN").check("sharedCanPeriod")) { - int sharedCanPeriod = config.findGroup("CAN").find("sharedCanPeriod").asInt(); + int sharedCanPeriod = config.findGroup("CAN").find("sharedCanPeriod").asInt32(); scb->setPeriod((double)sharedCanPeriod/1000.0); //yDebug("SharedCanBus [%d] using custom thread period = %dms\n", scb->getCanDeviceNum(), sharedCanPeriod);///TOBEREMOVED } diff --git a/src/libraries/icubmod/skinLib/SkinConfigReader.cpp b/src/libraries/icubmod/skinLib/SkinConfigReader.cpp index 8214303949..41af398bc9 100644 --- a/src/libraries/icubmod/skinLib/SkinConfigReader.cpp +++ b/src/libraries/icubmod/skinLib/SkinConfigReader.cpp @@ -56,7 +56,7 @@ void SkinConfigReader::setName(char *name) // // for(int j=1; jnumOfPatches+1; j++) // { -// int id = bPatchList.get(j).asInt(); +// int id = bPatchList.get(j).asInt32(); //#warning VALE aggiungi questo controllo in embObjskin //// if((id!=1) && (id!=2)) //// { @@ -93,7 +93,7 @@ void SkinConfigReader::setName(char *name) // // for(int j=1; jtotalCardsNum++; // skCfg->patchInfoList[i].cardAddrList[j-1] = addr; // } @@ -139,7 +139,7 @@ bool SkinConfigReader::readDefaultBoardCfg(yarp::os::Searchable& config, SkinBoa yError() << "skin " << _name << "doesn't find period in defaultCfgBoard group in xml file"; return false; } - boardCfg->period = xtmp.get(1).asInt(); + boardCfg->period = xtmp.get(1).asInt32(); xtmp = boardCfgDefGroup.findGroup("skinType"); if (xtmp.isNull()) @@ -147,7 +147,7 @@ bool SkinConfigReader::readDefaultBoardCfg(yarp::os::Searchable& config, SkinBoa yError() << "skin " << _name << "doesn't find skinType in defaultCfgBoard group in xml file"; return false; } - boardCfg->skinType= xtmp.get(1).asInt(); + boardCfg->skinType= xtmp.get(1).asInt32(); xtmp = boardCfgDefGroup.findGroup("noLoad"); if (xtmp.isNull()) @@ -155,7 +155,7 @@ bool SkinConfigReader::readDefaultBoardCfg(yarp::os::Searchable& config, SkinBoa yError() << "skin " << _name << "doesn't find noLoad in defaultCfgBoard group in xml file"; return false; } - boardCfg->noLoad= xtmp.get(1).asInt(); + boardCfg->noLoad= xtmp.get(1).asInt32(); xtmp = boardCfgDefGroup.findGroup("diagnostic"); if (xtmp.isNull()) @@ -205,7 +205,7 @@ bool SkinConfigReader::readDefaultTriangleCfg(yarp::os::Searchable& config, Skin yError() << "skin " << _name << "doesn't find shift in defaultCfgTriangle group in xml file"; return false; } - triangCfg->shift = xtmp.get(1).asInt(); + triangCfg->shift = xtmp.get(1).asInt32(); xtmp = triangleCfgDefGroup.findGroup("cdcOffset"); if (xtmp.isNull()) @@ -213,7 +213,7 @@ bool SkinConfigReader::readDefaultTriangleCfg(yarp::os::Searchable& config, Skin yError() << "skin " << _name << "doesn't find cdcOffset in defaultCfgTriangle group in xml file"; return false; } - triangCfg->cdcOffset = xtmp.get(1).asInt(); + triangCfg->cdcOffset = xtmp.get(1).asInt32(); return true; } @@ -242,7 +242,7 @@ bool SkinConfigReader::readSpecialBoardCfg(yarp::os::Searchable& config, Special return(false); } - numOfSets = bNumOfset.get(1).asInt(); + numOfSets = bNumOfset.get(1).asInt32(); if(numOfSets > *numofcfg) { yWarning() << "skin " << _name << "numOfSet is too big. Max is " << *numofcfg; @@ -264,12 +264,12 @@ bool SkinConfigReader::readSpecialBoardCfg(yarp::os::Searchable& config, Special return false; } - boardCfg[j-1].patch = xtmp.get(1).asInt(); - boardCfg[j-1].boardAddrStart = xtmp.get(2).asInt(); - boardCfg[j-1].boardAddrEnd = xtmp.get(3).asInt(); - boardCfg[j-1].cfg.period = xtmp.get(4).asInt(); - boardCfg[j-1].cfg.skinType = xtmp.get(5).asInt(); - boardCfg[j-1].cfg.noLoad = xtmp.get(6).asInt(); + boardCfg[j-1].patch = xtmp.get(1).asInt32(); + boardCfg[j-1].boardAddrStart = xtmp.get(2).asInt32(); + boardCfg[j-1].boardAddrEnd = xtmp.get(3).asInt32(); + boardCfg[j-1].cfg.period = xtmp.get(4).asInt32(); + boardCfg[j-1].cfg.skinType = xtmp.get(5).asInt32(); + boardCfg[j-1].cfg.noLoad = xtmp.get(6).asInt32(); } return true; } @@ -297,7 +297,7 @@ bool SkinConfigReader::readSpecialTriangleCfg(yarp::os::Searchable& config, Spec return(false); } - numOfSets = bNumOfset.get(1).asInt(); + numOfSets = bNumOfset.get(1).asInt32(); if(numOfSets > *numofcfg) { yWarning() << "skin " << _name << "numOfSets for specialCfgTriangles is too big!! Max is " << *numofcfg; @@ -319,13 +319,13 @@ bool SkinConfigReader::readSpecialTriangleCfg(yarp::os::Searchable& config, Spec return false; } - triangleCfg[j-1].patch = xtmp.get(1).asInt(); - triangleCfg[j-1].boardAddr = xtmp.get(2).asInt(); - triangleCfg[j-1].triangleStart = xtmp.get(3).asInt(); - triangleCfg[j-1].triangleEnd = xtmp.get(4).asInt(); - triangleCfg[j-1].cfg.enabled = xtmp.get(5).asInt()==1; - triangleCfg[j-1].cfg.shift = xtmp.get(6).asInt(); - triangleCfg[j-1].cfg.cdcOffset = xtmp.get(7).asInt(); + triangleCfg[j-1].patch = xtmp.get(1).asInt32(); + triangleCfg[j-1].boardAddr = xtmp.get(2).asInt32(); + triangleCfg[j-1].triangleStart = xtmp.get(3).asInt32(); + triangleCfg[j-1].triangleEnd = xtmp.get(4).asInt32(); + triangleCfg[j-1].cfg.enabled = xtmp.get(5).asInt32()==1; + triangleCfg[j-1].cfg.shift = xtmp.get(6).asInt32(); + triangleCfg[j-1].cfg.cdcOffset = xtmp.get(7).asInt32(); // //VALE: solo per debug: diff --git a/src/libraries/icubmod/skinWrapper/skinWrapper.cpp b/src/libraries/icubmod/skinWrapper/skinWrapper.cpp index 7f09b0969b..4aa0df9b10 100644 --- a/src/libraries/icubmod/skinWrapper/skinWrapper.cpp +++ b/src/libraries/icubmod/skinWrapper/skinWrapper.cpp @@ -53,7 +53,7 @@ bool skinWrapper::open(yarp::os::Searchable ¶ms) if (params.check("period")) { - period=params.find("period").asInt(); + period=params.find("period").asInt32(); } else { @@ -62,7 +62,7 @@ bool skinWrapper::open(yarp::os::Searchable ¶ms) } // Read the list of ports - int total_taxels=params.find("total_taxels").asInt(); + int total_taxels=params.find("total_taxels").asInt32(); std::string robotName=params.find("robotName").asString().c_str(); std::string root_name; root_name+="/"; diff --git a/src/libraries/icubmod/socketCan/SocketCan.cpp b/src/libraries/icubmod/socketCan/SocketCan.cpp index b5cb0fc2af..be9103153a 100644 --- a/src/libraries/icubmod/socketCan/SocketCan.cpp +++ b/src/libraries/icubmod/socketCan/SocketCan.cpp @@ -243,20 +243,20 @@ bool SocketCan::open(yarp::os::Searchable &par) int txTimeout=500; int rxTimeout=500; - netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); - if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt(); + netId=par.check("CanDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); + if (netId == -1) netId=par.check("canDeviceNum", Value(-1), "numeric identifier of the can device").asInt32(); - txTimeout=par.check("CanTxTimeout", Value(500), "timeout on transmission [ms]").asInt(); - if (txTimeout == 500) txTimeout=par.check("canTxTimeout", Value(500), "timeout on transmission [ms]").asInt(); + txTimeout=par.check("CanTxTimeout", Value(500), "timeout on transmission [ms]").asInt32(); + if (txTimeout == 500) txTimeout=par.check("canTxTimeout", Value(500), "timeout on transmission [ms]").asInt32(); - rxTimeout=par.check("CanRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt() ; - if (rxTimeout == 500) rxTimeout=par.check("canRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt() ; + rxTimeout=par.check("CanRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt32() ; + if (rxTimeout == 500) rxTimeout=par.check("canRxTimeout", Value(500), "timeout on receive when calling blocking read [ms]").asInt32() ; - canTxQueue=par.check("CanTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt(); - if (canTxQueue == TX_QUEUE_SIZE) canTxQueue=par.check("canTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt(); + canTxQueue=par.check("CanTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt32(); + if (canTxQueue == TX_QUEUE_SIZE) canTxQueue=par.check("canTxQueue", Value(TX_QUEUE_SIZE), "length of tx buffer").asInt32(); - canRxQueue=par.check("CanRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt() ; - if (canRxQueue == RX_QUEUE_SIZE) canRxQueue=par.check("canRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt() ; + canRxQueue=par.check("CanRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt32() ; + if (canRxQueue == RX_QUEUE_SIZE) canRxQueue=par.check("canRxQueue", Value(RX_QUEUE_SIZE), "length of rx buffer").asInt32() ; int so_timestamping_flags = 0; /* Create the socket */ diff --git a/src/libraries/icubmod/xsensmtx/XSensMTx.cpp b/src/libraries/icubmod/xsensmtx/XSensMTx.cpp index 88d800c514..9407efbbca 100644 --- a/src/libraries/icubmod/xsensmtx/XSensMTx.cpp +++ b/src/libraries/icubmod/xsensmtx/XSensMTx.cpp @@ -210,7 +210,7 @@ bool XSensMTx::open(yarp::os::Searchable &config) #ifdef WIN32 par.comPort = config.check ("serial", Value(11), - "numeric identifier of comport").asInt(); + "numeric identifier of comport").asInt32(); #else par.comPortString = config.check("serial",Value("/dev/ttyUSB0"), "device name of comport").asString().c_str(); diff --git a/src/libraries/learningMachine/include/iCub/learningMachine/LSSVMLearner.h b/src/libraries/learningMachine/include/iCub/learningMachine/LSSVMLearner.h index 0f5f2be505..e057378388 100644 --- a/src/libraries/learningMachine/include/iCub/learningMachine/LSSVMLearner.h +++ b/src/libraries/learningMachine/include/iCub/learningMachine/LSSVMLearner.h @@ -82,8 +82,8 @@ class RBFKernel : public Kernel { virtual bool configure(yarp::os::Searchable& config) { bool success = false; // format: set c dbl - if(config.find("gamma").isDouble() || config.find("gamma").isInt()) { - this->setGamma(config.find("gamma").asDouble()); + if(config.find("gamma").isFloat64() || config.find("gamma").isInt32()) { + this->setGamma(config.find("gamma").asFloat64()); success = true; } return success; diff --git a/src/libraries/learningMachine/include/iCub/learningMachine/PortableT.h b/src/libraries/learningMachine/include/iCub/learningMachine/PortableT.h index 31247c7475..a715fb7f74 100644 --- a/src/libraries/learningMachine/include/iCub/learningMachine/PortableT.h +++ b/src/libraries/learningMachine/include/iCub/learningMachine/PortableT.h @@ -107,8 +107,8 @@ class PortableT : public yarp::os::Portable { if(!this->hasWrapped()) { return false; } - connection.appendInt(BOTTLE_TAG_LIST); - connection.appendInt(2); + connection.appendInt32(BOTTLE_TAG_LIST); + connection.appendInt32(2); yarp::os::Bottle nameBottle; nameBottle.addString(this->wrapped->getName().c_str()); nameBottle.write(connection); @@ -132,8 +132,8 @@ class PortableT : public yarp::os::Portable { connection.convertTextMode(); // check headers for the pair (name + actual object serialization) - int header = connection.expectInt(); - int len = connection.expectInt(); + int header = connection.expectInt32(); + int len = connection.expectInt32(); if(header != BOTTLE_TAG_LIST || len != 2) { return false; } diff --git a/src/libraries/learningMachine/include/iCub/learningMachine/Prediction.h b/src/libraries/learningMachine/include/iCub/learningMachine/Prediction.h index fa874f57c5..ed0bc68d67 100644 --- a/src/libraries/learningMachine/include/iCub/learningMachine/Prediction.h +++ b/src/libraries/learningMachine/include/iCub/learningMachine/Prediction.h @@ -165,8 +165,8 @@ class Prediction : public yarp::os::Portable { */ bool write(yarp::os::ConnectionWriter& connection) const { // follows PortablePair implementation - connection.appendInt(BOTTLE_TAG_LIST); - connection.appendInt(2); + connection.appendInt32(BOTTLE_TAG_LIST); + connection.appendInt32(2); bool ok = this->prediction.write(connection); if (ok) { @@ -187,12 +187,12 @@ class Prediction : public yarp::os::Portable { // follows PortablePair implementation connection.convertTextMode(); - int header = connection.expectInt(); + int header = connection.expectInt32(); if(header != BOTTLE_TAG_LIST) { return false; } - int len = connection.expectInt(); + int len = connection.expectInt32(); if(len != 2) { return false; } diff --git a/src/libraries/learningMachine/src/DatasetRecorder.cpp b/src/libraries/learningMachine/src/DatasetRecorder.cpp index 9c99f63737..1b4e4de6fc 100644 --- a/src/libraries/learningMachine/src/DatasetRecorder.cpp +++ b/src/libraries/learningMachine/src/DatasetRecorder.cpp @@ -76,11 +76,11 @@ std::string DatasetRecorder::getInfo() { void DatasetRecorder::writeBottle(yarp::os::Bottle& bot) const { bot.addString(this->filename.c_str()); - bot.addInt(this->precision); + bot.addInt32(this->precision); } void DatasetRecorder::readBottle(yarp::os::Bottle& bot) { - this->precision = bot.pop().asInt(); + this->precision = bot.pop().asInt32(); this->filename = bot.pop().asString().c_str(); } @@ -103,8 +103,8 @@ bool DatasetRecorder::configure(yarp::os::Searchable& config) { } // set the precision - if(config.find("precision").isInt()) { - this->precision = config.find("precision").asInt(); + if(config.find("precision").isInt32()) { + this->precision = config.find("precision").asInt32(); success = true; } diff --git a/src/libraries/learningMachine/src/FixedRangeScaler.cpp b/src/libraries/learningMachine/src/FixedRangeScaler.cpp index 39683c6a2a..d13881ece6 100644 --- a/src/libraries/learningMachine/src/FixedRangeScaler.cpp +++ b/src/libraries/learningMachine/src/FixedRangeScaler.cpp @@ -71,45 +71,45 @@ bool FixedRangeScaler::configure(yarp::os::Searchable& config) { bool success = this->IScaler::configure(config); // set the expected incoming lower bound (double) - if(config.find("lowerin").isDouble() || config.find("lowerin").isInt()) { - this->setLowerBoundIn(config.find("lowerin").asDouble()); + if(config.find("lowerin").isFloat64() || config.find("lowerin").isInt32()) { + this->setLowerBoundIn(config.find("lowerin").asFloat64()); success = true; } // set the expected incoming upper bound (double) - if(config.find("upperin").isDouble() || config.find("upperin").isInt()) { - this->setUpperBoundIn(config.find("upperin").asDouble()); + if(config.find("upperin").isFloat64() || config.find("upperin").isInt32()) { + this->setUpperBoundIn(config.find("upperin").asFloat64()); success = true; } // set the desired outgoing lower bound (double) - if(config.find("lowerout").isDouble() || config.find("lowerout").isInt()) { - this->setLowerBoundOut(config.find("lowerout").asDouble()); + if(config.find("lowerout").isFloat64() || config.find("lowerout").isInt32()) { + this->setLowerBoundOut(config.find("lowerout").asFloat64()); success = true; } // set the desired outgoing bound (double) - if(config.find("upperout").isDouble() || config.find("upperout").isInt()) { - this->setUpperBoundOut(config.find("upperout").asDouble()); + if(config.find("upperout").isFloat64() || config.find("upperout").isInt32()) { + this->setUpperBoundOut(config.find("upperout").asFloat64()); success = true; } if(!config.findGroup("in").isNull()) { yarp::os::Bottle& bot = config.findGroup("in"); - if(bot.size() == 3 && (bot.get(1).isInt() || bot.get(1).isDouble()) && - (bot.get(2).isInt() || bot.get(2).isDouble())) { + if(bot.size() == 3 && (bot.get(1).isInt32() || bot.get(1).isFloat64()) && + (bot.get(2).isInt32() || bot.get(2).isFloat64())) { - this->setLowerBoundIn(bot.get(1).asDouble()); - this->setUpperBoundIn(bot.get(2).asDouble()); + this->setLowerBoundIn(bot.get(1).asFloat64()); + this->setUpperBoundIn(bot.get(2).asFloat64()); success = true; } } if(!config.findGroup("out").isNull()) { yarp::os::Bottle& bot = config.findGroup("out"); - if(bot.size() == 3 && (bot.get(1).isInt() || bot.get(1).isDouble()) && - (bot.get(2).isInt() || bot.get(2).isDouble())) { + if(bot.size() == 3 && (bot.get(1).isInt32() || bot.get(1).isFloat64()) && + (bot.get(2).isInt32() || bot.get(2).isFloat64())) { - this->setLowerBoundOut(bot.get(1).asDouble()); - this->setUpperBoundOut(bot.get(2).asDouble()); + this->setLowerBoundOut(bot.get(1).asFloat64()); + this->setUpperBoundOut(bot.get(2).asFloat64()); success = true; } } diff --git a/src/libraries/learningMachine/src/IFixedSizeLearner.cpp b/src/libraries/learningMachine/src/IFixedSizeLearner.cpp index 15e8955913..dbd1e9c44c 100644 --- a/src/libraries/learningMachine/src/IFixedSizeLearner.cpp +++ b/src/libraries/learningMachine/src/IFixedSizeLearner.cpp @@ -35,13 +35,13 @@ void IFixedSizeLearner::train() { bool IFixedSizeLearner::configure(yarp::os::Searchable& config) { bool success = false; // set the domain size (int) - if(config.find("dom").isInt()) { - this->setDomainSize(config.find("dom").asInt()); + if(config.find("dom").isInt32()) { + this->setDomainSize(config.find("dom").asInt32()); success = true; } // set the codomain size (int) - if(config.find("cod").isInt()) { - this->setCoDomainSize(config.find("cod").asInt()); + if(config.find("cod").isInt32()) { + this->setCoDomainSize(config.find("cod").asInt32()); success = true; } @@ -66,13 +66,13 @@ void IFixedSizeLearner::validateDomainSizes(const yarp::sig::Vector& input, cons } void IFixedSizeLearner::writeBottle(yarp::os::Bottle& bot) const { - bot.addInt(this->getDomainSize()); - bot.addInt(this->getCoDomainSize()); + bot.addInt32(this->getDomainSize()); + bot.addInt32(this->getCoDomainSize()); } void IFixedSizeLearner::readBottle(yarp::os::Bottle& bot) { - this->setCoDomainSize(bot.pop().asInt()); - this->setDomainSize(bot.pop().asInt()); + this->setCoDomainSize(bot.pop().asInt32()); + this->setDomainSize(bot.pop().asInt32()); } std::string IFixedSizeLearner::getInfo() { diff --git a/src/libraries/learningMachine/src/IFixedSizeTransformer.cpp b/src/libraries/learningMachine/src/IFixedSizeTransformer.cpp index 967d8e18dc..793a494974 100644 --- a/src/libraries/learningMachine/src/IFixedSizeTransformer.cpp +++ b/src/libraries/learningMachine/src/IFixedSizeTransformer.cpp @@ -43,13 +43,13 @@ void IFixedSizeTransformer::validateDomainSizes(const yarp::sig::Vector& input, bool IFixedSizeTransformer::configure(yarp::os::Searchable& config) { bool success = false; // set the domain size (int) - if(config.find("dom").isInt()) { - this->setDomainSize(config.find("dom").asInt()); + if(config.find("dom").isInt32()) { + this->setDomainSize(config.find("dom").asInt32()); success = true; } // set the codomain size (int) - if(config.find("cod").isInt()) { - this->setCoDomainSize(config.find("cod").asInt()); + if(config.find("cod").isInt32()) { + this->setCoDomainSize(config.find("cod").asInt32()); success = true; } @@ -57,13 +57,13 @@ bool IFixedSizeTransformer::configure(yarp::os::Searchable& config) { } void IFixedSizeTransformer::writeBottle(yarp::os::Bottle& bot) const { - bot.addInt(this->getDomainSize()); - bot.addInt(this->getCoDomainSize()); + bot.addInt32(this->getDomainSize()); + bot.addInt32(this->getCoDomainSize()); } void IFixedSizeTransformer::readBottle(yarp::os::Bottle& bot) { - this->setCoDomainSize(bot.pop().asInt()); - this->setDomainSize(bot.pop().asInt()); + this->setCoDomainSize(bot.pop().asInt32()); + this->setDomainSize(bot.pop().asInt32()); } diff --git a/src/libraries/learningMachine/src/IScaler.cpp b/src/libraries/learningMachine/src/IScaler.cpp index f10101ac68..7bc8a7bfe9 100644 --- a/src/libraries/learningMachine/src/IScaler.cpp +++ b/src/libraries/learningMachine/src/IScaler.cpp @@ -59,15 +59,15 @@ bool IScaler::fromString(const std::string& str) { } void IScaler::writeBottle(yarp::os::Bottle& bot) { - bot.addDouble(this->offset); - bot.addDouble(this->scale); - bot.addInt((this->updateEnabled ? 1 : 0)); + bot.addFloat64(this->offset); + bot.addFloat64(this->scale); + bot.addInt32((this->updateEnabled ? 1 : 0)); } void IScaler::readBottle(yarp::os::Bottle& bot) { - this->updateEnabled = (bot.pop().asInt() == 1); - this->scale = bot.pop().asDouble(); - this->offset = bot.pop().asDouble(); + this->updateEnabled = (bot.pop().asInt32() == 1); + this->scale = bot.pop().asFloat64(); + this->offset = bot.pop().asFloat64(); } bool IScaler::configure(yarp::os::Searchable& config) { diff --git a/src/libraries/learningMachine/src/LSSVMLearner.cpp b/src/libraries/learningMachine/src/LSSVMLearner.cpp index 518cb6db7c..5f29c75c9d 100644 --- a/src/libraries/learningMachine/src/LSSVMLearner.cpp +++ b/src/libraries/learningMachine/src/LSSVMLearner.cpp @@ -198,18 +198,18 @@ void LSSVMLearner::writeBottle(yarp::os::Bottle& bot) { // write inputs for(unsigned int i = 0; i < this->inputs.size(); i++) { for(unsigned int d = 0; d < this->getDomainSize(); d++) { - bot.addDouble(this->inputs[i](d)); + bot.addFloat64(this->inputs[i](d)); } } - bot.addInt(this->inputs.size()); + bot.addInt32(this->inputs.size()); // write outputs for(unsigned int i = 0; i < this->outputs.size(); i++) { for(unsigned int d = 0; d < this->getCoDomainSize(); d++) { - bot.addDouble(this->outputs[i](d)); + bot.addFloat64(this->outputs[i](d)); } } - bot.addInt(this->outputs.size()); + bot.addInt32(this->outputs.size()); // make sure to call the superclass's method this->IFixedSizeLearner::writeBottle(bot); @@ -220,20 +220,20 @@ void LSSVMLearner::readBottle(yarp::os::Bottle& bot) { this->IFixedSizeLearner::readBottle(bot); // read outputs - this->outputs.resize(bot.pop().asInt()); + this->outputs.resize(bot.pop().asInt32()); for(int i = this->outputs.size() - 1; i >= 0; i--) { this->outputs[i].resize(this->getCoDomainSize()); for(int d = this->getCoDomainSize() - 1; d >= 0; d--) { - this->outputs[i](d) = bot.pop().asDouble(); + this->outputs[i](d) = bot.pop().asFloat64(); } } // read inputs - this->inputs.resize(bot.pop().asInt()); + this->inputs.resize(bot.pop().asInt32()); for(int i = this->inputs.size() - 1; i >= 0; i--) { this->inputs[i].resize(this->getDomainSize()); for(int d = this->getDomainSize() - 1; d >= 0; d--) { - this->inputs[i](d) = bot.pop().asDouble(); + this->inputs[i](d) = bot.pop().asFloat64(); } } @@ -257,10 +257,10 @@ bool LSSVMLearner::configure(yarp::os::Searchable& config) { bool success = this->IFixedSizeLearner::configure(config); // format: set c dbl - if(config.find("c").isDouble() || config.find("c").isInt()) { - double val = config.find("c").asDouble(); + if(config.find("c").isFloat64() || config.find("c").isInt32()) { + double val = config.find("c").asFloat64(); if(val > 0) { - this->setC(config.find("c").asDouble()); + this->setC(config.find("c").asFloat64()); success = true; } } diff --git a/src/libraries/learningMachine/src/LinearGPRLearner.cpp b/src/libraries/learningMachine/src/LinearGPRLearner.cpp index 0cba17b1a2..c4e1c9bf63 100644 --- a/src/libraries/learningMachine/src/LinearGPRLearner.cpp +++ b/src/libraries/learningMachine/src/LinearGPRLearner.cpp @@ -171,8 +171,8 @@ bool LinearGPRLearner::configure(yarp::os::Searchable& config) { bool success = this->IFixedSizeLearner::configure(config); // format: set sigma val - if(config.find("sigma").isDouble() || config.find("sigma").isInt()) { - this->setSigma(config.find("sigma").asDouble()); + if(config.find("sigma").isFloat64() || config.find("sigma").isInt32()) { + this->setSigma(config.find("sigma").asFloat64()); success = true; } diff --git a/src/libraries/learningMachine/src/LinearScaler.cpp b/src/libraries/learningMachine/src/LinearScaler.cpp index 97033720bb..2b9b9d3c97 100644 --- a/src/libraries/learningMachine/src/LinearScaler.cpp +++ b/src/libraries/learningMachine/src/LinearScaler.cpp @@ -51,13 +51,13 @@ bool LinearScaler::configure(yarp::os::Searchable& config) { bool success = this->IScaler::configure(config); // set the desired scale (double) - if(config.find("scale").isDouble() || config.find("scale").isInt()) { - this->setScale(1. / config.find("scale").asDouble()); + if(config.find("scale").isFloat64() || config.find("scale").isInt32()) { + this->setScale(1. / config.find("scale").asFloat64()); success = true; } // set the desired offset (double) - if(config.find("offset").isDouble() || config.find("offset").isInt()) { - this->setOffset(config.find("offset").asDouble()); + if(config.find("offset").isFloat64() || config.find("offset").isInt32()) { + this->setOffset(config.find("offset").asFloat64()); success = true; } diff --git a/src/libraries/learningMachine/src/Normalizer.cpp b/src/libraries/learningMachine/src/Normalizer.cpp index ed6423f8ef..ff465d992a 100644 --- a/src/libraries/learningMachine/src/Normalizer.cpp +++ b/src/libraries/learningMachine/src/Normalizer.cpp @@ -76,13 +76,13 @@ bool Normalizer::configure(yarp::os::Searchable& config) { bool success = this->IScaler::configure(config); // set the desired lower bound (double) - if(config.find("lower").isDouble() || config.find("lower").isInt()) { - this->setLowerBound(config.find("lower").asDouble()); + if(config.find("lower").isFloat64() || config.find("lower").isInt32()) { + this->setLowerBound(config.find("lower").asFloat64()); success = true; } // set the desired upper bound (double) - if(config.find("upper").isDouble() || config.find("upper").isInt()) { - this->setUpperBound(config.find("upper").asDouble()); + if(config.find("upper").isFloat64() || config.find("upper").isInt32()) { + this->setUpperBound(config.find("upper").asFloat64()); success = true; } diff --git a/src/libraries/learningMachine/src/Prediction.cpp b/src/libraries/learningMachine/src/Prediction.cpp index 2482f9d0a1..86dd411a0f 100644 --- a/src/libraries/learningMachine/src/Prediction.cpp +++ b/src/libraries/learningMachine/src/Prediction.cpp @@ -41,8 +41,8 @@ std::string Prediction::toString() { bool Prediction::write(yarp::os::ConnectionWriter& connection) { // follows PortablePair implementation - connection.appendInt(BOTTLE_TAG_LIST); - connection.appendInt(2); + connection.appendInt32(BOTTLE_TAG_LIST); + connection.appendInt32(2); bool ok = this->prediction.write(connection); if (ok) { @@ -60,12 +60,12 @@ bool Prediction::read(yarp::os::ConnectionReader& connection) { // follows PortablePair implementation connection.convertTextMode(); - int header = connection.expectInt(); + int header = connection.expectInt32(); if(header != BOTTLE_TAG_LIST) { return false; } - int len = connection.expectInt(); + int len = connection.expectInt32(); if(len != 2) { return false; } diff --git a/src/libraries/learningMachine/src/RLSLearner.cpp b/src/libraries/learningMachine/src/RLSLearner.cpp index 43c314ba33..a4d3da19e0 100644 --- a/src/libraries/learningMachine/src/RLSLearner.cpp +++ b/src/libraries/learningMachine/src/RLSLearner.cpp @@ -161,8 +161,8 @@ bool RLSLearner::configure(yarp::os::Searchable& config) { bool success = this->IFixedSizeLearner::configure(config); // format: set lambda val - if(config.find("lambda").isDouble() || config.find("lambda").isInt()) { - this->setLambda(config.find("lambda").asDouble()); + if(config.find("lambda").isFloat64() || config.find("lambda").isInt32()) { + this->setLambda(config.find("lambda").asFloat64()); success = true; } diff --git a/src/libraries/learningMachine/src/RandomFeature.cpp b/src/libraries/learningMachine/src/RandomFeature.cpp index 9e4b5d64ef..e41f94d81e 100644 --- a/src/libraries/learningMachine/src/RandomFeature.cpp +++ b/src/libraries/learningMachine/src/RandomFeature.cpp @@ -112,8 +112,8 @@ bool RandomFeature::configure(yarp::os::Searchable &config) { bool success = this->IFixedSizeTransformer::configure(config); // format: set gamma val - if(config.find("gamma").isDouble() || config.find("gamma").isInt()) { - this->setGamma(config.find("gamma").asDouble()); + if(config.find("gamma").isFloat64() || config.find("gamma").isInt32()) { + this->setGamma(config.find("gamma").asFloat64()); success = true; } return success; diff --git a/src/libraries/learningMachine/src/ScaleTransformer.cpp b/src/libraries/learningMachine/src/ScaleTransformer.cpp index 8134c73af9..4c426f9d6a 100644 --- a/src/libraries/learningMachine/src/ScaleTransformer.cpp +++ b/src/libraries/learningMachine/src/ScaleTransformer.cpp @@ -187,9 +187,9 @@ bool ScaleTransformer::configure(yarp::os::Searchable &config) { if(!config.findGroup("type").isNull()) { //success = true; yarp::os::Bottle list = config.findGroup("type").tail(); - if(list.get(0).isInt() && list.get(1).isString()) { + if(list.get(0).isInt32() && list.get(1).isString()) { // shift index, since internal numbering in vector starts at 0, the user starts at 1 - this->setAt(list.get(0).asInt() - 1, list.get(1).asString().c_str()); + this->setAt(list.get(0).asInt32() - 1, list.get(1).asString().c_str()); success = true; } else if(list.get(0).asString() == "all" && list.get(1).isString()) { this->setAll(list.get(1).asString().c_str()); @@ -202,9 +202,9 @@ bool ScaleTransformer::configure(yarp::os::Searchable &config) { yarp::os::Bottle property; yarp::os::Bottle list = config.findGroup("config").tail(); property.addList() = list.tail(); - if(list.get(0).isInt()) { + if(list.get(0).isInt32()) { // format: set config idx key val - int i = list.get(0).asInt() - 1; + int i = list.get(0).asInt32() - 1; success = this->getAt(i)->configure(property); } else if(list.get(0).asString() == "all") { // format: set config all key val diff --git a/src/libraries/learningMachine/src/Serialization.cpp b/src/libraries/learningMachine/src/Serialization.cpp index 4095af6815..d6463ccc29 100644 --- a/src/libraries/learningMachine/src/Serialization.cpp +++ b/src/libraries/learningMachine/src/Serialization.cpp @@ -23,17 +23,17 @@ namespace learningmachine { namespace serialization { yarp::os::Bottle& operator<<(yarp::os::Bottle &out, int val) { - out.addInt(val); + out.addInt32(val); return out; } yarp::os::Bottle& operator<<(yarp::os::Bottle &out, size_t val) { - out.addInt(val); + out.addInt32(val); return out; } yarp::os::Bottle& operator<<(yarp::os::Bottle &out, double val) { - out.addDouble(val); + out.addFloat64(val); return out; } @@ -56,12 +56,12 @@ yarp::os::Bottle& operator<<(yarp::os::Bottle &out, const yarp::sig::Matrix& M) } yarp::os::Bottle& operator>>(yarp::os::Bottle &in, int& val) { - val = in.pop().asInt(); + val = in.pop().asInt32(); return in; } yarp::os::Bottle& operator>>(yarp::os::Bottle &in, double& val) { - val = in.pop().asDouble(); + val = in.pop().asFloat64(); return in; } diff --git a/src/libraries/learningMachine/src/SparseSpectrumFeature.cpp b/src/libraries/learningMachine/src/SparseSpectrumFeature.cpp index b5e0208c2e..b6d188b295 100644 --- a/src/libraries/learningMachine/src/SparseSpectrumFeature.cpp +++ b/src/libraries/learningMachine/src/SparseSpectrumFeature.cpp @@ -144,15 +144,15 @@ bool SparseSpectrumFeature::configure(yarp::os::Searchable &config) { bool success = this->IFixedSizeTransformer::configure(config); // format: set sigma val - if(config.find("sigma").isDouble() || config.find("sigma").isInt()) { - this->setSigma(config.find("sigma").asDouble()); + if(config.find("sigma").isFloat64() || config.find("sigma").isInt32()) { + this->setSigma(config.find("sigma").asFloat64()); success = true; } // format: set ell val | set ell (val ... val) - if(config.find("ell").isDouble() || config.find("ell").isInt()) { + if(config.find("ell").isFloat64() || config.find("ell").isInt32()) { yarp::sig::Vector ls = yarp::sig::Vector(this->getDomainSize()); - ls = config.find("ell").asDouble(); + ls = config.find("ell").asFloat64(); this->setEll(ls); success = true; } else if(config.find("ell").isList()) { @@ -160,8 +160,8 @@ bool SparseSpectrumFeature::configure(yarp::os::Searchable &config) { assert(b != (yarp::os::Bottle*) 0x0); yarp::sig::Vector ls(0); for(int i = 0; i < b->size(); i++) { - if(b->get(i).isDouble() || b->get(i).isInt()) { - ls.push_back(b->get(i).asDouble()); + if(b->get(i).isFloat64() || b->get(i).isInt32()) { + ls.push_back(b->get(i).asFloat64()); } } this->setEll(ls); diff --git a/src/libraries/learningMachine/src/Standardizer.cpp b/src/libraries/learningMachine/src/Standardizer.cpp index 2bbd42ff2c..77324c634f 100644 --- a/src/libraries/learningMachine/src/Standardizer.cpp +++ b/src/libraries/learningMachine/src/Standardizer.cpp @@ -81,13 +81,13 @@ bool Standardizer::configure(yarp::os::Searchable& config) { bool success = this->IScaler::configure(config); // set the desired output mean (double) - if(config.find("mean").isDouble() || config.find("mean").isInt()) { - this->setDesiredMean(config.find("mean").asDouble()); + if(config.find("mean").isFloat64() || config.find("mean").isInt32()) { + this->setDesiredMean(config.find("mean").asFloat64()); success = true; } // set the desired output standard deviation (double) - if(config.find("std").isDouble() || config.find("std").isInt()) { - this->setDesiredStd(config.find("std").asDouble()); + if(config.find("std").isFloat64() || config.find("std").isInt32()) { + this->setDesiredStd(config.find("std").asFloat64()); success = true; } diff --git a/src/libraries/optimization/src/affinity.cpp b/src/libraries/optimization/src/affinity.cpp index f29a260c3b..b571c6905c 100644 --- a/src/libraries/optimization/src/affinity.cpp +++ b/src/libraries/optimization/src/affinity.cpp @@ -328,10 +328,10 @@ bool AffinityWithMatchedPoints::setInitialGuess(const Matrix &A) bool AffinityWithMatchedPoints::setCalibrationOptions(const Property &options) { if (options.check("max_iter")) - max_iter=options.find("max_iter").asInt(); + max_iter=options.find("max_iter").asInt32(); if (options.check("tol")) - tol=options.find("tol").asDouble(); + tol=options.find("tol").asFloat64(); return true; } diff --git a/src/libraries/optimization/src/calibReference.cpp b/src/libraries/optimization/src/calibReference.cpp index b92a9920e8..af49ec10a0 100644 --- a/src/libraries/optimization/src/calibReference.cpp +++ b/src/libraries/optimization/src/calibReference.cpp @@ -640,10 +640,10 @@ bool CalibReferenceWithMatchedPoints::setScalingInitialGuess(const double s) bool CalibReferenceWithMatchedPoints::setCalibrationOptions(const Property &options) { if (options.check("max_iter")) - max_iter=options.find("max_iter").asInt(); + max_iter=options.find("max_iter").asInt32(); if (options.check("tol")) - tol=options.find("tol").asDouble(); + tol=options.find("tol").asFloat64(); return true; } diff --git a/src/libraries/optimization/src/neuralNetworks.cpp b/src/libraries/optimization/src/neuralNetworks.cpp index f7f54f2447..851c0191fd 100644 --- a/src/libraries/optimization/src/neuralNetworks.cpp +++ b/src/libraries/optimization/src/neuralNetworks.cpp @@ -68,8 +68,8 @@ class ff2LayNNTrainNLP : public Ipopt::TNLP { if (b->size()>=2) { - min=b->get(0).asDouble(); - max=b->get(1).asDouble(); + min=b->get(0).asFloat64(); + max=b->get(1).asFloat64(); return true; } } diff --git a/src/libraries/perceptiveModels/src/ports.cpp b/src/libraries/perceptiveModels/src/ports.cpp index f31d2dcc47..5c272b136d 100644 --- a/src/libraries/perceptiveModels/src/ports.cpp +++ b/src/libraries/perceptiveModels/src/ports.cpp @@ -44,7 +44,7 @@ Value iCub::perception::Port::getValue(const int index) Value ret; if ((index>=0) && (indexsource=source; name=options.find("name").asString(); - size=options.find("size").asInt(); - index=options.find("index").asInt(); + size=options.find("size").asInt32(); + index=options.find("index").asInt32(); return configured=true; } @@ -77,7 +77,7 @@ bool SensorPort::configure(void *source, const Property &options) this->source=source; name=options.find("name").asString(); - index=options.find("index").asInt(); + index=options.find("index").asInt32(); return configured=true; } diff --git a/src/libraries/perceptiveModels/src/springyFingers.cpp b/src/libraries/perceptiveModels/src/springyFingers.cpp index 4bd81e8e08..c4f294470f 100644 --- a/src/libraries/perceptiveModels/src/springyFingers.cpp +++ b/src/libraries/perceptiveModels/src/springyFingers.cpp @@ -75,8 +75,8 @@ bool SpringyFinger::fromProperty(const Property &options) else return false; - calibratingVelocity=options.check("calib_vel",Value(defaultCalibVel)).asDouble(); - outputGain=options.check("output_gain",Value(1.0)).asDouble(); + calibratingVelocity=options.check("calib_vel",Value(defaultCalibVel)).asFloat64(); + outputGain=options.check("output_gain",Value(1.0)).asFloat64(); calibrated=(options.check("calibrated",Value("false")).asString()=="true"); if (options.check("scaler")) @@ -147,16 +147,16 @@ bool SpringyFinger::getSensorsData(Value &data) const Out_1->second->getOutput(val_out[1]); Vector in(lssvm.getDomainSize()); - in[0]=val_in.asDouble(); + in[0]=val_in.asFloat64(); Vector out(lssvm.getCoDomainSize()); - out[0]=val_out[0].asDouble(); - out[1]=val_out[1].asDouble(); + out[0]=val_out[0].asFloat64(); + out[1]=val_out[1].asFloat64(); if (lssvm.getCoDomainSize()>2) { Out_2->second->getOutput(val_out[2]); - out[2]=val_out[2].asDouble(); + out[2]=val_out[2].asFloat64(); } Property prop; @@ -189,14 +189,14 @@ bool SpringyFinger::extractSensorsData(Vector &in, Vector &out) const { in.resize(b2->size()); for (size_t i=0; iget(i).asDouble(); + in[i]=b2->get(i).asFloat64(); } if (Bottle *b2=b1->find("out").asList()) { out.resize(b2->size()); for (size_t i=0; iget(i).asDouble(); + out[i]=b2->get(i).asFloat64(); ret=true; } @@ -281,7 +281,7 @@ bool SpringyFingersModel::fromProperty(const Property &options) type=options.find("type").asString(); robot=options.check("robot",Value("icub")).asString(); carrier=options.check("carrier",Value("udp")).asString(); - verbosity=options.check("verbosity",Value(0)).asInt(); + verbosity=options.check("verbosity",Value(0)).asInt32(); string part_motor=string(type+"_arm"); string part_analog=string(type+"_hand"); @@ -697,11 +697,11 @@ bool SpringyFingersModel::getOutput(Value &out) const fingers[4].getOutput(val[4]); Bottle bOut; Bottle &ins=bOut.addList(); - ins.addDouble(val[0].asDouble()); - ins.addDouble(val[1].asDouble()); - ins.addDouble(val[2].asDouble()); - ins.addDouble(val[3].asDouble()); - ins.addDouble(val[4].asDouble()); + ins.addFloat64(val[0].asFloat64()); + ins.addFloat64(val[1].asFloat64()); + ins.addFloat64(val[2].asFloat64()); + ins.addFloat64(val[3].asFloat64()); + ins.addFloat64(val[4].asFloat64()); out=bOut.get(0); return true; diff --git a/src/libraries/perceptiveModels/src/tactileFingers.cpp b/src/libraries/perceptiveModels/src/tactileFingers.cpp index 95a9a91163..3ed8be375b 100644 --- a/src/libraries/perceptiveModels/src/tactileFingers.cpp +++ b/src/libraries/perceptiveModels/src/tactileFingers.cpp @@ -42,7 +42,7 @@ bool TactileFinger::fromProperty(const Property &options) name=options.find("name").asString(); directLogic=(options.check("logic",Value("direct")).asString()=="direct"); - outputGain=options.check("output_gain",Value(1.0)).asDouble(); + outputGain=options.check("output_gain",Value(1.0)).asFloat64(); if ((name=="thumb") || (name=="index") || (name=="middle") || (name=="ring") || (name=="little")) @@ -106,7 +106,7 @@ bool TactileFinger::getSensorsData(Value &data) const return false; Value val_in; In->second->getOutput(val_in); - in[j]=val_in.asDouble(); + in[j]=val_in.asFloat64(); } Property prop; @@ -136,7 +136,7 @@ bool TactileFinger::extractSensorsData(Vector &in) const { in.resize(b2->size()); for (size_t i=0; iget(i).asDouble(); + in[i]=b2->get(i).asFloat64(); ret=true; } @@ -189,7 +189,7 @@ bool TactileFingersModel::fromProperty(const Property &options) robot=options.check("robot",Value("icub")).asString(); carrier=options.check("carrier",Value("udp")).asString(); compensation=(options.check("compensation",Value("false")).asString()=="true"); - verbosity=options.check("verbosity",Value(0)).asInt(); + verbosity=options.check("verbosity",Value(0)).asInt32(); port->open("/"+name+"/"+type+"_hand:i"); string skinPortName("/"+robot+"/skin/"+type+"_hand"); @@ -375,11 +375,11 @@ bool TactileFingersModel::getOutput(Value &out) const fingers[4].getOutput(val[4]); Bottle bOut; Bottle &ins=bOut.addList(); - ins.addDouble(val[0].asDouble()); - ins.addDouble(val[1].asDouble()); - ins.addDouble(val[2].asDouble()); - ins.addDouble(val[3].asDouble()); - ins.addDouble(val[4].asDouble()); + ins.addFloat64(val[0].asFloat64()); + ins.addFloat64(val[1].asFloat64()); + ins.addFloat64(val[2].asFloat64()); + ins.addFloat64(val[3].asFloat64()); + ins.addFloat64(val[4].asFloat64()); out=bOut.get(0); return true; diff --git a/src/libraries/skinDynLib/src/common.cpp b/src/libraries/skinDynLib/src/common.cpp index 5982b22564..dd131f11f2 100644 --- a/src/libraries/skinDynLib/src/common.cpp +++ b/src/libraries/skinDynLib/src/common.cpp @@ -92,7 +92,7 @@ yarp::sig::Vector iCub::skinDynLib::vectorFromBottle(const yarp::os::Bottle b, i for (int i = 0; i < size; i++) { - v[i] = b.get(in).asDouble(); + v[i] = b.get(in).asFloat64(); in++; } return v; @@ -102,7 +102,7 @@ void iCub::skinDynLib::vectorIntoBottle(const yarp::sig::Vector v, yarp::os::Bot { for (unsigned int i = 0; i < v.size(); i++) { - b.addDouble(v[i]); + b.addFloat64(v[i]); } } @@ -115,7 +115,7 @@ yarp::sig::Matrix iCub::skinDynLib::matrixFromBottle(const yarp::os::Bottle b, i { for (int j = 0; jwrite(connection)) diff --git a/src/libraries/skinDynLib/src/skinContact.cpp b/src/libraries/skinDynLib/src/skinContact.cpp index 50d2ddecdd..dcad30bea0 100644 --- a/src/libraries/skinDynLib/src/skinContact.cpp +++ b/src/libraries/skinDynLib/src/skinContact.cpp @@ -108,42 +108,42 @@ bool skinContact::write(ConnectionWriter& connection) const // - a list of N int, i.e. the active taxel ids // - a double, i.e. the pressure - connection.appendInt(BOTTLE_TAG_LIST); - connection.appendInt(8); + connection.appendInt32(BOTTLE_TAG_LIST); + connection.appendInt32(8); // list of 4 int, i.e. contactId, bodyPart, linkNumber, skinPart - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_INT); - connection.appendInt(4); - connection.appendInt(contactId); - connection.appendInt(bodyPart); // left_arm, right_arm, ... - connection.appendInt(linkNumber); - connection.appendInt(skinPart); + connection.appendInt32(BOTTLE_TAG_LIST + BOTTLE_TAG_INT32); + connection.appendInt32(4); + connection.appendInt32(contactId); + connection.appendInt32(bodyPart); // left_arm, right_arm, ... + connection.appendInt32(linkNumber); + connection.appendInt32(skinPart); // list of 3 double, i.e. the CoP - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_DOUBLE); - connection.appendInt(3); - for(int i=0;i<3;i++) connection.appendDouble(CoP[i]); + connection.appendInt32(BOTTLE_TAG_LIST + BOTTLE_TAG_FLOAT64); + connection.appendInt32(3); + for(int i=0;i<3;i++) connection.appendFloat64(CoP[i]); // list of 3 double, i.e. the force - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_DOUBLE); - connection.appendInt(3); - for(int i=0;i<3;i++) connection.appendDouble(F[i]); + connection.appendInt32(BOTTLE_TAG_LIST + BOTTLE_TAG_FLOAT64); + connection.appendInt32(3); + for(int i=0;i<3;i++) connection.appendFloat64(F[i]); // list of 3 double, i.e. the moment - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_DOUBLE); - connection.appendInt(3); - for(int i=0;i<3;i++) connection.appendDouble(Mu[i]); + connection.appendInt32(BOTTLE_TAG_LIST + BOTTLE_TAG_FLOAT64); + connection.appendInt32(3); + for(int i=0;i<3;i++) connection.appendFloat64(Mu[i]); // - a list of 3 double, i.e. the geometric center - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_DOUBLE); - connection.appendInt(3); - for(int i=0;i<3;i++) connection.appendDouble(geoCenter[i]); + connection.appendInt32(BOTTLE_TAG_LIST + BOTTLE_TAG_FLOAT64); + connection.appendInt32(3); + for(int i=0;i<3;i++) connection.appendFloat64(geoCenter[i]); // - a list of 3 double, i.e. the normal direction - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_DOUBLE); - connection.appendInt(3); - for(int i=0;i<3;i++) connection.appendDouble(normalDir[i]); + connection.appendInt32(BOTTLE_TAG_LIST + BOTTLE_TAG_FLOAT64); + connection.appendInt32(3); + for(int i=0;i<3;i++) connection.appendFloat64(normalDir[i]); // - a list of N int, i.e. the active taxel ids - connection.appendInt(BOTTLE_TAG_LIST + BOTTLE_TAG_INT); - connection.appendInt(activeTaxels); - for(unsigned int i=0;iwrite(connection)) diff --git a/src/libraries/skinDynLib/src/skinPart.cpp b/src/libraries/skinDynLib/src/skinPart.cpp index 62db9c16b3..d6bc7f63e1 100644 --- a/src/libraries/skinDynLib/src/skinPart.cpp +++ b/src/libraries/skinDynLib/src/skinPart.cpp @@ -216,7 +216,7 @@ using namespace iCub::skinDynLib; for (int i = 0; i < getSize(); i++) { - taxel2Repr.push_back(b.get(i).asInt()); + taxel2Repr.push_back(b.get(i).asInt32()); } initRepresentativeTaxels(); } diff --git a/src/modules/actionsRenderingEngine/include/iCub/MotorThread.h b/src/modules/actionsRenderingEngine/include/iCub/MotorThread.h index b4e236c946..ec2ea68f5e 100644 --- a/src/modules/actionsRenderingEngine/include/iCub/MotorThread.h +++ b/src/modules/actionsRenderingEngine/include/iCub/MotorThread.h @@ -55,9 +55,9 @@ #define ARM_HOMING_PERIOD 1.5 //[s] -#define S2C_HOMOGRAPHY yarp::os::createVocab('h','o','m','o') -#define S2C_DISPARITY yarp::os::createVocab('d','i','s','p') -#define S2C_NETWORK yarp::os::createVocab('n','e','t','w') +#define S2C_HOMOGRAPHY yarp::os::createVocab32('h','o','m','o') +#define S2C_DISPARITY yarp::os::createVocab32('d','i','s','p') +#define S2C_NETWORK yarp::os::createVocab32('n','e','t','w') using namespace std; @@ -308,7 +308,7 @@ class MotorThread: public PeriodicThread if (Bottle *bCartesian=bTarget->find("cartesian").asList()) if ((size_t)bCartesian->size()==track_cartesian_target.length()) for (size_t i=0; iget(i).asDouble(); + track_cartesian_target[i]=bCartesian->get(i).asFloat64(); } diff --git a/src/modules/actionsRenderingEngine/include/iCub/VisuoThread.h b/src/modules/actionsRenderingEngine/include/iCub/VisuoThread.h index 4bde6b7882..3b31fe8879 100644 --- a/src/modules/actionsRenderingEngine/include/iCub/VisuoThread.h +++ b/src/modules/actionsRenderingEngine/include/iCub/VisuoThread.h @@ -37,10 +37,10 @@ #include -#define PARAM_FIXATION yarp::os::createVocab('f','i','x','a') -#define PARAM_MOTION yarp::os::createVocab('m','o','t','i') -#define PARAM_TRACK yarp::os::createVocab('t','r','a','c') -#define PARAM_RAW yarp::os::createVocab('r','a','w') +#define PARAM_FIXATION yarp::os::createVocab32('f','i','x','a') +#define PARAM_MOTION yarp::os::createVocab32('m','o','t','i') +#define PARAM_TRACK yarp::os::createVocab32('t','r','a','c') +#define PARAM_RAW yarp::os::createVocab32('r','a','w') #define MODE_TRACK_TEMPLATE 0 #define MODE_TRACK_MOTION 1 diff --git a/src/modules/actionsRenderingEngine/src/MotorThread.cpp b/src/modules/actionsRenderingEngine/src/MotorThread.cpp index 3721d989c6..1b90a680d2 100644 --- a/src/modules/actionsRenderingEngine/src/MotorThread.cpp +++ b/src/modules/actionsRenderingEngine/src/MotorThread.cpp @@ -57,11 +57,11 @@ bool MotorThread::checkOptions(const Bottle &options, const string ¶meter) void Dragger::init(Bottle &initializer, double thread_rate) { - extForceThresh=initializer.check("external_force_thresh",Value(1e9)).asDouble(); - samplingRate=initializer.check("subsampling_rate",Value(500.0)).asDouble(); + extForceThresh=initializer.check("external_force_thresh",Value(1e9)).asFloat64(); + samplingRate=initializer.check("subsampling_rate",Value(500.0)).asFloat64(); - damping=initializer.check("damping",Value(1e9)).asDouble(); - inertia=initializer.check("inertia",Value(1e9)).asDouble(); + damping=initializer.check("damping",Value(1e9)).asFloat64(); + inertia=initializer.check("inertia",Value(1e9)).asFloat64(); Vector zeros3d(3); zeros3d=0.0; @@ -305,32 +305,32 @@ int MotorThread::setStereoToCartesianMode(const int mode, Bottle &reply) } //get left offsets - if(!bKinOffsets.find("left").asList()->check(Vocab::decode(modeS2C))) + if(!bKinOffsets.find("left").asList()->check(Vocab32::decode(modeS2C))) { Bottle &bKinMode=bKinOffsets.find("left").asList()->addList(); - bKinMode.addString(Vocab::decode(modeS2C)); + bKinMode.addString(Vocab32::decode(modeS2C)); Bottle &bKinVec=bKinMode.addList(); for(int i=0; i<3; i++) - bKinVec.addDouble(0.0); + bKinVec.addFloat64(0.0); } - Bottle *bKinLeft=bKinOffsets.find("left").asList()->find(Vocab::decode(modeS2C)).asList(); + Bottle *bKinLeft=bKinOffsets.find("left").asList()->find(Vocab32::decode(modeS2C)).asList(); for(int i=0; i<3; i++) - defaultKinematicOffset[LEFT][i]=bKinLeft->get(i).asDouble(); + defaultKinematicOffset[LEFT][i]=bKinLeft->get(i).asFloat64(); //get left offsets - if(!bKinOffsets.find("right").asList()->check(Vocab::decode(modeS2C))) + if(!bKinOffsets.find("right").asList()->check(Vocab32::decode(modeS2C))) { Bottle &bKinMode=bKinOffsets.find("right").asList()->addList(); - bKinMode.addString(Vocab::decode(modeS2C)); + bKinMode.addString(Vocab32::decode(modeS2C)); Bottle &bKinVec=bKinMode.addList(); for(int i=0; i<3; i++) - bKinVec.addDouble(0.0); + bKinVec.addFloat64(0.0); } - Bottle *bKinRight=bKinOffsets.find("right").asList()->find(Vocab::decode(modeS2C)).asList(); + Bottle *bKinRight=bKinOffsets.find("right").asList()->find(Vocab32::decode(modeS2C)).asList(); for(int i=0; i<3; i++) - defaultKinematicOffset[RIGHT][i]=bKinRight->get(i).asDouble(); + defaultKinematicOffset[RIGHT][i]=bKinRight->get(i).asFloat64(); return modeS2C; } @@ -350,7 +350,7 @@ bool MotorThread::targetToCartesian(Bottle *bTarget, Vector &xd) Bottle *bCartesian=bTarget->find("cartesian").asList(); xd.clear(); for(int i=0; isize(); i++) - xd.push_back(bCartesian->get(i).asDouble()); + xd.push_back(bCartesian->get(i).asFloat64()); found=true; } @@ -367,7 +367,7 @@ bool MotorThread::targetToCartesian(Bottle *bTarget, Vector &xd) { Vector stereo; for(int i=0; isize(); i++) - stereo.push_back(bStereo->get(i).asDouble()); + stereo.push_back(bStereo->get(i).asFloat64()); found=stereoToCartesian(stereo,xd); } @@ -432,7 +432,7 @@ bool MotorThread::loadExplorationPoses(const string &file_name) Bottle *b=tmpTorso.get(i).asList(); Vector v(b->size()); for(int j=0; jsize(); j++) - v[j]=b->get(j).asDouble(); + v[j]=b->get(j).asFloat64(); pos_torsoes.push_back(v); } @@ -442,7 +442,7 @@ bool MotorThread::loadExplorationPoses(const string &file_name) Bottle *b=tmpHand.get(i).asList(); Vector v(b->size()); for(int j=0; jsize(); j++) - v[j]=b->get(j).asDouble(); + v[j]=b->get(j).asFloat64(); handPoses.push_back(v); } @@ -452,7 +452,7 @@ bool MotorThread::loadExplorationPoses(const string &file_name) Bottle *b=tmpHead.get(i).asList(); Vector v(b->size()); for(int j=0; jsize(); j++) - v[j]=b->get(j).asDouble(); + v[j]=b->get(j).asFloat64(); headPoses.push_back(v); } @@ -525,22 +525,22 @@ bool MotorThread::stereoToCartesianHomography(const Vector &stereo, Vector &xd) bool MotorThread::stereoToCartesianDisparity(const Vector &stereo, Vector &xd) { Bottle bEye; - bEye.addDouble(stereo[0]); - bEye.addDouble(stereo[1]); + bEye.addFloat64(stereo[0]); + bEye.addFloat64(stereo[1]); Bottle bX; do { disparityPort.write(bEye,bX); } - while(bX.size()==0 || bX.get(2).asDouble()<0.0 ); + while(bX.size()==0 || bX.get(2).asFloat64()<0.0 ); - if(bX.size()!=0 && bX.get(2).asDouble()>0.0 ) + if(bX.size()!=0 && bX.get(2).asFloat64()>0.0 ) { xd.resize(3); - xd[0]=bX.get(0).asDouble(); - xd[1]=bX.get(1).asDouble(); - xd[2]=bX.get(2).asDouble(); + xd[0]=bX.get(0).asFloat64(); + xd[1]=bX.get(1).asFloat64(); + xd[2]=bX.get(2).asFloat64(); } xd=eye2root(xd,false); @@ -601,10 +601,10 @@ bool MotorThread::loadKinematicOffsets() { Bottle &bKinList=bKinOffsets.addList(); bKinList.addString("table_height"); - bKinList.addDouble(-0.1); + bKinList.addFloat64(-0.1); } - table_height=bKinOffsets.find("table_height").asDouble(); + table_height=bKinOffsets.find("table_height").asFloat64(); table.resize(4,0.0); table[2]=1.0; table[3]=-table_height; @@ -672,7 +672,7 @@ bool MotorThread::getGeneralOptions(Bottle &b) homeFix.resize(pB->size()-offs); for (size_t i=0; iget(offs+i).asDouble(); + homeFix[i]=pB->get(offs+i).asFloat64(); } else return false; @@ -682,7 +682,7 @@ bool MotorThread::getGeneralOptions(Bottle &b) reachAboveDisp.resize(pB->size()); for (int i=0; isize(); i++) - reachAboveDisp[i]=pB->get(i).asDouble(); + reachAboveDisp[i]=pB->get(i).asFloat64(); } else return false; @@ -692,7 +692,7 @@ bool MotorThread::getGeneralOptions(Bottle &b) graspAboveRelief.resize(pB->size()); for (int i=0; isize(); i++) - graspAboveRelief[i]=pB->get(i).asDouble(); + graspAboveRelief[i]=pB->get(i).asFloat64(); } else return false; @@ -702,13 +702,13 @@ bool MotorThread::getGeneralOptions(Bottle &b) pushAboveRelief.resize(pB->size()); for (int i=0; isize(); i++) - pushAboveRelief[i]=pB->get(i).asDouble(); + pushAboveRelief[i]=pB->get(i).asFloat64(); } else return false; - go_up_distance=b.check("go_up",Value(0.1)).asDouble(); - table_height_tolerance=b.find("table_height_tolerance").asDouble(); + go_up_distance=b.check("go_up",Value(0.1)).asFloat64(); + table_height_tolerance=b.find("table_height_tolerance").asFloat64(); return true; } @@ -721,7 +721,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) homePos[arm].resize(pB->size()); for (int i=0; isize(); i++) - homePos[arm][i]=pB->get(i).asDouble(); + homePos[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -731,7 +731,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) homeOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - homeOrient[arm][i]=pB->get(i).asDouble(); + homeOrient[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -741,7 +741,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) reachSideDisp[arm].resize(pB->size()); for (int i=0; isize(); i++) - reachSideDisp[arm][i]=pB->get(i).asDouble(); + reachSideDisp[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -751,7 +751,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) reachAboveOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - reachAboveOrient[arm][i]=pB->get(i).asDouble(); + reachAboveOrient[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -761,7 +761,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) reachAboveCata[arm].resize(pB->size()); for (int i=0; isize(); i++) - reachAboveCata[arm][i]=pB->get(i).asDouble(); + reachAboveCata[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -771,7 +771,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) reachSideOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - reachSideOrient[arm][i]=pB->get(i).asDouble(); + reachSideOrient[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -781,7 +781,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) deployPos[arm].resize(pB->size()); for (int i=0; isize(); i++) - deployPos[arm][i]=pB->get(i).asDouble(); + deployPos[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -790,7 +790,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) { deployOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - deployOrient[arm][i]=pB->get(i).asDouble(); + deployOrient[arm][i]=pB->get(i).asFloat64(); } else deployOrient[arm]=reachAboveOrient[arm]; @@ -800,7 +800,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) drawNearPos[arm].resize(pB->size()); for (int i=0; isize(); i++) - drawNearPos[arm][i]=pB->get(i).asDouble(); + drawNearPos[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -810,7 +810,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) drawNearOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - drawNearOrient[arm][i]=pB->get(i).asDouble(); + drawNearOrient[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -820,7 +820,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) shiftPos[arm].resize(pB->size()); for (int i=0; isize(); i++) - shiftPos[arm][i]=pB->get(i).asDouble(); + shiftPos[arm][i]=pB->get(i).asFloat64(); } else { @@ -833,7 +833,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) expectPos[arm].resize(pB->size()); for (int i=0; isize(); i++) - expectPos[arm][i]=pB->get(i).asDouble(); + expectPos[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -843,7 +843,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) expectOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - expectOrient[arm][i]=pB->get(i).asDouble(); + expectOrient[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -853,7 +853,7 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) takeToolPos[arm].resize(pB->size()); for (int i=0; isize(); i++) - takeToolPos[arm][i]=pB->get(i).asDouble(); + takeToolPos[arm][i]=pB->get(i).asFloat64(); } else return false; @@ -863,12 +863,12 @@ bool MotorThread::getArmOptions(Bottle &b, const int &arm) takeToolOrient[arm].resize(pB->size()); for (int i=0; isize(); i++) - takeToolOrient[arm][i]=pB->get(i).asDouble(); + takeToolOrient[arm][i]=pB->get(i).asFloat64(); } else return false; - extForceThresh[arm]=b.check("external_forces_thresh",Value(0.0)).asDouble(); + extForceThresh[arm]=b.check("external_forces_thresh",Value(0.0)).asFloat64(); string modelFile("grasp_model_"); modelFile+=(arm==LEFT?"left":"right"); @@ -935,17 +935,17 @@ bool MotorThread::threadInit() string name=rf.find("name").asString(); string robot=bMotor.check("robot",Value("icub")).asString(); string partUsed=bMotor.check("part_used",Value("both_arms")).asString(); - int actionprimitives_layer=bMotor.check("actionprimitives_layer",Value(2)).asInt(); - setPeriod((double)bMotor.check("thread_period",Value(100)).asInt()/1000.0); + int actionprimitives_layer=bMotor.check("actionprimitives_layer",Value(2)).asInt32(); + setPeriod((double)bMotor.check("thread_period",Value(100)).asInt32()/1000.0); actions_path=bMotor.check("actions",Value("actions")).asString(); - double eyesTrajTime=bMotor.check("eyes_traj_time",Value(1.0)).asDouble(); - double neckTrajTime=bMotor.check("neck_traj_time",Value(2.0)).asDouble(); + double eyesTrajTime=bMotor.check("eyes_traj_time",Value(1.0)).asFloat64(); + double neckTrajTime=bMotor.check("neck_traj_time",Value(2.0)).asFloat64(); - double kp=bMotor.check("stereo_kp",Value(0.001)).asDouble(); - double ki=bMotor.check("stereo_ki",Value(0.001)).asDouble(); - double kd=bMotor.check("stereo_kd",Value(0.0)).asDouble(); + double kp=bMotor.check("stereo_kp",Value(0.001)).asFloat64(); + double ki=bMotor.check("stereo_ki",Value(0.001)).asFloat64(); + double kd=bMotor.check("stereo_kd",Value(0.0)).asFloat64(); stereo_track=bMotor.check("stereo_track",Value("on")).asString()=="on"; dominant_eye=(bMotor.check("dominant_eye",Value("left")).asString()=="left")?LEFT:RIGHT; @@ -1065,21 +1065,21 @@ bool MotorThread::threadInit() Bottle &bKp=stereoOpt.addList(); bKp.addString("Kp"); Bottle &bKpVal=bKp.addList(); - bKpVal.addDouble(kp); + bKpVal.addFloat64(kp); Bottle &bKi=stereoOpt.addList(); bKi.addString("Ki"); Bottle &bKiVal=bKi.addList(); - bKiVal.addDouble(ki); + bKiVal.addFloat64(ki); Bottle &bKd=stereoOpt.addList(); bKd.addString("Kd"); Bottle &bKdVal=bKd.addList(); - bKdVal.addDouble(kd); + bKdVal.addFloat64(kd); Bottle &bTs=stereoOpt.addList(); bTs.addString("Ts"); - bTs.addDouble(0.05); + bTs.addFloat64(0.05); Bottle &bDominantEye=stereoOpt.addList(); bDominantEye.addString("dominantEye"); @@ -1090,30 +1090,30 @@ bool MotorThread::threadInit() //bind neck pitch and roll; if(neckPitchRange!=NULL && neckPitchRange->size()==1) { - double neckPitchBlock=neckPitchRange->get(0).asDouble(); + double neckPitchBlock=neckPitchRange->get(0).asFloat64(); ctrl_gaze->blockNeckPitch(neckPitchBlock); } else if(neckPitchRange!=NULL && neckPitchRange->size()>1) { - double neckPitchMin=neckPitchRange->get(0).asDouble(); - double neckPitchMax=neckPitchRange->get(1).asDouble(); + double neckPitchMin=neckPitchRange->get(0).asFloat64(); + double neckPitchMax=neckPitchRange->get(1).asFloat64(); ctrl_gaze->bindNeckPitch(neckPitchMin,neckPitchMax); } if(neckRollRange!=NULL && neckRollRange->size()==1) { - double neckRollBlock=neckRollRange->get(0).asDouble(); + double neckRollBlock=neckRollRange->get(0).asFloat64(); ctrl_gaze->blockNeckRoll(neckRollBlock); } else if(neckRollRange!=NULL && neckRollRange->size()>1) { - double neckRollMin=neckRollRange->get(0).asDouble(); - double neckRollMax=neckRollRange->get(1).asDouble(); + double neckRollMin=neckRollRange->get(0).asFloat64(); + double neckRollMax=neckRollRange->get(1).asFloat64(); ctrl_gaze->bindNeckRoll(neckRollMin,neckRollMax); } if (bMotor.check("block_eyes")) { - ctrl_gaze->blockEyes(bMotor.find("block_eyes").asDouble()); + ctrl_gaze->blockEyes(bMotor.find("block_eyes").asFloat64()); ctrl_gaze->waitMotionDone(); } @@ -1191,8 +1191,8 @@ bool MotorThread::threadInit() for(int i=0; isize(); i++) { - torso_stiffness.push_back(bImpedanceTorsoStiff->get(i).asDouble()); - torso_damping.push_back(bImpedanceTorsoDamp->get(i).asDouble()); + torso_stiffness.push_back(bImpedanceTorsoStiff->get(i).asFloat64()); + torso_damping.push_back(bImpedanceTorsoDamp->get(i).asFloat64()); } for(int i=0; isize(); i++) @@ -1205,13 +1205,13 @@ bool MotorThread::threadInit() for(int i=0; isize(); i++) { - arm_stiffness.push_back(bImpedanceArmStiff->get(i).asDouble()); - arm_damping.push_back(bImpedanceArmDamp->get(i).asDouble()); + arm_stiffness.push_back(bImpedanceArmStiff->get(i).asFloat64()); + arm_damping.push_back(bImpedanceArmDamp->get(i).asFloat64()); } option.put("local",name); - default_exec_time=option.check("default_exec_time",Value("3.0")).asDouble(); + default_exec_time=option.check("default_exec_time",Value("3.0")).asFloat64(); reachingTimeout=std::max(2.0*default_exec_time,4.0); string arm_name[]={"left_arm","right_arm"}; @@ -1279,7 +1279,7 @@ bool MotorThread::threadInit() int context; tmpCtrl->storeContext(&context); - double armTargetTol=bMotor.check("arm_target_tol",Value(0.01)).asDouble(); + double armTargetTol=bMotor.check("arm_target_tol",Value(0.01)).asFloat64(); tmpCtrl->setInTargetTol(armTargetTol); storeContext(arm); @@ -1291,8 +1291,8 @@ bool MotorThread::threadInit() { if (pB->size()>=2) { - double height=pB->get(0).asDouble(); - double weight=pB->get(1).asDouble(); + double height=pB->get(0).asFloat64(); + double weight=pB->get(1).asFloat64(); changeElbowHeight(arm,height,weight); } } @@ -1319,7 +1319,7 @@ bool MotorThread::threadInit() } //set the initial stereo2cartesian mode - int starting_modeS2C=bMotor.check("stereoTocartesian_mode",Value("homography")).asVocab(); + int starting_modeS2C=bMotor.check("stereoTocartesian_mode",Value("homography")).asVocab32(); setStereoToCartesianMode(starting_modeS2C); // initializer dragger @@ -1334,7 +1334,7 @@ bool MotorThread::threadInit() head_mode=HEAD_MODE_IDLE; arm_mode=ARM_MODE_IDLE; - random_pos_y=bMotor.check("random_pos_y",Value(0.1)).asDouble(); + random_pos_y=bMotor.check("random_pos_y",Value(0.1)).asFloat64(); closed=false; interrupted=false; @@ -1442,13 +1442,13 @@ void MotorThread::run() Vector tmp_x=dragger.x0 - x; for(size_t i=0; isize()); for (size_t i=0; iget(i).asDouble(); + approach_data[i]=bApproach->get(i).asFloat64(); } } @@ -1864,12 +1864,12 @@ bool MotorThread::point_far(Bottle &options) Bottle pointing_sequence; if (action[arm]->getHandSequence("pointing_hand",pointing_sequence)) { - int numWayPoints=pointing_sequence.find("numWayPoints").asInt(); + int numWayPoints=pointing_sequence.find("numWayPoints").asInt32(); ostringstream wp; wp<<"wp_"<find("poss").asList(); Vector joints(poss->size()); for (size_t i=0; iget(i).asDouble(); + joints[i]=poss->get(i).asFloat64(); Bottle finger_joints; finger_joints.addList().read(joints); requirements.put("finger-joints",finger_joints.get(0)); @@ -1924,7 +1924,7 @@ bool MotorThread::look(Bottle &options) if (options.check("block_eyes")) { - ctrl_gaze->blockEyes(options.find("block_eyes").asDouble()); + ctrl_gaze->blockEyes(options.find("block_eyes").asFloat64()); ctrl_gaze->waitMotionDone(); } @@ -2157,15 +2157,15 @@ bool MotorThread::changeElbowHeight(const int arm, const double height, Bottle &optTask2=tweakOptions.addList(); optTask2.addString("task_2"); Bottle &plTask2=optTask2.addList(); - plTask2.addInt(6); + plTask2.addInt32(6); Bottle &posPart=plTask2.addList(); - posPart.addDouble(0.0); - posPart.addDouble(0.0); - posPart.addDouble(height); + posPart.addFloat64(0.0); + posPart.addFloat64(0.0); + posPart.addFloat64(height); Bottle &weightsPart=plTask2.addList(); - weightsPart.addDouble(0.0); - weightsPart.addDouble(0.0); - weightsPart.addDouble(weight); + weightsPart.addFloat64(0.0); + weightsPart.addFloat64(0.0); + weightsPart.addFloat64(weight); ret=ctrl->tweakSet(tweakOptions); deleteContext(arm); @@ -2476,11 +2476,11 @@ bool MotorThread::getHandImagePosition(Bottle &hand_image_pos) ctrl_gaze->getHeadPose(x_head,o_head); hand_image_pos.clear(); - hand_image_pos.addDouble(px[LEFT][0]); - hand_image_pos.addDouble(px[LEFT][1]); - hand_image_pos.addDouble(px[RIGHT][0]); - hand_image_pos.addDouble(px[RIGHT][1]); - hand_image_pos.addDouble(norm(x_head-x_hand)); + hand_image_pos.addFloat64(px[LEFT][0]); + hand_image_pos.addFloat64(px[LEFT][1]); + hand_image_pos.addFloat64(px[RIGHT][0]); + hand_image_pos.addFloat64(px[RIGHT][1]); + hand_image_pos.addFloat64(norm(x_head-x_hand)); return true; } @@ -2683,7 +2683,7 @@ bool MotorThread::exploreTorso(Bottle &options) Bottle info; ctrl_gaze->getInfo(info); - double head_version=info.check("head_version",Value(1.0)).asDouble(); + double head_version=info.check("head_version",Value(1.0)).asFloat64(); ostringstream type; type<<(dominant_eye==LEFT?"left":"right"); @@ -2693,7 +2693,7 @@ bool MotorThread::exploreTorso(Bottle &options) iCubEye iKinTorso=iCubEye(type.str()); iKinTorso.releaseLink(0); // pitch iKinTorso.releaseLink(1); // roll - for (size_t i=2; iget(j).asDouble(); + x[j]=b->get(j).asFloat64(); for(int j=0; j<4; j++) - o[j]=b->get(j+3).asDouble(); + o[j]=b->get(j+3).asFloat64(); ctrl->goToPoseSync(init_x-x,o); Time::delay(0.1); @@ -3112,7 +3112,7 @@ bool MotorThread::startLearningModeKinOffset(Bottle &options) { size_t n=std::min(x.length(),(size_t)b1->size()); for (size_t i=0; iget(i).asDouble(); + x[i]=b1->get(i).asFloat64(); specifiedTarget=true; } } @@ -3165,10 +3165,10 @@ bool MotorThread::suspendLearningModeKinOffset(Bottle &options) //update the offset and save on file Bottle bOffset; for(int i=0; i<3; i++) - bOffset.addDouble(defaultKinematicOffset[dragger.arm][i]); + bOffset.addFloat64(defaultKinematicOffset[dragger.arm][i]); string arm_name=(dragger.arm==LEFT?"left":"right"); - *bKinOffsets.find(arm_name).asList()->find(Vocab::decode(modeS2C)).asList()=bOffset; + *bKinOffsets.find(arm_name).asList()->find(Vocab32::decode(modeS2C)).asList()=bOffset; saveKinematicOffsets(); } diff --git a/src/modules/actionsRenderingEngine/src/VisuoThread.cpp b/src/modules/actionsRenderingEngine/src/VisuoThread.cpp index fbc8c7c24d..08f183308a 100644 --- a/src/modules/actionsRenderingEngine/src/VisuoThread.cpp +++ b/src/modules/actionsRenderingEngine/src/VisuoThread.cpp @@ -212,7 +212,7 @@ void VisuoThread::updateLocationsMIL() for(int i=0; iget(0).asList()->size(); i++) { Bottle *b=bLocations->get(0).asList()->get(i).asList(); - locations[b->get(0).asString()]=cvPoint(b->get(1).asInt(),b->get(2).asInt()); + locations[b->get(0).asString()]=cvPoint(b->get(1).asInt32(),b->get(2).asInt32()); } } } @@ -244,12 +244,12 @@ void VisuoThread::updateMotionCUT() { Item item; item.t=Time::now(); - item.size=bMotion[cam]->get(0).asList()->get(2).asDouble(); - item.p=cvPoint(bMotion[cam]->get(0).asList()->get(0).asInt(),bMotion[cam]->get(0).asList()->get(1).asInt()); + item.size=bMotion[cam]->get(0).asList()->get(2).asFloat64(); + item.p=cvPoint(bMotion[cam]->get(0).asList()->get(0).asInt32(),bMotion[cam]->get(0).asList()->get(1).asInt32()); buffer[cam].push_back(item); - stereo[2*cam]=bMotion[cam]->get(0).asList()->get(0).asDouble(); - stereo[2*cam+1]=bMotion[cam]->get(0).asList()->get(1).asDouble(); + stereo[2*cam]=bMotion[cam]->get(0).asList()->get(0).asFloat64(); + stereo[2*cam+1]=bMotion[cam]->get(0).asList()->get(1).asFloat64(); } // Avoid time unconsistencies @@ -316,13 +316,13 @@ void VisuoThread::updatePFTracker() Bottle v; v.clear(); Bottle &vl=v.addList(); - vl.addInt(cvRound(stereoTracker.vec[0])); - vl.addInt(cvRound(stereoTracker.vec[1])); - vl.addInt(stereoTracker.side); + vl.addInt32(cvRound(stereoTracker.vec[0])); + vl.addInt32(cvRound(stereoTracker.vec[1])); + vl.addInt32(stereoTracker.side); Bottle &vr=v.addList(); - vr.addInt(cvRound(stereoTracker.vec[6])); - vr.addInt(cvRound(stereoTracker.vec[7])); - vr.addInt(stereoTracker.side); + vr.addInt32(cvRound(stereoTracker.vec[6])); + vr.addInt32(cvRound(stereoTracker.vec[7])); + vr.addInt32(stereoTracker.side); boundMILPort.write(v); } @@ -365,20 +365,20 @@ bool VisuoThread::threadInit() Bottle bVision=rf.findGroup("vision"); - setPeriod((double)bVision.check("period",Value(20)).asInt()/1000.0); + setPeriod((double)bVision.check("period",Value(20)).asInt32()/1000.0); - minMotionBufSize=bVision.check("minMotionBufSize",Value(10)).asInt(); - minTrackBufSize=bVision.check("minTrackBufSize",Value(1)).asInt(); - maxTrackBufSize=bVision.check("maxTrackBufSize",Value(2)).asInt(); - timeTol=bVision.check("timeTol",Value(0.5)).asDouble(); - motionStdThresh=bVision.check("motionStdThresh",Value(5.0)).asDouble(); - speedStdThresh=bVision.check("speedStdThresh",Value(700.0)).asDouble(); - stereoDistThresh=bVision.check("stereoDistThresh",Value(300.0)).asDouble(); + minMotionBufSize=bVision.check("minMotionBufSize",Value(10)).asInt32(); + minTrackBufSize=bVision.check("minTrackBufSize",Value(1)).asInt32(); + maxTrackBufSize=bVision.check("maxTrackBufSize",Value(2)).asInt32(); + timeTol=bVision.check("timeTol",Value(0.5)).asFloat64(); + motionStdThresh=bVision.check("motionStdThresh",Value(5.0)).asFloat64(); + speedStdThresh=bVision.check("speedStdThresh",Value(700.0)).asFloat64(); + stereoDistThresh=bVision.check("stereoDistThresh",Value(300.0)).asFloat64(); dominant_eye=bVision.check("dominant_eye",Value("left")).asString()=="left"?LEFT:RIGHT; - rawWaitThresh=bVision.check("raw_detection_wait_thresh",Value(15.0)).asDouble(); - motionWaitThresh=bVision.check("motion_detection_wait_thresh",Value(5.0)).asDouble(); - objectWaitThresh=bVision.check("object_detection_wait_thresh",Value(5.0)).asDouble(); + rawWaitThresh=bVision.check("raw_detection_wait_thresh",Value(15.0)).asFloat64(); + motionWaitThresh=bVision.check("motion_detection_wait_thresh",Value(5.0)).asFloat64(); + objectWaitThresh=bVision.check("object_detection_wait_thresh",Value(5.0)).asFloat64(); // open ports outPort[LEFT].open("/"+name+"/left/img:o"); @@ -455,17 +455,17 @@ bool VisuoThread::getTarget(Value &type, Bottle &options) { if(list->get(0).asString()=="right") { - bStereo.addDouble(0.0); - bStereo.addDouble(0.0); - bStereo.addDouble(list->get(1).asDouble()); - bStereo.addDouble(list->get(2).asDouble()); + bStereo.addFloat64(0.0); + bStereo.addFloat64(0.0); + bStereo.addFloat64(list->get(1).asFloat64()); + bStereo.addFloat64(list->get(2).asFloat64()); } else if(list->get(0).asString()=="left") { - bStereo.addDouble(list->get(1).asDouble()); - bStereo.addDouble(list->get(2).asDouble()); - bStereo.addDouble(0.0); - bStereo.addDouble(0.0); + bStereo.addFloat64(list->get(1).asFloat64()); + bStereo.addFloat64(list->get(2).asFloat64()); + bStereo.addFloat64(0.0); + bStereo.addFloat64(0.0); } else if(list->get(0).asString()=="cartesian") { @@ -475,7 +475,7 @@ bool VisuoThread::getTarget(Value &type, Bottle &options) Bottle &bCartesian=bNewCartesian.addList(); for(int i=1; isize(); i++) - bCartesian.addDouble(list->get(i).asDouble()); + bCartesian.addFloat64(list->get(i).asFloat64()); } else { @@ -485,22 +485,22 @@ bool VisuoThread::getTarget(Value &type, Bottle &options) Bottle &bCartesian=bNewCartesian.addList(); for(int i=0; isize(); i++) - bCartesian.addDouble(list->get(i).asDouble()); + bCartesian.addFloat64(list->get(i).asFloat64()); } ok=true; } else if(list->size()==2) { - bStereo.addDouble(list->get(0).asDouble()); - bStereo.addDouble(list->get(1).asDouble()); - bStereo.addDouble(0.0); - bStereo.addDouble(0.0); + bStereo.addFloat64(list->get(0).asFloat64()); + bStereo.addFloat64(list->get(1).asFloat64()); + bStereo.addFloat64(0.0); + bStereo.addFloat64(0.0); ok=true; } } - else switch(type.asVocab()) + else switch(type.asVocab32()) { case PARAM_FIXATION: { @@ -557,7 +557,7 @@ bool VisuoThread::getFixation(Bottle &bStereo) imgMutex.unlock(); for(size_t i=0; iget(0).asInt(); - stereo[1]=bL->get(1).asInt(); + stereo[0]=bL->get(0).asInt32(); + stereo[1]=bL->get(1).asInt32(); } if(bR!=NULL) { - stereo[2]=bR->get(0).asInt(); - stereo[3]=bR->get(1).asInt(); + stereo[2]=bR->get(0).asInt32(); + stereo[3]=bR->get(1).asInt32(); } } @@ -709,7 +709,7 @@ bool VisuoThread::getRaw(Bottle &bStereo) } for(size_t i=0; i -#define ACK yarp::os::createVocab('a','c','k') -#define NACK yarp::os::createVocab('n','a','c','k') - -#define RPC_HELP yarp::os::createVocab('h','e','l','p') -#define RPC_GET yarp::os::createVocab('g','e','t') -#define RPC_GET_STATUS yarp::os::createVocab('s','t','a','t') -#define RPC_IMPEDANCE yarp::os::createVocab('i','m','p','e') -#define RPC_S2C_MODE yarp::os::createVocab('m','o','d','e') -#define RPC_INTERRUPT yarp::os::createVocab('i','n','t','e') -#define RPC_REINSTATE yarp::os::createVocab('r','e','i','n') -#define RPC_WAVEING yarp::os::createVocab('w','a','v','e') -#define RPC_ELBOW yarp::os::createVocab('e','l','b','o') -#define RPC_EXECTIME yarp::os::createVocab('t','i','m','e') - -#define CMD_IDLE yarp::os::createVocab('i','d','l','e') -#define CMD_HOME yarp::os::createVocab('h','o','m','e') -#define CMD_CALIBRATE yarp::os::createVocab('c','a','l','i') -#define CMD_EXPLORE yarp::os::createVocab('e','x','p','l') - -#define CMD_OBSERVE yarp::os::createVocab('o','b','s','e') -#define CMD_DROP yarp::os::createVocab('d','r','o','p') - -#define CMD_HOLD yarp::os::createVocab('h','o','l','d') - -#define CMD_LEARN_MIL yarp::os::createVocab('l','e','a','r') - -#define CMD_GET yarp::os::createVocab('g','e','t') -#define CMD_TAKE yarp::os::createVocab('t','a','k','e') -#define CMD_GRASP yarp::os::createVocab('g','r','a','s') -#define CMD_TOUCH yarp::os::createVocab('t','o','u','c') -#define CMD_PICK yarp::os::createVocab('p','i','c','k') -#define CMD_PUSH yarp::os::createVocab('p','u','s','h') -#define CMD_POINT yarp::os::createVocab('p','o','i','n') -#define CMD_POINT_FAR yarp::os::createVocab('p','f','a','r') -#define CMD_LOOK yarp::os::createVocab('l','o','o','k') -#define CMD_TRACK yarp::os::createVocab('t','r','a','c') -#define CMD_EXPECT yarp::os::createVocab('e','x','p','e') -#define CMD_GIVE yarp::os::createVocab('g','i','v','e') -#define CMD_HAND yarp::os::createVocab('h','a','n','d') -#define CMD_GAZE yarp::os::createVocab('r','e','l','e') +#define ACK yarp::os::createVocab32('a','c','k') +#define NACK yarp::os::createVocab32('n','a','c','k') + +#define RPC_HELP yarp::os::createVocab32('h','e','l','p') +#define RPC_GET yarp::os::createVocab32('g','e','t') +#define RPC_GET_STATUS yarp::os::createVocab32('s','t','a','t') +#define RPC_IMPEDANCE yarp::os::createVocab32('i','m','p','e') +#define RPC_S2C_MODE yarp::os::createVocab32('m','o','d','e') +#define RPC_INTERRUPT yarp::os::createVocab32('i','n','t','e') +#define RPC_REINSTATE yarp::os::createVocab32('r','e','i','n') +#define RPC_WAVEING yarp::os::createVocab32('w','a','v','e') +#define RPC_ELBOW yarp::os::createVocab32('e','l','b','o') +#define RPC_EXECTIME yarp::os::createVocab32('t','i','m','e') + +#define CMD_IDLE yarp::os::createVocab32('i','d','l','e') +#define CMD_HOME yarp::os::createVocab32('h','o','m','e') +#define CMD_CALIBRATE yarp::os::createVocab32('c','a','l','i') +#define CMD_EXPLORE yarp::os::createVocab32('e','x','p','l') + +#define CMD_OBSERVE yarp::os::createVocab32('o','b','s','e') +#define CMD_DROP yarp::os::createVocab32('d','r','o','p') + +#define CMD_HOLD yarp::os::createVocab32('h','o','l','d') + +#define CMD_LEARN_MIL yarp::os::createVocab32('l','e','a','r') + +#define CMD_GET yarp::os::createVocab32('g','e','t') +#define CMD_TAKE yarp::os::createVocab32('t','a','k','e') +#define CMD_GRASP yarp::os::createVocab32('g','r','a','s') +#define CMD_TOUCH yarp::os::createVocab32('t','o','u','c') +#define CMD_PICK yarp::os::createVocab32('p','i','c','k') +#define CMD_PUSH yarp::os::createVocab32('p','u','s','h') +#define CMD_POINT yarp::os::createVocab32('p','o','i','n') +#define CMD_POINT_FAR yarp::os::createVocab32('p','f','a','r') +#define CMD_LOOK yarp::os::createVocab32('l','o','o','k') +#define CMD_TRACK yarp::os::createVocab32('t','r','a','c') +#define CMD_EXPECT yarp::os::createVocab32('e','x','p','e') +#define CMD_GIVE yarp::os::createVocab32('g','i','v','e') +#define CMD_HAND yarp::os::createVocab32('h','a','n','d') +#define CMD_GAZE yarp::os::createVocab32('r','e','l','e') //commands for tool -#define CMD_TAKE_TOOL yarp::os::createVocab('t','a','t','o') +#define CMD_TAKE_TOOL yarp::os::createVocab32('t','a','t','o') -#define CMD_ACTION_TEACH yarp::os::createVocab('t','e','a','c') -#define CMD_ACTION_IMITATE yarp::os::createVocab('i','m','i','t') +#define CMD_ACTION_TEACH yarp::os::createVocab32('t','e','a','c') +#define CMD_ACTION_IMITATE yarp::os::createVocab32('i','m','i','t') //sub commands: get -#define GET_S2C yarp::os::createVocab('s','2','c') -#define GET_TABLE yarp::os::createVocab('t','a','b','l') -#define GET_HOLDING yarp::os::createVocab('h','o','l','d') -#define GET_HAND yarp::os::createVocab('h','a','n','d') -#define GET_IMAGE yarp::os::createVocab('i','m','a','g') -#define GET_IDLE yarp::os::createVocab('i','d','l','e') +#define GET_S2C yarp::os::createVocab32('s','2','c') +#define GET_TABLE yarp::os::createVocab32('t','a','b','l') +#define GET_HOLDING yarp::os::createVocab32('h','o','l','d') +#define GET_HAND yarp::os::createVocab32('h','a','n','d') +#define GET_IMAGE yarp::os::createVocab32('i','m','a','g') +#define GET_IDLE yarp::os::createVocab32('i','d','l','e') //sub commands: calib -#define CALIB_TABLE yarp::os::createVocab('t','a','b','l') -#define CALIB_FINGERS yarp::os::createVocab('f','i','n','g') -#define CALIB_KIN_OFFSET yarp::os::createVocab('k','i','n','e') +#define CALIB_TABLE yarp::os::createVocab32('t','a','b','l') +#define CALIB_FINGERS yarp::os::createVocab32('f','i','n','g') +#define CALIB_KIN_OFFSET yarp::os::createVocab32('k','i','n','e') //sub commands: explore -#define EXPLORE_TORSO yarp::os::createVocab('t','o','r','s') -#define EXPLORE_HAND yarp::os::createVocab('h','a','n','d') +#define EXPLORE_TORSO yarp::os::createVocab32('t','o','r','s') +#define EXPLORE_HAND yarp::os::createVocab32('h','a','n','d') #define PORT_TAG_CMD 0 @@ -532,7 +532,7 @@ class ActionsRenderingEngine return true; } - switch(command.get(0).asVocab()) + switch(command.get(0).asVocab32()) { case RPC_HELP: { @@ -550,7 +550,7 @@ class ActionsRenderingEngine { if(command.size()>1) { - switch(command.get(1).asVocab()) + switch(command.get(1).asVocab32()) { case RPC_GET_STATUS: { @@ -606,7 +606,7 @@ class ActionsRenderingEngine //set the stereo2cartesian mode case RPC_S2C_MODE: { - motorThr->setStereoToCartesianMode(command.get(1).asVocab(),reply); + motorThr->setStereoToCartesianMode(command.get(1).asVocab32(),reply); break; } @@ -633,8 +633,8 @@ class ActionsRenderingEngine if (command.size()>=4) { string arm=command.get(1).asString(); - double height=command.get(2).asDouble(); - double weight=command.get(3).asDouble(); + double height=command.get(2).asFloat64(); + double weight=command.get(3).asFloat64(); if ((arm=="both") || (arm=="left")) motorThr->changeElbowHeight(LEFT,height,weight); @@ -654,7 +654,7 @@ class ActionsRenderingEngine { if (command.size()>1) { - double execTime=command.get(1).asDouble(); + double execTime=command.get(1).asFloat64(); motorThr->changeExecTime(LEFT,execTime); motorThr->changeExecTime(RIGHT,execTime); reply.addString("execution time updated"); @@ -678,33 +678,33 @@ class ActionsRenderingEngine { if(closing) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("Sorry. Module closing."); return true; } if(command.size()==0) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("No command received."); } else if(interrupted) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("Module currently interrupted. Reinstate for action."); } else { if(port_tag==PORT_TAG_GET) { - if(command.get(0).asVocab()!=CMD_GET) + if(command.get(0).asVocab32()!=CMD_GET) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("This port can only process [get] commands"); } else if(command.size()>1) { - switch(command.get(1).asVocab()) + switch(command.get(1).asVocab32()) { case GET_S2C: { @@ -720,10 +720,10 @@ class ActionsRenderingEngine if(motorThr->targetToCartesian(tmp_command.find("target").asList(),xd)) { for(size_t i=0; iisHolding(command)) - reply.addVocab(ACK); + reply.addVocab32(ACK); else - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } case GET_HAND: { - if(command.get(2).asVocab()==GET_IMAGE) + if(command.get(2).asVocab32()==GET_IMAGE) { reply.clear(); if(!motorThr->getHandImagePosition(reply)) - reply.addVocab(NACK); + reply.addVocab32(NACK); } else - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -784,29 +784,29 @@ class ActionsRenderingEngine default: { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } } } else - reply.addVocab(NACK); + reply.addVocab32(NACK); } else if(port_tag==PORT_TAG_CMD) { - switch(command.get(0).asVocab()) + switch(command.get(0).asVocab32()) { case CMD_IDLE: { motorThr->setGazeIdle(); - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } case CMD_HOME: { motorThr->goHome(command); - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } @@ -815,18 +815,18 @@ class ActionsRenderingEngine bool holding; if (motorThr->hand(command,"",&holding)) { - reply.addVocab(ACK); - reply.addInt(holding?1:0); + reply.addVocab32(ACK); + reply.addInt32(holding?1:0); } else - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } case CMD_GAZE: { motorThr->clearIt(command); - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } @@ -836,7 +836,7 @@ class ActionsRenderingEngine { if(command.size()>1) { - switch(command.get(1).asVocab()) + switch(command.get(1).asVocab32()) { case GET_S2C: { @@ -848,10 +848,10 @@ class ActionsRenderingEngine { reply.clear(); for(size_t i=0; i1) { - switch(command.get(1).asVocab()) + switch(command.get(1).asVocab32()) { case EXPLORE_TORSO: { if(motorThr->exploreTorso(command)) - reply.addVocab(ACK); + reply.addVocab32(ACK); else - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -884,9 +884,9 @@ class ActionsRenderingEngine case EXPLORE_HAND: { if(motorThr->exploreHand(command)) - reply.addVocab(ACK); + reply.addVocab32(ACK); else - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -894,7 +894,7 @@ class ActionsRenderingEngine default: { string rep=command.get(1).asString(); - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("parameter '"+rep+"' not supported by 'explore' command."); break; } @@ -902,7 +902,7 @@ class ActionsRenderingEngine } else { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("explore command needs further parameter (e.g. 'torso')"); } break; @@ -910,15 +910,15 @@ class ActionsRenderingEngine case CMD_CALIBRATE: { - switch(command.get(1).asVocab()) + switch(command.get(1).asVocab32()) { case CALIB_TABLE: { idle = false; if(motorThr->calibTable(command)) - reply.addVocab(ACK); + reply.addVocab32(ACK); else - reply.addVocab(NACK); + reply.addVocab32(NACK); idle = true; break; } @@ -926,9 +926,9 @@ class ActionsRenderingEngine case CALIB_FINGERS: { if(motorThr->calibFingers(command)) - reply.addVocab(ACK); + reply.addVocab32(ACK); else - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -942,21 +942,21 @@ class ActionsRenderingEngine visuoThr->getTarget(command.get(3),command); if (motorThr->startLearningModeKinOffset(command)) { - reply.addVocab(ACK); + reply.addVocab32(ACK); reply.addString("learn kinematic offset mode: on"); } else - reply.addVocab(NACK); + reply.addVocab32(NACK); } else if(command.get(2).asString()=="stop") { if(motorThr->suspendLearningModeKinOffset(command)) { - reply.addVocab(ACK); + reply.addVocab32(ACK); reply.addString("learn kinematic offset mode: off"); } else - reply.addVocab(NACK); + reply.addVocab32(NACK); } break; @@ -979,14 +979,14 @@ class ActionsRenderingEngine if(!motorThr->startLearningModeAction(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("action "+action_name+" already known"); } else { motorThr->setGazeIdle(); motorThr->lookAtHand(command); - reply.addVocab(ACK); + reply.addVocab32(ACK); reply.addString("start teaching"); } } @@ -996,11 +996,11 @@ class ActionsRenderingEngine if(motorThr->suspendLearningModeAction(command)) { motorThr->setGazeIdle(); - reply.addVocab(ACK); + reply.addVocab32(ACK); reply.addString("stop teaching"); } else - reply.addVocab(NACK); + reply.addVocab32(NACK); } break; @@ -1018,12 +1018,12 @@ class ActionsRenderingEngine if(!motorThr->imitateAction(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("action "+action_name+" unknown"); } else { - reply.addVocab(ACK); + reply.addVocab32(ACK); reply.addString("action "+action_name+" done"); } motorThr->setGazeIdle(); @@ -1059,7 +1059,7 @@ class ActionsRenderingEngine { if(!motorThr->isHolding(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("Nothing to observe. Not holding anything"); motorThr->release(command); motorThr->goHome(command); @@ -1069,7 +1069,7 @@ class ActionsRenderingEngine motorThr->lookAtHand(command); motorThr->drawNear(command); - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } @@ -1081,7 +1081,7 @@ class ActionsRenderingEngine motorThr->setGazeIdle(); motorThr->release(command); motorThr->goHome(command); - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1100,14 +1100,14 @@ class ActionsRenderingEngine motorThr->goHome(b); } - reply.addVocab(ACK); + reply.addVocab32(ACK); } else { motorThr->setGazeIdle(); motorThr->release(command); motorThr->goHome(command); - reply.addVocab(NACK); + reply.addVocab32(NACK); } break; @@ -1117,7 +1117,7 @@ class ActionsRenderingEngine { if(!motorThr->isHolding(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("Nothing to give. Not holding anything"); motorThr->release(command); motorThr->goHome(command); @@ -1129,7 +1129,7 @@ class ActionsRenderingEngine motorThr->setGazeIdle(); motorThr->release(command); motorThr->goHome(command); - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1149,7 +1149,7 @@ class ActionsRenderingEngine motorThr->goHome(command); motorThr->setGazeIdle(); - reply.addVocab(ACK); + reply.addVocab32(ACK); idle = true; break; } @@ -1159,7 +1159,7 @@ class ActionsRenderingEngine idle = false; if(command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1168,7 +1168,7 @@ class ActionsRenderingEngine command.addString("pretake_hand"); if(!motorThr->reach(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1193,7 +1193,7 @@ class ActionsRenderingEngine } } - reply.addVocab(ACK); + reply.addVocab32(ACK); } else { @@ -1206,7 +1206,7 @@ class ActionsRenderingEngine motorThr->goHome(command); } - reply.addVocab(NACK); + reply.addVocab32(NACK); } idle = true; @@ -1218,7 +1218,7 @@ class ActionsRenderingEngine idle = false; if (command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1236,7 +1236,7 @@ class ActionsRenderingEngine motorThr->goHome(b); } - reply.addVocab(ACK); + reply.addVocab32(ACK); } else { @@ -1245,7 +1245,7 @@ class ActionsRenderingEngine if (!check(command,"still")) motorThr->goHome(command); - reply.addVocab(NACK); + reply.addVocab32(NACK); } idle = true; @@ -1256,7 +1256,7 @@ class ActionsRenderingEngine { if(command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1265,7 +1265,7 @@ class ActionsRenderingEngine command.addString("touch"); if(!motorThr->reach(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1276,7 +1276,7 @@ class ActionsRenderingEngine motorThr->goHome(command); } - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } @@ -1284,7 +1284,7 @@ class ActionsRenderingEngine { if(command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1292,7 +1292,7 @@ class ActionsRenderingEngine if (!motorThr->push(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1303,7 +1303,7 @@ class ActionsRenderingEngine motorThr->goHome(command); } - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } @@ -1311,7 +1311,7 @@ class ActionsRenderingEngine { if(command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1319,7 +1319,7 @@ class ActionsRenderingEngine if(!motorThr->point(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1329,14 +1329,14 @@ class ActionsRenderingEngine motorThr->goHome(command); } - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } case CMD_POINT_FAR: { if(command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1344,7 +1344,7 @@ class ActionsRenderingEngine if(!motorThr->point_far(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1354,14 +1354,14 @@ class ActionsRenderingEngine motorThr->goHome(command); } - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } case CMD_LOOK: { if(command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } @@ -1370,41 +1370,41 @@ class ActionsRenderingEngine if(!motorThr->look(command)) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } case CMD_TRACK: { - if (command.get(1).asVocab()!=Vocab::encode("motion")) + if (command.get(1).asVocab32()!=Vocab32::encode("motion")) visuoThr->getTarget(command.get(1),command); else visuoThr->trackMotion(); motorThr->track(command); - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } case CMD_TAKE_TOOL: { if (command.size()<2) { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } motorThr->takeTool(command); - reply.addVocab(ACK); + reply.addVocab32(ACK); break; } default: { - reply.addVocab(NACK); + reply.addVocab32(NACK); break; } } @@ -1414,7 +1414,7 @@ class ActionsRenderingEngine if(reply.isNull() || reply.size()==0) { - reply.addVocab(NACK); + reply.addVocab32(NACK); reply.addString("Random Error"); } diff --git a/src/modules/actionsRenderingEngine/src/pointing_far.cpp b/src/modules/actionsRenderingEngine/src/pointing_far.cpp index 21648369f7..1f1899b7b4 100644 --- a/src/modules/actionsRenderingEngine/src/pointing_far.cpp +++ b/src/modules/actionsRenderingEngine/src/pointing_far.cpp @@ -67,7 +67,7 @@ class PointingFarNLP : public Ipopt::TNLP hand=hand.substr(0,underscore); // update joints limits - for (size_t i=0; igetN(); i++) + for (unsigned int i=0; igetN(); i++) { double min,max; iarm->getLimits(i,&min,&max); @@ -134,7 +134,7 @@ class PointingFarNLP : public Ipopt::TNLP void getResult(Vector &q, Vector &x) const { q.resize(finger_tip->getN()); - for (size_t i=0; igetAng(i); x=finger_tip->EndEffPose(); } @@ -315,7 +315,7 @@ bool PointingFar::compute(ICartesianControl *iarm, const Property& requirements, Vector point(3,0.0); for (int i=0; isize(); i++) - point[i]=bPoint->get(i).asDouble(); + point[i]=bPoint->get(i).asFloat64(); Ipopt::SmartPtr app=new Ipopt::IpoptApplication; app->Options()->SetNumericValue("tol",0.01); @@ -337,7 +337,7 @@ bool PointingFar::compute(ICartesianControl *iarm, const Property& requirements, { Vector finger_joints(bFingerJoints->size()); for (size_t i=0; iget(i).asDouble(); + finger_joints[i]=bFingerJoints->get(i).asFloat64(); nlp->setFingerJoints(finger_joints); } @@ -358,7 +358,7 @@ bool PointingFar::point(ICartesianControl *iarm, const Vector& q, const Vector& // specify all joints Vector dof(10,1.0); iarm->setDOF(dof,dof); - for (size_t i=0; isetLimits(i,q[i],q[i]); double traj; diff --git a/src/modules/actionsRenderingEngine/src/utils.cpp b/src/modules/actionsRenderingEngine/src/utils.cpp index aa05aa5987..258c693f4e 100644 --- a/src/modules/actionsRenderingEngine/src/utils.cpp +++ b/src/modules/actionsRenderingEngine/src/utils.cpp @@ -34,7 +34,7 @@ bool ObjectPropertiesCollectorPort::getStereoPosition(const string &obj_name, Ve //ask for the object's id Bottle bAsk,bGet,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("name"); bTempAsk.addString("=="); @@ -43,19 +43,19 @@ bool ObjectPropertiesCollectorPort::getStereoPosition(const string &obj_name, Ve this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false || bReply.get(1).asList()->find("id").asList()->size()==0) return false; - bGet.addVocab(Vocab::encode("get")); + bGet.addVocab32("get"); Bottle &bTempGet=bGet.addList().addList(); bTempGet.addString("id"); - bTempGet.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempGet.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); this->write(bGet,bReply); - if(bReply.size()==0 || bReply.get(0).asVocab()!=Vocab::encode("ack")) + if(bReply.size()==0 || bReply.get(0).asVocab32()!=Vocab32::encode("ack")) return false; if(!bReply.get(1).asList()->check("position_2d_left") && !bReply.get(1).asList()->check("position_2d_right")) @@ -68,16 +68,16 @@ bool ObjectPropertiesCollectorPort::getStereoPosition(const string &obj_name, Ve { Bottle *bStereo=bReply.get(1).asList()->find("position_2d_left").asList(); - stereo[0]=0.5*(bStereo->get(0).asDouble()+bStereo->get(2).asDouble()); - stereo[1]=0.5*(bStereo->get(1).asDouble()+bStereo->get(3).asDouble()); + stereo[0]=0.5*(bStereo->get(0).asFloat64()+bStereo->get(2).asFloat64()); + stereo[1]=0.5*(bStereo->get(1).asFloat64()+bStereo->get(3).asFloat64()); } if(bReply.get(1).asList()->check("position_2d_right")) { Bottle *bStereo=bReply.get(1).asList()->find("position_2d_right").asList(); - stereo[2]=0.5*(bStereo->get(0).asDouble()+bStereo->get(2).asDouble()); - stereo[3]=0.5*(bStereo->get(1).asDouble()+bStereo->get(3).asDouble()); + stereo[2]=0.5*(bStereo->get(0).asFloat64()+bStereo->get(2).asFloat64()); + stereo[3]=0.5*(bStereo->get(1).asFloat64()+bStereo->get(3).asFloat64()); } return true; @@ -92,7 +92,7 @@ bool ObjectPropertiesCollectorPort::getCartesianPosition(const string &obj_name, //ask for the object's id Bottle bAsk,bGet,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("name"); bTempAsk.addString("=="); @@ -101,19 +101,19 @@ bool ObjectPropertiesCollectorPort::getCartesianPosition(const string &obj_name, this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false || bReply.get(1).asList()->find("id").asList()->size()==0) return false; - bGet.addVocab(Vocab::encode("get")); + bGet.addVocab32("get"); Bottle &bTempGet=bGet.addList().addList(); bTempGet.addString("id"); - bTempGet.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempGet.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); this->write(bGet,bReply); - if(bReply.size()==0 || bReply.get(0).asVocab()!=Vocab::encode("ack")) + if(bReply.size()==0 || bReply.get(0).asVocab32()!=Vocab32::encode("ack")) return false; @@ -127,7 +127,7 @@ bool ObjectPropertiesCollectorPort::getCartesianPosition(const string &obj_name, Bottle *bX=bReply.get(1).asList()->find("position_3d").asList(); for(int i=0; isize(); i++) - x[i]=bX->get(i).asDouble(); + x[i]=bX->get(i).asFloat64(); } @@ -144,7 +144,7 @@ bool ObjectPropertiesCollectorPort::getKinematicOffsets(const string &obj_name, //ask for the object's id Bottle bAsk,bGet,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("name"); bTempAsk.addString("=="); @@ -153,20 +153,20 @@ bool ObjectPropertiesCollectorPort::getKinematicOffsets(const string &obj_name, this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false || bReply.get(1).asList()->find("id").asList()->size()==0) return false; - bGet.addVocab(Vocab::encode("get")); + bGet.addVocab32("get"); Bottle &bTempGet=bGet.addList().addList(); bTempGet.addString("id"); - bTempGet.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempGet.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); this->write(bGet,bReply); - if(bReply.size()==0 || bReply.get(0).asVocab()!=Vocab::encode("ack")) + if(bReply.size()==0 || bReply.get(0).asVocab32()!=Vocab32::encode("ack")) return false; @@ -175,7 +175,7 @@ bool ObjectPropertiesCollectorPort::getKinematicOffsets(const string &obj_name, kinematic_offset[LEFT].resize(3); Bottle *bCartesianOffset=bReply.get(1).asList()->find("kinematic_offset_left").asList(); for(int i=0; isize(); i++) - kinematic_offset[LEFT][i]=bCartesianOffset->get(i).asDouble(); + kinematic_offset[LEFT][i]=bCartesianOffset->get(i).asFloat64(); } if(bReply.get(1).asList()->check("kinematic_offset_right")) @@ -183,7 +183,7 @@ bool ObjectPropertiesCollectorPort::getKinematicOffsets(const string &obj_name, kinematic_offset[RIGHT].resize(3); Bottle *bCartesianOffset=bReply.get(1).asList()->find("kinematic_offset_right").asList(); for(int i=0; isize(); i++) - kinematic_offset[RIGHT][i]=bCartesianOffset->get(i).asDouble(); + kinematic_offset[RIGHT][i]=bCartesianOffset->get(i).asFloat64(); } return true; @@ -198,7 +198,7 @@ bool ObjectPropertiesCollectorPort::setKinematicOffsets(const string &obj_name, //ask for the object's id Bottle bAsk,bSet,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("name"); bTempAsk.addString("=="); @@ -207,35 +207,35 @@ bool ObjectPropertiesCollectorPort::setKinematicOffsets(const string &obj_name, this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false || bReply.get(1).asList()->find("id").asList()->size()==0) return false; - bSet.addVocab(Vocab::encode("set")); + bSet.addVocab32("set"); Bottle &bTempSet=bSet.addList(); Bottle &bTempSetId=bTempSet.addList(); bTempSetId.addString("id"); - bTempSetId.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempSetId.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); //Kinematic offset left Bottle &bTempSetKinematicOffsetLeft=bTempSet.addList(); bTempSetKinematicOffsetLeft.addString("kinematic_offset_left"); Bottle &bTempSetVectorLeft=bTempSetKinematicOffsetLeft.addList(); for(size_t i=0; iwrite(bSet,bReply); - return bReply.get(0).asVocab()==Vocab::encode("ack"); + return bReply.get(0).asVocab32()==Vocab32::encode("ack"); } @@ -250,7 +250,7 @@ bool ObjectPropertiesCollectorPort::getTableHeight(double &table_height) //ask for the object's id Bottle bAsk,bGet,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("entity"); bTempAsk.addString("=="); @@ -259,25 +259,25 @@ bool ObjectPropertiesCollectorPort::getTableHeight(double &table_height) this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false || bReply.get(1).asList()->find("id").asList()->size()==0) return false; - bGet.addVocab(Vocab::encode("get")); + bGet.addVocab32("get"); Bottle &bTempGet=bGet.addList().addList(); bTempGet.addString("id"); - bTempGet.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempGet.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); this->write(bGet,bReply); - if(bReply.size()==0 || bReply.get(0).asVocab()!=Vocab::encode("ack")) + if(bReply.size()==0 || bReply.get(0).asVocab32()!=Vocab32::encode("ack")) return false; if(!bReply.get(1).asList()->check("height")) return false; - table_height=bReply.get(1).asList()->find("height").asDouble(); + table_height=bReply.get(1).asList()->find("height").asFloat64(); return true; } @@ -290,7 +290,7 @@ bool ObjectPropertiesCollectorPort::setTableHeight(const double table_height) //ask for the object's id Bottle bAsk,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("entity"); bTempAsk.addString("=="); @@ -299,7 +299,7 @@ bool ObjectPropertiesCollectorPort::setTableHeight(const double table_height) this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false) return false; @@ -307,35 +307,35 @@ bool ObjectPropertiesCollectorPort::setTableHeight(const double table_height) if(bReply.get(1).asList()->find("id").asList()->size()==0) { Bottle bAdd; - bAdd.addVocab(Vocab::encode("add")); + bAdd.addVocab32("add"); Bottle &bTempAdd=bAdd.addList(); Bottle &bEntity=bTempAdd.addList(); bEntity.addString("entity"); bEntity.addString("table"); Bottle &bHeight=bTempAdd.addList(); - bHeight.addString("height"); bHeight.addDouble(table_height); + bHeight.addString("height"); bHeight.addFloat64(table_height); this->write(bAdd,bReply); } else { Bottle bSet; - bSet.addVocab(Vocab::encode("set")); + bSet.addVocab32("set"); Bottle &bTempSet=bSet.addList(); Bottle &bTempSetId=bTempSet.addList(); bTempSetId.addString("id"); - bTempSetId.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempSetId.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); Bottle &bTableHeight=bTempSet.addList(); bTableHeight.addString("height"); - bTableHeight.addDouble(table_height); + bTableHeight.addFloat64(table_height); this->write(bSet,bReply); } - return bReply.get(0).asVocab()==Vocab::encode("ack"); + return bReply.get(0).asVocab32()==Vocab32::encode("ack"); } @@ -345,7 +345,7 @@ bool ObjectPropertiesCollectorPort::setAction(const string &act_name, const Bott return false; // rpc add: should ask to see if the same action already exists? Bottle bAdd, bReply; - bAdd.addVocab(Vocab::encode("add")); + bAdd.addVocab32("add"); Bottle &bTempAdd=bAdd.addList(); Bottle &bEntity=bTempAdd.addList(); @@ -357,7 +357,7 @@ bool ObjectPropertiesCollectorPort::setAction(const string &act_name, const Bott bTraj.addString("trajectory"); bTraj.addList()=*trajectory; this->write(bAdd,bReply); - return bReply.get(0).asVocab()==Vocab::encode("ack"); + return bReply.get(0).asVocab32()==Vocab32::encode("ack"); }; bool ObjectPropertiesCollectorPort::getAction(const string &act_name, Bottle *trajectory) { @@ -365,7 +365,7 @@ bool ObjectPropertiesCollectorPort::getAction(const string &act_name, Bottle *tr return false; //ask for the object's id Bottle bAsk,bGet,bReply; - bAsk.addVocab(Vocab::encode("ask")); + bAsk.addVocab32("ask"); Bottle &bTempAsk=bAsk.addList().addList(); bTempAsk.addString("name"); bTempAsk.addString("=="); @@ -374,19 +374,19 @@ bool ObjectPropertiesCollectorPort::getAction(const string &act_name, Bottle *tr this->write(bAsk,bReply); if(bReply.size()==0 || - bReply.get(0).asVocab()!=Vocab::encode("ack") || + bReply.get(0).asVocab32()!=Vocab32::encode("ack") || bReply.get(1).asList()->check("id")==false || bReply.get(1).asList()->find("id").asList()->size()==0) return false; - bGet.addVocab(Vocab::encode("get")); + bGet.addVocab32("get"); Bottle &bTempGet=bGet.addList().addList(); bTempGet.addString("id"); - bTempGet.addInt(bReply.get(1).asList()->find("id").asList()->get(0).asInt()); + bTempGet.addInt32(bReply.get(1).asList()->find("id").asList()->get(0).asInt32()); this->write(bGet,bReply); - if(bReply.size()==0 || bReply.get(0).asVocab()!=Vocab::encode("ack")) + if(bReply.size()==0 || bReply.get(0).asVocab32()!=Vocab32::encode("ack")) return false; if(!bReply.get(1).asList()->check("trajectory")) diff --git a/src/modules/camCalib/src/CamCalibModule.cpp b/src/modules/camCalib/src/CamCalibModule.cpp index 13c4707d4c..558d0e9e65 100644 --- a/src/modules/camCalib/src/CamCalibModule.cpp +++ b/src/modules/camCalib/src/CamCalibModule.cpp @@ -158,7 +158,7 @@ bool CamCalibModule::configure(yarp::os::ResourceFinder &rf){ { yWarning() << "port " << getName("/conf") << " already in use"; } - _prtImgIn.setSaturation(rf.check("saturation",Value(1.0)).asDouble()); + _prtImgIn.setSaturation(rf.check("saturation",Value(1.0)).asFloat64()); _prtImgIn.open(getName("/in")); _prtImgIn.setPointers(&_prtImgOut,_calibTool); _prtImgIn.setVerbose(rf.check("verbose")); @@ -210,7 +210,7 @@ bool CamCalibModule::respond(const Bottle& command, Bottle& reply) } else if (command.get(0).asString()=="sat" || command.get(0).asString()=="saturation") { - double satVal = command.get(1).asDouble(); + double satVal = command.get(1).asFloat64(); _prtImgIn.setSaturation(satVal); reply.addString("ok"); diff --git a/src/modules/camCalib/src/PinholeCalibTool.cpp b/src/modules/camCalib/src/PinholeCalibTool.cpp index 75f2aa47b4..90457fe22d 100644 --- a/src/modules/camCalib/src/PinholeCalibTool.cpp +++ b/src/modules/camCalib/src/PinholeCalibTool.cpp @@ -54,32 +54,32 @@ bool PinholeCalibTool::configure (Searchable &config){ _calibImgSize.width = config.check("w", Value(320), - "Image width for which calibration parameters were calculated (int)").asInt(); + "Image width for which calibration parameters were calculated (int)").asInt32(); _calibImgSize.height = config.check("h", Value(240), - "Image height for which calibration parameters were calculated (int)").asInt(); + "Image height for which calibration parameters were calculated (int)").asInt32(); _drawCenterCross = config.check("drawCenterCross", Value(0), - "Draw a cross at calibration center (int [0|1]).").asInt()!=0; + "Draw a cross at calibration center (int [0|1]).").asInt32()!=0; CV_MAT_ELEM( *_intrinsic_matrix , float, 0, 0) = (float)config.check("fx", Value(320.0), - "Focal length x (double)").asDouble(); + "Focal length x (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 0, 1) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 0, 2) = (float)config.check("cx", Value(160.0), - "Principal point x (double)").asDouble(); + "Principal point x (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 0) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 1) = (float)config.check("fy", Value(320.0), - "Focal length y (double)").asDouble(); + "Focal length y (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 2) = (float)config.check("cy", Value(120.0), - "Principal point y (double)").asDouble(); + "Principal point y (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 0) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 1) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 2) = 1.0f; @@ -99,10 +99,10 @@ bool PinholeCalibTool::configure (Searchable &config){ if ( !config.check("p2") ) { stopConfig("p2"); return false;} - fprintf(stdout,"fx=%g\n",config.find("fx").asDouble()); - fprintf(stdout,"fy=%g\n",config.find("fy").asDouble()); - fprintf(stdout,"cx=%g\n",config.find("cx").asDouble()); - fprintf(stdout,"cy=%g\n",config.find("cy").asDouble()); + fprintf(stdout,"fx=%g\n",config.find("fx").asFloat64()); + fprintf(stdout,"fy=%g\n",config.find("fy").asFloat64()); + fprintf(stdout,"cx=%g\n",config.find("cx").asFloat64()); + fprintf(stdout,"cy=%g\n",config.find("cy").asFloat64()); // copy to scaled matrix ;) @@ -119,16 +119,16 @@ bool PinholeCalibTool::configure (Searchable &config){ /* init the distortion coeffs */ CV_MAT_ELEM( *_distortion_coeffs, float, 0, 0) = (float)config.check("k1", Value(0.0), - "Radial distortion 1(double)").asDouble(); + "Radial distortion 1(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 1) = (float)config.check("k2", Value(0.0), - "Radial distortion 2(double)").asDouble(); + "Radial distortion 2(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 2) = (float)config.check("p1", Value(0.0), - "Tangential distortion 1(double)").asDouble(); + "Tangential distortion 1(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 3) = (float)config.check("p2", Value(0.0), - "Tangential distortion 2(double)").asDouble(); + "Tangential distortion 2(double)").asFloat64(); _needInit = true; return true; diff --git a/src/modules/camCalib/src/SphericalCalibTool.cpp b/src/modules/camCalib/src/SphericalCalibTool.cpp index fce4a93aa8..95a7684b6a 100644 --- a/src/modules/camCalib/src/SphericalCalibTool.cpp +++ b/src/modules/camCalib/src/SphericalCalibTool.cpp @@ -52,22 +52,22 @@ bool SphericalCalibTool::configure (Searchable &config){ // Defaults will correspond to a view field of 90 deg. _calibImgSize.width = config.check("w", Value(320), - "Image width for which calibration parameters were calculated (int)").asInt(); + "Image width for which calibration parameters were calculated (int)").asInt32(); _calibImgSize.height = config.check("h", Value(240), - "Image height for which calibration parameters were calculated (int)").asInt(); + "Image height for which calibration parameters were calculated (int)").asInt32(); _drawCenterCross = config.check("drawCenterCross", Value(0), - "Draw a cross at calibration center (int [0|1]).").asInt()!=0; - - _fx = config.check("fx", Value(320.0), "Focal distance (on horizontal pixel size units) (double)").asDouble(); - _fy = config.check("fy", Value(240.0), "Focal distance (on vertical pixel size units) (double)").asDouble(); - _cx = config.check("cx", Value(320.0), "Image center (on horizontal pixel size units) (double)").asDouble(); - _cy = config.check("cy", Value(240.0), "Image center (on vertical pixel size units) (double)").asDouble(); - _k1 = config.check("k1", Value(0.0), "Radial distortion (first parameter) (double)").asDouble(); - _k2 = config.check("k2", Value(0.0), "Radial distortion (second parameter) (double)").asDouble(); - _p1 = config.check("p1", Value(0.0), "Tangential distortion (first parameter) (double)").asDouble(); - _p2 = config.check("p2", Value(0.0), "Tangential distortion (second parameter) (double)").asDouble(); + "Draw a cross at calibration center (int [0|1]).").asInt32()!=0; + + _fx = config.check("fx", Value(320.0), "Focal distance (on horizontal pixel size units) (double)").asFloat64(); + _fy = config.check("fy", Value(240.0), "Focal distance (on vertical pixel size units) (double)").asFloat64(); + _cx = config.check("cx", Value(320.0), "Image center (on horizontal pixel size units) (double)").asFloat64(); + _cy = config.check("cy", Value(240.0), "Image center (on vertical pixel size units) (double)").asFloat64(); + _k1 = config.check("k1", Value(0.0), "Radial distortion (first parameter) (double)").asFloat64(); + _k2 = config.check("k2", Value(0.0), "Radial distortion (second parameter) (double)").asFloat64(); + _p1 = config.check("p1", Value(0.0), "Tangential distortion (first parameter) (double)").asFloat64(); + _p2 = config.check("p2", Value(0.0), "Tangential distortion (second parameter) (double)").asFloat64(); //check to see if the value is read correctly without caring about the default values. if ( !config.check("drawCenterCross") ) { stopConfig("drawCenterCross"); return false; } diff --git a/src/modules/camCalibWithPose/src/CamCalibModule.cpp b/src/modules/camCalibWithPose/src/CamCalibModule.cpp index 36b68006e3..7f2d4d78ad 100644 --- a/src/modules/camCalibWithPose/src/CamCalibModule.cpp +++ b/src/modules/camCalibWithPose/src/CamCalibModule.cpp @@ -78,15 +78,15 @@ void CamCalibPort::onRead(ImageOf &yrpImgIn) Bottle& b = rpyPort.prepare(); b.clear(); - b.addDouble(roll); - b.addDouble(pitch); - b.addDouble(yaw); - b.addDouble(backdoorRoll); - b.addDouble(backdoorPitch); - b.addDouble(backdoorYaw); - b.addDouble(backdoorRoll - roll); - b.addDouble(backdoorPitch - pitch); - b.addDouble(backdoorYaw - yaw); + b.addFloat64(roll); + b.addFloat64(pitch); + b.addFloat64(yaw); + b.addFloat64(backdoorRoll); + b.addFloat64(backdoorPitch); + b.addFloat64(backdoorYaw); + b.addFloat64(backdoorRoll - roll); + b.addFloat64(backdoorPitch - pitch); + b.addFloat64(backdoorYaw - yaw); rpyPort.write(); @@ -279,8 +279,8 @@ bool CamCalibPort::selectBottleFromMap(double time, bottle->clear(); for(int i = 0; i < it_prev->second.size(); ++i) { if(i < 3) { - double x0 = it_prev->second.get(i).asDouble(); - double x1 = it_next->second.get(i).asDouble(); + double x0 = it_prev->second.get(i).asFloat64(); + double x1 = it_next->second.get(i).asFloat64(); double t0 = it_prev->first; double t1 = it_next->first; double tx = time; @@ -291,8 +291,8 @@ bool CamCalibPort::selectBottleFromMap(double time, xx = x0 + (tx - t0)*(x1 - x0)/(t1 - t0); } else { - double v0 = it_prev->second.get(i+6).asDouble(); - double v1 = it_next->second.get(i+6).asDouble(); + double v0 = it_prev->second.get(i+6).asFloat64(); + double v1 = it_next->second.get(i+6).asFloat64(); double a = (v1 - v0) / (t1 - t0); if (fabs(v1 - v0) > 30) { @@ -320,7 +320,7 @@ bool CamCalibPort::selectBottleFromMap(double time, } } - bottle->addDouble(xx); + bottle->addFloat64(xx); } else { bottle->add(it_prev->second.get(i)); } @@ -359,21 +359,21 @@ bool CamCalibPort::updatePose(double time) } } - double tix = useTorso ? m_curr_t_encs.get(1).asDouble()/180.0*M_PI : 0; // torso roll - double tiy = useTorso ? -m_curr_t_encs.get(2).asDouble()/180.0*M_PI : 0; // torso pitch - double tiz = useTorso ? -m_curr_t_encs.get(0).asDouble()/180.0*M_PI : 0; // torso yaw + double tix = useTorso ? m_curr_t_encs.get(1).asFloat64()/180.0*M_PI : 0; // torso roll + double tiy = useTorso ? -m_curr_t_encs.get(2).asFloat64()/180.0*M_PI : 0; // torso pitch + double tiz = useTorso ? -m_curr_t_encs.get(0).asFloat64()/180.0*M_PI : 0; // torso yaw - double nix = -m_curr_h_encs.get(1).asDouble()/180.0*M_PI; // neck roll - double niy = m_curr_h_encs.get(0).asDouble()/180.0*M_PI; // neck pitch - double niz = m_curr_h_encs.get(2).asDouble()/180.0*M_PI; // neck yaw + double nix = -m_curr_h_encs.get(1).asFloat64()/180.0*M_PI; // neck roll + double niy = m_curr_h_encs.get(0).asFloat64()/180.0*M_PI; // neck pitch + double niz = m_curr_h_encs.get(2).asFloat64()/180.0*M_PI; // neck yaw - double t = useEyes ? m_curr_h_encs.get(3).asDouble()/180.0*M_PI : 0; // eye tilt - double vs = useEyes ? m_curr_h_encs.get(4).asDouble()/180.0*M_PI : 0; // eye version - double vg = useEyes ? m_curr_h_encs.get(5).asDouble()/180.0*M_PI : 0; // eye vergence + double t = useEyes ? m_curr_h_encs.get(3).asFloat64()/180.0*M_PI : 0; // eye tilt + double vs = useEyes ? m_curr_h_encs.get(4).asFloat64()/180.0*M_PI : 0; // eye version + double vg = useEyes ? m_curr_h_encs.get(5).asFloat64()/180.0*M_PI : 0; // eye vergence - double imu_x = useIMU ? m_curr_imu.get(0).asDouble()/180.0*M_PI : 0; // imu roll - double imu_y = useIMU ? m_curr_imu.get(1).asDouble()/180.0*M_PI : 0; // imu pitch - double imu_z = useIMU ? m_curr_imu.get(2).asDouble()/180.0*M_PI : 0; // imu yaw + double imu_x = useIMU ? m_curr_imu.get(0).asFloat64()/180.0*M_PI : 0; // imu roll + double imu_y = useIMU ? m_curr_imu.get(1).asFloat64()/180.0*M_PI : 0; // imu pitch + double imu_z = useIMU ? m_curr_imu.get(2).asFloat64()/180.0*M_PI : 0; // imu yaw // Torso rotation matrix @@ -530,7 +530,7 @@ bool CamCalibModule::configure(yarp::os::ResourceFinder &rf) string str = rf.check("name", Value("/camCalib"), "module name (string)").asString(); setName(str.c_str()); // modulePortName - double maxDelay = rf.check("maxDelay", Value(0.010), "Max delay between image and encoders").asDouble(); + double maxDelay = rf.check("maxDelay", Value(0.010), "Max delay between image and encoders").asFloat64(); // pass configuration over to bottle Bottle botConfig(rf.toString()); @@ -575,7 +575,7 @@ bool CamCalibModule::configure(yarp::os::ResourceFinder &rf) if (yarp::os::Network::exists(getName("/conf"))) { yWarning() << "port " << getName("/conf") << " already in use"; } - _prtImgIn.setSaturation(rf.check("saturation",Value(1.0)).asDouble()); + _prtImgIn.setSaturation(rf.check("saturation",Value(1.0)).asFloat64()); _prtImgIn.open(getName("/in")); _prtImgIn.setPointers(&_prtImgOut,_calibTool); _prtImgIn.setVerbose(rf.check("verbose")); @@ -687,16 +687,16 @@ bool CamCalibModule::respond(const Bottle& command, Bottle& reply) reply.addString("quitting"); return false; } else if (command.get(0).asString()=="sat" || command.get(0).asString()=="saturation") { - double satVal = command.get(1).asDouble(); + double satVal = command.get(1).asFloat64(); _prtImgIn.setSaturation(satVal); reply.addString("ok"); } else if (command.get(0).asString()=="filt") { - _prtImgIn.filter_enable = command.get(1).asInt(); + _prtImgIn.filter_enable = command.get(1).asInt32(); } else if (command.get(0).asString()=="cf1") { - _prtImgIn.cf1 = command.get(1).asDouble(); + _prtImgIn.cf1 = command.get(1).asFloat64(); } else if (command.get(0).asString()=="cf2") { - _prtImgIn.cf2 = command.get(1).asDouble(); + _prtImgIn.cf2 = command.get(1).asFloat64(); } else { yError() << "command not known - type help for more info"; } diff --git a/src/modules/camCalibWithPose/src/PinholeCalibTool.cpp b/src/modules/camCalibWithPose/src/PinholeCalibTool.cpp index 6041cd9996..8a271c4671 100644 --- a/src/modules/camCalibWithPose/src/PinholeCalibTool.cpp +++ b/src/modules/camCalibWithPose/src/PinholeCalibTool.cpp @@ -54,32 +54,32 @@ bool PinholeCalibTool::configure (Searchable &config){ _calibImgSize.width = config.check("w", Value(320), - "Image width for which calibration parameters were calculated (int)").asInt(); + "Image width for which calibration parameters were calculated (int)").asInt32(); _calibImgSize.height = config.check("h", Value(240), - "Image height for which calibration parameters were calculated (int)").asInt(); + "Image height for which calibration parameters were calculated (int)").asInt32(); _drawCenterCross = config.check("drawCenterCross", Value(0), - "Draw a cross at calibration center (int [0|1]).").asInt()!=0; + "Draw a cross at calibration center (int [0|1]).").asInt32()!=0; CV_MAT_ELEM( *_intrinsic_matrix , float, 0, 0) = (float)config.check("fx", Value(320.0), - "Focal length x (double)").asDouble(); + "Focal length x (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 0, 1) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 0, 2) = (float)config.check("cx", Value(160.0), - "Principal point x (double)").asDouble(); + "Principal point x (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 0) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 1) = (float)config.check("fy", Value(320.0), - "Focal length y (double)").asDouble(); + "Focal length y (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 2) = (float)config.check("cy", Value(120.0), - "Principal point y (double)").asDouble(); + "Principal point y (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 0) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 1) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 2) = 1.0f; @@ -99,10 +99,10 @@ bool PinholeCalibTool::configure (Searchable &config){ if ( !config.check("p2") ) { stopConfig("p2"); return false;} - fprintf(stdout,"fx=%g\n",config.find("fx").asDouble()); - fprintf(stdout,"fy=%g\n",config.find("fy").asDouble()); - fprintf(stdout,"cx=%g\n",config.find("cx").asDouble()); - fprintf(stdout,"cy=%g\n",config.find("cy").asDouble()); + fprintf(stdout,"fx=%g\n",config.find("fx").asFloat64()); + fprintf(stdout,"fy=%g\n",config.find("fy").asFloat64()); + fprintf(stdout,"cx=%g\n",config.find("cx").asFloat64()); + fprintf(stdout,"cy=%g\n",config.find("cy").asFloat64()); // copy to scaled matrix ;) @@ -119,16 +119,16 @@ bool PinholeCalibTool::configure (Searchable &config){ /* init the distortion coeffs */ CV_MAT_ELEM( *_distortion_coeffs, float, 0, 0) = (float)config.check("k1", Value(0.0), - "Radial distortion 1(double)").asDouble(); + "Radial distortion 1(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 1) = (float)config.check("k2", Value(0.0), - "Radial distortion 2(double)").asDouble(); + "Radial distortion 2(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 2) = (float)config.check("p1", Value(0.0), - "Tangential distortion 1(double)").asDouble(); + "Tangential distortion 1(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 3) = (float)config.check("p2", Value(0.0), - "Tangential distortion 2(double)").asDouble(); + "Tangential distortion 2(double)").asFloat64(); _needInit = true; return true; diff --git a/src/modules/camCalibWithPose/src/SphericalCalibTool.cpp b/src/modules/camCalibWithPose/src/SphericalCalibTool.cpp index 37f3ba8f18..8ef89fcc67 100644 --- a/src/modules/camCalibWithPose/src/SphericalCalibTool.cpp +++ b/src/modules/camCalibWithPose/src/SphericalCalibTool.cpp @@ -52,22 +52,22 @@ bool SphericalCalibTool::configure (Searchable &config){ // Defaults will correspond to a view field of 90 deg. _calibImgSize.width = config.check("w", Value(320), - "Image width for which calibration parameters were calculated (int)").asInt(); + "Image width for which calibration parameters were calculated (int)").asInt32(); _calibImgSize.height = config.check("h", Value(240), - "Image height for which calibration parameters were calculated (int)").asInt(); + "Image height for which calibration parameters were calculated (int)").asInt32(); _drawCenterCross = config.check("drawCenterCross", Value(0), - "Draw a cross at calibration center (int [0|1]).").asInt()!=0; - - _fx = config.check("fx", Value(320.0), "Focal distance (on horizontal pixel size units) (double)").asDouble(); - _fy = config.check("fy", Value(240.0), "Focal distance (on vertical pixel size units) (double)").asDouble(); - _cx = config.check("cx", Value(320.0), "Image center (on horizontal pixel size units) (double)").asDouble(); - _cy = config.check("cy", Value(240.0), "Image center (on vertical pixel size units) (double)").asDouble(); - _k1 = config.check("k1", Value(0.0), "Radial distortion (first parameter) (double)").asDouble(); - _k2 = config.check("k2", Value(0.0), "Radial distortion (second parameter) (double)").asDouble(); - _p1 = config.check("p1", Value(0.0), "Tangential distortion (first parameter) (double)").asDouble(); - _p2 = config.check("p2", Value(0.0), "Tangential distortion (second parameter) (double)").asDouble(); + "Draw a cross at calibration center (int [0|1]).").asInt32()!=0; + + _fx = config.check("fx", Value(320.0), "Focal distance (on horizontal pixel size units) (double)").asFloat64(); + _fy = config.check("fy", Value(240.0), "Focal distance (on vertical pixel size units) (double)").asFloat64(); + _cx = config.check("cx", Value(320.0), "Image center (on horizontal pixel size units) (double)").asFloat64(); + _cy = config.check("cy", Value(240.0), "Image center (on vertical pixel size units) (double)").asFloat64(); + _k1 = config.check("k1", Value(0.0), "Radial distortion (first parameter) (double)").asFloat64(); + _k2 = config.check("k2", Value(0.0), "Radial distortion (second parameter) (double)").asFloat64(); + _p1 = config.check("p1", Value(0.0), "Tangential distortion (first parameter) (double)").asFloat64(); + _p2 = config.check("p2", Value(0.0), "Tangential distortion (second parameter) (double)").asFloat64(); //check to see if the value is read correctly without caring about the default values. if ( !config.check("drawCenterCross") ) { stopConfig("drawCenterCross"); return false; } diff --git a/src/modules/cartesianInterfaceControl/main.cpp b/src/modules/cartesianInterfaceControl/main.cpp index 7c1acf299c..604c920cc7 100644 --- a/src/modules/cartesianInterfaceControl/main.cpp +++ b/src/modules/cartesianInterfaceControl/main.cpp @@ -189,11 +189,11 @@ class CtrlThread : public PeriodicThread { iarm->storeContext(&startup_context_id); // set trajectory time - defaultExecTime = rf.check("T", Value(2.0)).asDouble(); + defaultExecTime = rf.check("T", Value(2.0)).asFloat64(); Bottle info; iarm->getInfo(info); - double hwver = info.find("arm_version").asDouble(); + double hwver = info.find("arm_version").asFloat64(); printf("Detected arm kinematics version %g\n", hwver); map torsoJointsRemap{{ "pitch", 0 }, { "roll", 1 }, { "yaw", 2 }}; @@ -242,7 +242,7 @@ class CtrlThread : public PeriodicThread { // set cartesian tolerance if (rf.check("tol")) - iarm->setInTargetTol(rf.find("tol").asDouble()); + iarm->setInTargetTol(rf.find("tol").asFloat64()); // latch the controller context for our task iarm->storeContext(&task_context_id); @@ -276,11 +276,11 @@ class CtrlThread : public PeriodicThread { if (Bottle* b = port_xd.read(false)) { if (b->size() >= 3) { for (int i = 0; i < 3; i++) - xd[i] = b->get(i).asDouble(); + xd[i] = b->get(i).asFloat64(); if (ctrlCompletePose && (b->size() >= 7)) { for (int i = 0; i < 4; i++) - od[i] = b->get(3 + i).asDouble(); + od[i] = b->get(3 + i).asFloat64(); } if (reinstateContext) diff --git a/src/modules/ctpService/main.cpp b/src/modules/ctpService/main.cpp index 6c4813cc8f..dcf77fc87c 100644 --- a/src/modules/ctpService/main.cpp +++ b/src/modules/ctpService/main.cpp @@ -117,13 +117,13 @@ using namespace yarp::dev; using namespace yarp::math; using namespace iCub::ctrl; -#define VCTP_TIME yarp::os::createVocab('t','i','m','e') -#define VCTP_OFFSET yarp::os::createVocab('o','f','f') -#define VCTP_CMD_NOW yarp::os::createVocab('c','t','p','n') -#define VCTP_CMD_QUEUE yarp::os::createVocab('c','t','p','q') -#define VCTP_CMD_FILE yarp::os::createVocab('c','t','p','f') -#define VCTP_POSITION yarp::os::createVocab('p','o','s') -#define VCTP_WAIT yarp::os::createVocab('w','a','i','t') +#define VCTP_TIME yarp::os::createVocab32('t','i','m','e') +#define VCTP_OFFSET yarp::os::createVocab32('o','f','f') +#define VCTP_CMD_NOW yarp::os::createVocab32('c','t','p','n') +#define VCTP_CMD_QUEUE yarp::os::createVocab32('c','t','p','q') +#define VCTP_CMD_FILE yarp::os::createVocab32('c','t','p','f') +#define VCTP_POSITION yarp::os::createVocab32('p','o','s') +#define VCTP_WAIT yarp::os::createVocab32('w','a','i','t') #define VEL_FILT_SIZE 10 #define VEL_FILT_THRES 1.0 @@ -449,10 +449,10 @@ class VelocityThread: public Thread Bottle c,r; c.addString("gain"); - c.addInt(i); + c.addInt32(i); if (rf->check(gainStr)) { - c.addDouble(rf->find(gainStr).asDouble()); + c.addFloat64(rf->find(gainStr).asFloat64()); p->write(c,r); i++; } @@ -475,10 +475,10 @@ class VelocityThread: public Thread Bottle c,r; c.addString("svel"); - c.addInt(i); + c.addInt32(i); if (rf->check(svelStr)) { - c.addDouble(rf->find(svelStr).asDouble()); + c.addFloat64(rf->find(svelStr).asFloat64()); p->write(c,r); i++; } @@ -506,11 +506,11 @@ class VelocityThread: public Thread if (b.size()>2) { - time=b.get(1).asDouble(); + time=b.get(1).asFloat64(); v.resize(b.size()-2); for (size_t i=0; igetCmd().resize(posCmd->size()); for(int k=0;ksize();k++) - (*action)->getCmd()[k]=posCmd->get(k).asDouble(); + (*action)->getCmd()[k]=posCmd->get(k).asFloat64(); (*action)->getOffset()=offset; (*action)->getTime()=time; @@ -862,9 +862,9 @@ class scriptModule: public RFModule bool ret; if (command.size()!=0) { - switch (command.get(0).asVocab()) + switch (command.get(0).asVocab32()) { - case yarp::os::createVocab('h','e','l','p'): + case yarp::os::createVocab32('h','e','l','p'): { cout << "Available commands:" << endl; cout<<"Queue command:\n"; @@ -873,7 +873,7 @@ class scriptModule: public RFModule cout<<"[ctpq] [time] seconds [off] j [pos] (list)\n"; cout<<"Load sequence from file:\n"; cout<<"[ctpf] filename\n"; - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); return true; } case VCTP_CMD_NOW: @@ -901,7 +901,7 @@ class scriptModule: public RFModule } else { - reply.addVocab(Vocab::encode("nack")); + reply.addVocab32("nack"); return false; } } diff --git a/src/modules/dualCamCalib/src/DualCamCalibModule.cpp b/src/modules/dualCamCalib/src/DualCamCalibModule.cpp index afbebb1c5a..2829922cb5 100644 --- a/src/modules/dualCamCalib/src/DualCamCalibModule.cpp +++ b/src/modules/dualCamCalib/src/DualCamCalibModule.cpp @@ -37,7 +37,7 @@ bool CamCalibModule::configure(yarp::os::ResourceFinder &rf) if (rf.check("fps")) { - requested_fps=rf.find("fps").asDouble(); + requested_fps=rf.find("fps").asFloat64(); yInfo() << "Module will run at " << requested_fps; } else diff --git a/src/modules/dualCamCalib/src/PinholeCalibTool.cpp b/src/modules/dualCamCalib/src/PinholeCalibTool.cpp index d8f24d1c4a..9f0db27d07 100644 --- a/src/modules/dualCamCalib/src/PinholeCalibTool.cpp +++ b/src/modules/dualCamCalib/src/PinholeCalibTool.cpp @@ -54,32 +54,32 @@ bool PinholeCalibTool::configure (Searchable &config){ _calibImgSize.width = config.check("w", Value(320), - "Image width for which calibration parameters were calculated (int)").asInt(); + "Image width for which calibration parameters were calculated (int)").asInt32(); _calibImgSize.height = config.check("h", Value(240), - "Image height for which calibration parameters were calculated (int)").asInt(); + "Image height for which calibration parameters were calculated (int)").asInt32(); _drawCenterCross = config.check("drawCenterCross", Value(0), - "Draw a cross at calibration center (int [0|1]).").asInt()!=0; + "Draw a cross at calibration center (int [0|1]).").asInt32()!=0; CV_MAT_ELEM( *_intrinsic_matrix , float, 0, 0) = (float)config.check("fx", Value(320.0), - "Focal length x (double)").asDouble(); + "Focal length x (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 0, 1) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 0, 2) = (float)config.check("cx", Value(160.0), - "Principal point x (double)").asDouble(); + "Principal point x (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 0) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 1) = (float)config.check("fy", Value(320.0), - "Focal length y (double)").asDouble(); + "Focal length y (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 1, 2) = (float)config.check("cy", Value(120.0), - "Principal point y (double)").asDouble(); + "Principal point y (double)").asFloat64(); CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 0) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 1) = 0.0f; CV_MAT_ELEM( *_intrinsic_matrix, float, 2, 2) = 1.0f; @@ -99,10 +99,10 @@ bool PinholeCalibTool::configure (Searchable &config){ if ( !config.check("p2") ) { stopConfig("p2"); return false;} - fprintf(stdout,"fx=%g\n",config.find("fx").asDouble()); - fprintf(stdout,"fy=%g\n",config.find("fy").asDouble()); - fprintf(stdout,"cx=%g\n",config.find("cx").asDouble()); - fprintf(stdout,"cy=%g\n",config.find("cy").asDouble()); + fprintf(stdout,"fx=%g\n",config.find("fx").asFloat64()); + fprintf(stdout,"fy=%g\n",config.find("fy").asFloat64()); + fprintf(stdout,"cx=%g\n",config.find("cx").asFloat64()); + fprintf(stdout,"cy=%g\n",config.find("cy").asFloat64()); // copy to scaled matrix ;) @@ -119,16 +119,16 @@ bool PinholeCalibTool::configure (Searchable &config){ /* init the distortion coeffs */ CV_MAT_ELEM( *_distortion_coeffs, float, 0, 0) = (float)config.check("k1", Value(0.0), - "Radial distortion 1(double)").asDouble(); + "Radial distortion 1(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 1) = (float)config.check("k2", Value(0.0), - "Radial distortion 2(double)").asDouble(); + "Radial distortion 2(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 2) = (float)config.check("p1", Value(0.0), - "Tangential distortion 1(double)").asDouble(); + "Tangential distortion 1(double)").asFloat64(); CV_MAT_ELEM( *_distortion_coeffs, float, 0, 3) = (float)config.check("p2", Value(0.0), - "Tangential distortion 2(double)").asDouble(); + "Tangential distortion 2(double)").asFloat64(); _needInit = true; return true; diff --git a/src/modules/dualCamCalib/src/SphericalCalibTool.cpp b/src/modules/dualCamCalib/src/SphericalCalibTool.cpp index fce4a93aa8..95a7684b6a 100644 --- a/src/modules/dualCamCalib/src/SphericalCalibTool.cpp +++ b/src/modules/dualCamCalib/src/SphericalCalibTool.cpp @@ -52,22 +52,22 @@ bool SphericalCalibTool::configure (Searchable &config){ // Defaults will correspond to a view field of 90 deg. _calibImgSize.width = config.check("w", Value(320), - "Image width for which calibration parameters were calculated (int)").asInt(); + "Image width for which calibration parameters were calculated (int)").asInt32(); _calibImgSize.height = config.check("h", Value(240), - "Image height for which calibration parameters were calculated (int)").asInt(); + "Image height for which calibration parameters were calculated (int)").asInt32(); _drawCenterCross = config.check("drawCenterCross", Value(0), - "Draw a cross at calibration center (int [0|1]).").asInt()!=0; - - _fx = config.check("fx", Value(320.0), "Focal distance (on horizontal pixel size units) (double)").asDouble(); - _fy = config.check("fy", Value(240.0), "Focal distance (on vertical pixel size units) (double)").asDouble(); - _cx = config.check("cx", Value(320.0), "Image center (on horizontal pixel size units) (double)").asDouble(); - _cy = config.check("cy", Value(240.0), "Image center (on vertical pixel size units) (double)").asDouble(); - _k1 = config.check("k1", Value(0.0), "Radial distortion (first parameter) (double)").asDouble(); - _k2 = config.check("k2", Value(0.0), "Radial distortion (second parameter) (double)").asDouble(); - _p1 = config.check("p1", Value(0.0), "Tangential distortion (first parameter) (double)").asDouble(); - _p2 = config.check("p2", Value(0.0), "Tangential distortion (second parameter) (double)").asDouble(); + "Draw a cross at calibration center (int [0|1]).").asInt32()!=0; + + _fx = config.check("fx", Value(320.0), "Focal distance (on horizontal pixel size units) (double)").asFloat64(); + _fy = config.check("fy", Value(240.0), "Focal distance (on vertical pixel size units) (double)").asFloat64(); + _cx = config.check("cx", Value(320.0), "Image center (on horizontal pixel size units) (double)").asFloat64(); + _cy = config.check("cy", Value(240.0), "Image center (on vertical pixel size units) (double)").asFloat64(); + _k1 = config.check("k1", Value(0.0), "Radial distortion (first parameter) (double)").asFloat64(); + _k2 = config.check("k2", Value(0.0), "Radial distortion (second parameter) (double)").asFloat64(); + _p1 = config.check("p1", Value(0.0), "Tangential distortion (first parameter) (double)").asFloat64(); + _p2 = config.check("p2", Value(0.0), "Tangential distortion (second parameter) (double)").asFloat64(); //check to see if the value is read correctly without caring about the default values. if ( !config.check("drawCenterCross") ) { stopConfig("drawCenterCross"); return false; } diff --git a/src/modules/gravityCompensator/main.cpp b/src/modules/gravityCompensator/main.cpp index 8dc53b0bd6..d89dc0c59a 100644 --- a/src/modules/gravityCompensator/main.cpp +++ b/src/modules/gravityCompensator/main.cpp @@ -201,7 +201,7 @@ class gravityModuleCompensator: public RFModule name = "gravityCompensator"; if (rf.check("period")) - rate = rf.find("period").asInt(); + rate = rf.find("period").asInt32(); else rate = 20; if (rf.check("rate")) @@ -401,9 +401,9 @@ class gravityModuleCompensator: public RFModule bool respond(const Bottle& command, Bottle& reply) override { - reply.addVocab(Vocab::encode("many")); - reply.addString("Available commands:"); - reply.addString("calib all"); + reply.addVocab32("many"); + reply.addString("Available commands:"); + reply.addString("calib all"); Bottle position_bot; string helpMessage = getName() + @@ -418,7 +418,7 @@ class gravityModuleCompensator: public RFModule if (command.get(0).asString()=="help") { cout << helpMessage; - reply.addVocab(Vocab::encode("many")); + reply.addVocab32("many"); reply.addString(" commands are: \n" ); reply.addString(helpMessage.c_str()); } diff --git a/src/modules/iKinCartesianSolver/main.cpp b/src/modules/iKinCartesianSolver/main.cpp index e03b300f9c..c803e14d01 100644 --- a/src/modules/iKinCartesianSolver/main.cpp +++ b/src/modules/iKinCartesianSolver/main.cpp @@ -189,7 +189,7 @@ class GenericLinIneqConstr : public iKinLinIneqConstr { GenericLinIneqConstr(iKinChain* chain_, Searchable& options) : chain(chain_), C_orig(0, chain_->getN()), iKinLinIneqConstr() { if (options.check("LIC_num")) { - auto LIC_num = options.find("LIC_num").asInt(); + auto LIC_num = options.find("LIC_num").asInt32(); if (LIC_num > 0) { for (auto i = 0; i < LIC_num; i++) { ostringstream tag; @@ -210,10 +210,10 @@ class GenericLinIneqConstr : public iKinLinIneqConstr { } C_orig = pile(C_orig, zeros(chain->getN())); for (auto i = 0; i < row->size(); i++) { - C_orig(C_orig.rows() - 1, i) = row->get(i).asDouble(); + C_orig(C_orig.rows() - 1, i) = row->get(i).asFloat64(); } - lB_orig = cat(lB_orig, group.check("lB", Value(lowerBoundInf)).asDouble()); - uB_orig = cat(uB_orig, group.check("uB", Value(upperBoundInf)).asDouble()); + lB_orig = cat(lB_orig, group.check("lB", Value(lowerBoundInf)).asFloat64()); + uB_orig = cat(uB_orig, group.check("uB", Value(upperBoundInf)).asFloat64()); } yInfo() << "Detected generic linear inequalities constraints"; @@ -282,7 +282,7 @@ class CustomCartesianSolver : public CartesianSolver { desc->cns = cns.get(); bool failure = false; - desc->num = options.find("NumberOfDrivers").asInt(); + desc->num = options.find("NumberOfDrivers").asInt32(); for (int cnt = 0; cnt < desc->num; cnt++) { ostringstream str; str << "driver_" << cnt; diff --git a/src/modules/iKinGazeCtrl/src/controller.cpp b/src/modules/iKinGazeCtrl/src/controller.cpp index 9112584fa4..d6c8d1651c 100644 --- a/src/modules/iKinGazeCtrl/src/controller.cpp +++ b/src/modules/iKinGazeCtrl/src/controller.cpp @@ -223,9 +223,9 @@ void Controller::notifyEvent(const string &event, const double checkPoint) ev.clear(); ev.addString(event); - ev.addDouble(q_stamp); + ev.addFloat64(q_stamp); if (checkPoint>=0.0) - ev.addDouble(checkPoint); + ev.addFloat64(checkPoint); txInfo_event.update(q_stamp); port_event.setEnvelope(txInfo_event); @@ -302,7 +302,7 @@ void Controller::stopLimb(const bool execStopPosition) ostringstream ss; ss<<"vel_"<size()>=4) { string type=mono->get(0).asString(); - double u=mono->get(1).asDouble(); - double v=mono->get(2).asDouble(); + double u=mono->get(1).asFloat64(); + double v=mono->get(2).asFloat64(); double z; bool ok=false; - if (mono->get(3).isDouble()) + if (mono->get(3).isFloat64()) { - z=mono->get(3).asDouble(); + z=mono->get(3).asFloat64(); ok=true; } else if ((mono->get(3).asString()=="ver") && (mono->size()>=5)) { - double ver=mono->get(4).asDouble(); + double ver=mono->get(4).asFloat64(); z=getDistFromVergence(ver); ok=true; } @@ -567,10 +567,10 @@ void Localizer::handleStereoInput() { if (stereo->size()>=4) { - double ul=stereo->get(0).asDouble(); - double vl=stereo->get(1).asDouble(); - double ur=stereo->get(2).asDouble(); - double vr=stereo->get(3).asDouble(); + double ul=stereo->get(0).asFloat64(); + double vl=stereo->get(1).asFloat64(); + double ur=stereo->get(2).asFloat64(); + double vr=stereo->get(3).asFloat64(); Vector ref(1), fb(1), fp; double u, v; @@ -617,9 +617,9 @@ void Localizer::handleAnglesInput() Vector ang(3); string type=angles->get(0).asString(); - ang[0]=CTRL_DEG2RAD*angles->get(1).asDouble(); - ang[1]=CTRL_DEG2RAD*angles->get(2).asDouble(); - ang[2]=CTRL_DEG2RAD*angles->get(3).asDouble(); + ang[0]=CTRL_DEG2RAD*angles->get(1).asFloat64(); + ang[1]=CTRL_DEG2RAD*angles->get(2).asFloat64(); + ang[2]=CTRL_DEG2RAD*angles->get(3).asFloat64(); Vector xd=get3DPoint(type,ang); commData->port_xd->set_xd(xd); diff --git a/src/modules/iKinGazeCtrl/src/main.cpp b/src/modules/iKinGazeCtrl/src/main.cpp index 4a54a46d70..78d0984d1d 100644 --- a/src/modules/iKinGazeCtrl/src/main.cpp +++ b/src/modules/iKinGazeCtrl/src/main.cpp @@ -746,7 +746,7 @@ class GazeModule: public RFModule lock_guard lg(mutexContext); for (int i=0; isize(); i++) { - int id=contextIdList->get(i).asInt(); + int id=contextIdList->get(i).asInt32(); auto itr=contextMap.find(id); if (itr!=contextMap.end()) contextMap.erase(itr); @@ -765,15 +765,15 @@ class GazeModule: public RFModule Bottle &serverVer=info.addList(); serverVer.addString("server_version"); - serverVer.addDouble(GAZECTRL_SERVER_VER); + serverVer.addFloat64(GAZECTRL_SERVER_VER); Bottle &headVer=info.addList(); headVer.addString("head_version"); - headVer.addDouble(commData.head_version); + headVer.addFloat64(commData.head_version); Bottle &minVer=info.addList(); minVer.addString("min_allowed_vergence"); - minVer.addDouble(CTRL_RAD2DEG*commData.minAllowedVergence); + minVer.addFloat64(CTRL_RAD2DEG*commData.minAllowedVergence); Bottle &events=info.addList(); events.addString("events"); @@ -808,7 +808,7 @@ class GazeModule: public RFModule int r=0; int c=0; for (int i=0; isize(); i++) { - Prj(r,c)=pB->get(i).asDouble(); + Prj(r,c)=pB->get(i).asFloat64(); if (++c>=Prj.cols()) { c=0; @@ -829,7 +829,7 @@ class GazeModule: public RFModule int r=0; int c=0; for (int i=0; isize(); i++) { - Prj(r,c)=pB->get(i).asDouble(); + Prj(r,c)=pB->get(i).asFloat64(); if (++c>=Prj.cols()) { c=0; @@ -846,7 +846,7 @@ class GazeModule: public RFModule { Matrix Prj=zeros(3,4); int w,h; loc->getIntrinsicsMatrix("left",Prj,w,h); - w=options.find("camera_width_left").asInt(); + w=options.find("camera_width_left").asInt32(); loc->setIntrinsicsMatrix("left",Prj,w,h); } @@ -854,7 +854,7 @@ class GazeModule: public RFModule { Matrix Prj=zeros(3,4); int w,h; loc->getIntrinsicsMatrix("left",Prj,w,h); - h=options.find("camera_height_left").asInt(); + h=options.find("camera_height_left").asInt32(); loc->setIntrinsicsMatrix("left",Prj,w,h); } @@ -862,7 +862,7 @@ class GazeModule: public RFModule { Matrix Prj=zeros(3,4); int w,h; loc->getIntrinsicsMatrix("right",Prj,w,h); - w=options.find("camera_width_right").asInt(); + w=options.find("camera_width_right").asInt32(); loc->setIntrinsicsMatrix("right",Prj,w,h); } @@ -870,7 +870,7 @@ class GazeModule: public RFModule { Matrix Prj=zeros(3,4); int w,h; loc->getIntrinsicsMatrix("right",Prj,w,h); - h=options.find("camera_height_right").asInt(); + h=options.find("camera_height_right").asInt32(); loc->setIntrinsicsMatrix("right",Prj,w,h); } @@ -883,7 +883,7 @@ class GazeModule: public RFModule int r=0; int c=0; for (int i=0; isize(); i++) { - HN(r,c)=pB->get(i).asDouble(); + HN(r,c)=pB->get(i).asFloat64(); if (++c>=HN.cols()) { c=0; @@ -912,7 +912,7 @@ class GazeModule: public RFModule int r=0; int c=0; for (int i=0; isize(); i++) { - HN(r,c)=pB->get(i).asDouble(); + HN(r,c)=pB->get(i).asFloat64(); if (++c>=HN.cols()) { c=0; @@ -954,14 +954,14 @@ class GazeModule: public RFModule if (loc->getIntrinsicsMatrix("left",PrjL,wL,hL)) for (int r=0; rgetIntrinsicsMatrix("right",PrjR,wR,hR)) for (int r=0; rgetExtrinsicsMatrix("left",HL)) for (int r=0; rgetExtrinsicsMatrix("right",HR)) for (int r=0; r0) { - switch (command.get(0).asVocab()) + switch (command.get(0).asVocab32()) { //----------------- - case createVocab('g','e','t'): + case createVocab32('g','e','t'): { if (command.size()>1) { - int type=command.get(1).asVocab(); + int type=command.get(1).asVocab32(); - if (type==createVocab('T','n','e','c')) + if (type==createVocab32('T','n','e','c')) { - reply.addVocab(ack); - reply.addDouble(ctrl->getTneck()); + reply.addVocab32(ack); + reply.addFloat64(ctrl->getTneck()); return true; } - else if (type==createVocab('T','e','y','e')) + else if (type==createVocab32('T','e','y','e')) { - reply.addVocab(ack); - reply.addDouble(ctrl->getTeyes()); + reply.addVocab32(ack); + reply.addFloat64(ctrl->getTeyes()); return true; } - else if (type==createVocab('v','o','r')) + else if (type==createVocab32('v','o','r')) { Vector gain=eyesRefGen->getCounterRotGain(); - reply.addVocab(ack); - reply.addDouble(gain[0]); + reply.addVocab32(ack); + reply.addFloat64(gain[0]); return true; } - else if (type==createVocab('o','c','r')) + else if (type==createVocab32('o','c','r')) { Vector gain=eyesRefGen->getCounterRotGain(); - reply.addVocab(ack); - reply.addDouble(gain[1]); + reply.addVocab32(ack); + reply.addFloat64(gain[1]); return true; } - else if (type==createVocab('s','a','c','c')) + else if (type==createVocab32('s','a','c','c')) { - reply.addVocab(ack); - reply.addInt((int)commData.saccadesOn); + reply.addVocab32(ack); + reply.addInt32((int)commData.saccadesOn); return true; } - else if (type==createVocab('s','i','n','h')) + else if (type==createVocab32('s','i','n','h')) { - reply.addVocab(ack); - reply.addDouble(commData.saccadesInhibitionPeriod); + reply.addVocab32(ack); + reply.addFloat64(commData.saccadesInhibitionPeriod); return true; } - else if (type==createVocab('s','a','c','t')) + else if (type==createVocab32('s','a','c','t')) { - reply.addVocab(ack); - reply.addDouble(commData.saccadesActivationAngle); + reply.addVocab32(ack); + reply.addFloat64(commData.saccadesActivationAngle); return true; } - else if (type==createVocab('t','r','a','c')) + else if (type==createVocab32('t','r','a','c')) { - reply.addVocab(ack); - reply.addInt((int)ctrl->getTrackingMode()); + reply.addVocab32(ack); + reply.addInt32((int)ctrl->getTrackingMode()); return true; } - else if (type==createVocab('s','t','a','b')) + else if (type==createVocab32('s','t','a','b')) { - reply.addVocab(ack); - reply.addInt((int)ctrl->getGazeStabilization()); + reply.addVocab32(ack); + reply.addInt32((int)ctrl->getGazeStabilization()); return true; } - else if (type==createVocab('d','o','n','e')) + else if (type==createVocab32('d','o','n','e')) { - reply.addVocab(ack); - reply.addInt((int)ctrl->isMotionDone()); + reply.addVocab32(ack); + reply.addInt32((int)ctrl->isMotionDone()); return true; } - else if (type==createVocab('s','d','o','n')) + else if (type==createVocab32('s','d','o','n')) { - reply.addVocab(ack); - reply.addInt((int)!commData.saccadeUnderway); + reply.addVocab32(ack); + reply.addInt32((int)!commData.saccadeUnderway); return true; } - else if (type==createVocab('p','i','t','c')) + else if (type==createVocab32('p','i','t','c')) { double min_deg,max_deg; slv->getCurNeckPitchRange(min_deg,max_deg); - reply.addVocab(ack); - reply.addDouble(min_deg); - reply.addDouble(max_deg); + reply.addVocab32(ack); + reply.addFloat64(min_deg); + reply.addFloat64(max_deg); return true; } - else if (type==createVocab('r','o','l','l')) + else if (type==createVocab32('r','o','l','l')) { double min_deg,max_deg; slv->getCurNeckRollRange(min_deg,max_deg); - reply.addVocab(ack); - reply.addDouble(min_deg); - reply.addDouble(max_deg); + reply.addVocab32(ack); + reply.addFloat64(min_deg); + reply.addFloat64(max_deg); return true; } - else if (type==createVocab('y','a','w')) + else if (type==createVocab32('y','a','w')) { double min_deg,max_deg; slv->getCurNeckYawRange(min_deg,max_deg); - reply.addVocab(ack); - reply.addDouble(min_deg); - reply.addDouble(max_deg); + reply.addVocab32(ack); + reply.addFloat64(min_deg); + reply.addFloat64(max_deg); return true; } - else if (type==createVocab('e','y','e','s')) + else if (type==createVocab32('e','y','e','s')) { - reply.addVocab(ack); - reply.addDouble(commData.eyesBoundVer); + reply.addVocab32(ack); + reply.addFloat64(commData.eyesBoundVer); return true; } - else if (type==createVocab('n','t','o','l')) + else if (type==createVocab32('n','t','o','l')) { double angle=slv->getNeckAngleUserTolerance(); - reply.addVocab(ack); - reply.addDouble(angle); + reply.addVocab32(ack); + reply.addFloat64(angle); return true; } - else if (type==createVocab('d','e','s')) + else if (type==createVocab32('d','e','s')) { Vector des; if (ctrl->getDesired(des)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(des); return true; } } - else if (type==createVocab('v','e','l')) + else if (type==createVocab32('v','e','l')) { Vector vel; if (ctrl->getVelocity(vel)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(vel); return true; } } - else if ((type==createVocab('p','o','s','e')) && (command.size()>2)) + else if ((type==createVocab32('p','o','s','e')) && (command.size()>2)) { string poseSel=command.get(2).asString(); Vector x; @@ -1453,17 +1453,17 @@ class GazeModule: public RFModule if (ctrl->getPose(poseSel,x,stamp)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(x); Bottle &bStamp=reply.addList(); - bStamp.addInt(stamp.getCount()); - bStamp.addDouble(stamp.getTime()); + bStamp.addInt32(stamp.getCount()); + bStamp.addFloat64(stamp.getTime()); return true; } } - else if ((type==createVocab('2','D')) && (command.size()>2)) + else if ((type==createVocab32('2','D')) && (command.size()>2)) { if (Bottle *bOpt=command.get(2).asList()) { @@ -1471,67 +1471,67 @@ class GazeModule: public RFModule { Vector x(3); string eye=bOpt->get(0).asString(); - x[0]=bOpt->get(1).asDouble(); - x[1]=bOpt->get(2).asDouble(); - x[2]=bOpt->get(3).asDouble(); + x[0]=bOpt->get(1).asFloat64(); + x[1]=bOpt->get(2).asFloat64(); + x[2]=bOpt->get(3).asFloat64(); Vector px; if (loc->projectPoint(eye,x,px)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(px); return true; } } } } - else if ((type==createVocab('3','D')) && (command.size()>3)) + else if ((type==createVocab32('3','D')) && (command.size()>3)) { - int subType=command.get(2).asVocab(); - if (subType==createVocab('m','o','n','o')) + int subType=command.get(2).asVocab32(); + if (subType==createVocab32('m','o','n','o')) { if (Bottle *bOpt=command.get(3).asList()) { if (bOpt->size()>3) { string eye=bOpt->get(0).asString(); - double u=bOpt->get(1).asDouble(); - double v=bOpt->get(2).asDouble(); - double z=bOpt->get(3).asDouble(); + double u=bOpt->get(1).asFloat64(); + double v=bOpt->get(2).asFloat64(); + double z=bOpt->get(3).asFloat64(); Vector x; if (loc->projectPoint(eye,u,v,z,x)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(x); return true; } } } } - else if (subType==createVocab('s','t','e','r')) + else if (subType==createVocab32('s','t','e','r')) { if (Bottle *bOpt=command.get(3).asList()) { if (bOpt->size()>3) { Vector pxl(2),pxr(2); - pxl[0]=bOpt->get(0).asDouble(); - pxl[1]=bOpt->get(1).asDouble(); - pxr[0]=bOpt->get(2).asDouble(); - pxr[1]=bOpt->get(3).asDouble(); + pxl[0]=bOpt->get(0).asFloat64(); + pxl[1]=bOpt->get(1).asFloat64(); + pxr[0]=bOpt->get(2).asFloat64(); + pxr[1]=bOpt->get(3).asFloat64(); Vector x; if (loc->triangulatePoint(pxl,pxr,x)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(x); return true; } } } } - else if (subType==createVocab('p','r','o','j')) + else if (subType==createVocab32('p','r','o','j')) { if (Bottle *bOpt=command.get(3).asList()) { @@ -1539,24 +1539,24 @@ class GazeModule: public RFModule { Vector plane(4); string eye=bOpt->get(0).asString(); - double u=bOpt->get(1).asDouble(); - double v=bOpt->get(2).asDouble(); - plane[0]=bOpt->get(3).asDouble(); - plane[1]=bOpt->get(4).asDouble(); - plane[2]=bOpt->get(5).asDouble(); - plane[3]=bOpt->get(6).asDouble(); + double u=bOpt->get(1).asFloat64(); + double v=bOpt->get(2).asFloat64(); + plane[0]=bOpt->get(3).asFloat64(); + plane[1]=bOpt->get(4).asFloat64(); + plane[2]=bOpt->get(5).asFloat64(); + plane[3]=bOpt->get(6).asFloat64(); Vector x; if (loc->projectPoint(eye,u,v,plane,x)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(x); return true; } } } } - else if (subType==createVocab('a','n','g')) + else if (subType==createVocab32('a','n','g')) { if (Bottle *bOpt=command.get(3).asList()) { @@ -1564,61 +1564,61 @@ class GazeModule: public RFModule { Vector ang(3); string type=bOpt->get(0).asString(); - ang[0]=CTRL_DEG2RAD*bOpt->get(1).asDouble(); - ang[1]=CTRL_DEG2RAD*bOpt->get(2).asDouble(); - ang[2]=CTRL_DEG2RAD*bOpt->get(3).asDouble(); + ang[0]=CTRL_DEG2RAD*bOpt->get(1).asFloat64(); + ang[1]=CTRL_DEG2RAD*bOpt->get(2).asFloat64(); + ang[2]=CTRL_DEG2RAD*bOpt->get(3).asFloat64(); Vector x=loc->get3DPoint(type,ang); - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(x); return true; } } } } - else if ((type==createVocab('a','n','g')) && (command.size()>2)) + else if ((type==createVocab32('a','n','g')) && (command.size()>2)) { if (Bottle *bOpt=command.get(2).asList()) { if (bOpt->size()>2) { Vector x(3); - x[0]=bOpt->get(0).asDouble(); - x[1]=bOpt->get(1).asDouble(); - x[2]=bOpt->get(2).asDouble(); + x[0]=bOpt->get(0).asFloat64(); + x[1]=bOpt->get(1).asFloat64(); + x[2]=bOpt->get(2).asFloat64(); Vector ang=CTRL_RAD2DEG*loc->getAbsAngles(x); - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList().read(ang); return true; } } } - else if (type==createVocab('p','i','d')) + else if (type==createVocab32('p','i','d')) { Bottle options; loc->getPidOptions(options); - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList()=options; return true; } - else if (type==createVocab('i','n','f','o')) + else if (type==createVocab32('i','n','f','o')) { Bottle info; if (getInfo(info)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList()=info; return true; } } - else if (type==createVocab('t','w','e','a')) + else if (type==createVocab32('t','w','e','a')) { Bottle options; if (tweakGet(options)) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList()=options; return true; } @@ -1629,95 +1629,95 @@ class GazeModule: public RFModule } //----------------- - case createVocab('s','e','t'): + case createVocab32('s','e','t'): { if (command.size()>2) { - int type=command.get(1).asVocab(); - if (type==createVocab('T','n','e','c')) + int type=command.get(1).asVocab32(); + if (type==createVocab32('T','n','e','c')) { - double execTime=command.get(2).asDouble(); + double execTime=command.get(2).asFloat64(); ctrl->setTneck(execTime); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('T','e','y','e')) + else if (type==createVocab32('T','e','y','e')) { - double execTime=command.get(2).asDouble(); + double execTime=command.get(2).asFloat64(); ctrl->setTeyes(execTime); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('v','o','r')) + else if (type==createVocab32('v','o','r')) { Vector gain=eyesRefGen->getCounterRotGain(); - gain[0]=command.get(2).asDouble(); + gain[0]=command.get(2).asFloat64(); eyesRefGen->setCounterRotGain(gain); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('o','c','r')) + else if (type==createVocab32('o','c','r')) { Vector gain=eyesRefGen->getCounterRotGain(); - gain[1]=command.get(2).asDouble(); + gain[1]=command.get(2).asFloat64(); eyesRefGen->setCounterRotGain(gain); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('s','a','c','c')) + else if (type==createVocab32('s','a','c','c')) { - commData.saccadesOn=(command.get(2).asInt()>0); - reply.addVocab(ack); + commData.saccadesOn=(command.get(2).asInt32()>0); + reply.addVocab32(ack); return true; } - else if (type==createVocab('s','i','n','h')) + else if (type==createVocab32('s','i','n','h')) { - double period=command.get(2).asDouble(); + double period=command.get(2).asFloat64(); commData.saccadesInhibitionPeriod=period; - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('s','a','c','t')) + else if (type==createVocab32('s','a','c','t')) { - double angle=command.get(2).asDouble(); + double angle=command.get(2).asFloat64(); commData.saccadesActivationAngle=angle; - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('n','t','o','l')) + else if (type==createVocab32('n','t','o','l')) { - double angle=command.get(2).asDouble(); + double angle=command.get(2).asFloat64(); slv->setNeckAngleUserTolerance(angle); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('t','r','a','c')) + else if (type==createVocab32('t','r','a','c')) { - bool mode=(command.get(2).asInt()>0); + bool mode=(command.get(2).asInt32()>0); ctrl->setTrackingMode(mode); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (type==createVocab('s','t','a','b')) + else if (type==createVocab32('s','t','a','b')) { - bool mode=(command.get(2).asInt()>0); - reply.addVocab(ctrl->setGazeStabilization(mode)?ack:nack); + bool mode=(command.get(2).asInt32()>0); + reply.addVocab32(ctrl->setGazeStabilization(mode)?ack:nack); return true; } - else if (type==createVocab('p','i','d')) + else if (type==createVocab32('p','i','d')) { if (Bottle *bOpt=command.get(2).asList()) { loc->setPidOptions(*bOpt); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } - else if (type==createVocab('t','w','e','a')) + else if (type==createVocab32('t','w','e','a')) { if (Bottle *bOpt=command.get(2).asList()) { - reply.addVocab(tweakSet(*bOpt)?ack:nack); + reply.addVocab32(tweakSet(*bOpt)?ack:nack); return true; } } @@ -1727,50 +1727,50 @@ class GazeModule: public RFModule } //----------------- - case createVocab('l','o','o','k'): + case createVocab32('l','o','o','k'): { if (command.size()>2) { - int type=command.get(1).asVocab(); - if (type==createVocab('3','D')) + int type=command.get(1).asVocab32(); + if (type==createVocab32('3','D')) { if (Bottle *bOpt=command.get(2).asList()) { if (bOpt->size()>2) { Vector x(3); - x[0]=bOpt->get(0).asDouble(); - x[1]=bOpt->get(1).asDouble(); - x[2]=bOpt->get(2).asDouble(); + x[0]=bOpt->get(0).asFloat64(); + x[1]=bOpt->get(1).asFloat64(); + x[2]=bOpt->get(2).asFloat64(); if (ctrl->look(x)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } } } - else if (type==createVocab('m','o','n','o')) + else if (type==createVocab32('m','o','n','o')) { if (Bottle *bOpt=command.get(2).asList()) { if (bOpt->size()>3) { string eye=bOpt->get(0).asString(); - double u=bOpt->get(1).asDouble(); - double v=bOpt->get(2).asDouble(); + double u=bOpt->get(1).asFloat64(); + double v=bOpt->get(2).asFloat64(); double z; bool ok=false; - if (bOpt->get(3).isDouble()) + if (bOpt->get(3).isFloat64()) { - z=bOpt->get(3).asDouble(); + z=bOpt->get(3).asFloat64(); ok=true; } else if ((bOpt->get(3).asString()=="ver") && (bOpt->size()>4)) { - double ver=bOpt->get(4).asDouble(); + double ver=bOpt->get(4).asFloat64(); z=loc->getDistFromVergence(ver); ok=true; } @@ -1782,7 +1782,7 @@ class GazeModule: public RFModule { if (ctrl->look(x)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1790,31 +1790,31 @@ class GazeModule: public RFModule } } } - else if (type==createVocab('s','t','e','r')) + else if (type==createVocab32('s','t','e','r')) { if (Bottle *bOpt=command.get(2).asList()) { if (bOpt->size()>3) { Vector pxl(2),pxr(2); - pxl[0]=bOpt->get(0).asDouble(); - pxl[1]=bOpt->get(1).asDouble(); - pxr[0]=bOpt->get(2).asDouble(); - pxr[1]=bOpt->get(3).asDouble(); + pxl[0]=bOpt->get(0).asFloat64(); + pxl[1]=bOpt->get(1).asFloat64(); + pxr[0]=bOpt->get(2).asFloat64(); + pxr[1]=bOpt->get(3).asFloat64(); Vector x; if (loc->triangulatePoint(pxl,pxr,x)) { if (ctrl->look(x)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } } } } - else if (type==createVocab('a','n','g')) + else if (type==createVocab32('a','n','g')) { if (Bottle *bOpt=command.get(2).asList()) { @@ -1822,14 +1822,14 @@ class GazeModule: public RFModule { Vector ang(3); string type=bOpt->get(0).asString(); - ang[0]=CTRL_DEG2RAD*bOpt->get(1).asDouble(); - ang[1]=CTRL_DEG2RAD*bOpt->get(2).asDouble(); - ang[2]=CTRL_DEG2RAD*bOpt->get(3).asDouble(); + ang[0]=CTRL_DEG2RAD*bOpt->get(1).asFloat64(); + ang[1]=CTRL_DEG2RAD*bOpt->get(2).asFloat64(); + ang[2]=CTRL_DEG2RAD*bOpt->get(3).asFloat64(); Vector x=loc->get3DPoint(type,ang); if (ctrl->look(x)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1841,32 +1841,32 @@ class GazeModule: public RFModule } //----------------- - case createVocab('s','t','o','p'): + case createVocab32('s','t','o','p'): { ctrl->stopControl(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } //----------------- - case createVocab('s','t','o','r'): + case createVocab32('s','t','o','r'): { int id; storeContext(&id); - reply.addVocab(ack); - reply.addInt(id); + reply.addVocab32(ack); + reply.addInt32(id); return true; } //----------------- - case createVocab('r','e','s','t'): + case createVocab32('r','e','s','t'): { if (command.size()>1) { - int id=command.get(1).asInt(); + int id=command.get(1).asInt32(); if (restoreContext(id)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1875,14 +1875,14 @@ class GazeModule: public RFModule } //----------------- - case createVocab('d','e','l'): + case createVocab32('d','e','l'): { if (command.size()>1) { Bottle *ids=command.get(1).asList(); if (deleteContexts(ids)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1891,40 +1891,40 @@ class GazeModule: public RFModule } //----------------- - case createVocab('b','i','n','d'): + case createVocab32('b','i','n','d'): { if (command.size()>2) { - int joint=command.get(1).asVocab(); - if (joint==createVocab('p','i','t','c')) + int joint=command.get(1).asVocab32(); + if (joint==createVocab32('p','i','t','c')) { - double min=command.get(2).asDouble(); - double max=command.get(3).asDouble(); + double min=command.get(2).asFloat64(); + double max=command.get(3).asFloat64(); slv->bindNeckPitch(min,max); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (joint==createVocab('r','o','l','l')) + else if (joint==createVocab32('r','o','l','l')) { - double min=command.get(2).asDouble(); - double max=command.get(3).asDouble(); + double min=command.get(2).asFloat64(); + double max=command.get(3).asFloat64(); slv->bindNeckRoll(min,max); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (joint==createVocab('y','a','w')) + else if (joint==createVocab32('y','a','w')) { - double min=command.get(2).asDouble(); - double max=command.get(3).asDouble(); + double min=command.get(2).asFloat64(); + double max=command.get(3).asFloat64(); slv->bindNeckYaw(min,max); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (joint==createVocab('e','y','e','s')) + else if (joint==createVocab32('e','y','e','s')) { - double ver=command.get(2).asDouble(); + double ver=command.get(2).asFloat64(); eyesRefGen->bindEyes(ver); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1933,33 +1933,33 @@ class GazeModule: public RFModule } //----------------- - case createVocab('c','l','e','a'): + case createVocab32('c','l','e','a'): { if (command.size()>1) { - int joint=command.get(1).asVocab(); - if (joint==createVocab('p','i','t','c')) + int joint=command.get(1).asVocab32(); + if (joint==createVocab32('p','i','t','c')) { slv->clearNeckPitch(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (joint==createVocab('r','o','l','l')) + else if (joint==createVocab32('r','o','l','l')) { slv->clearNeckRoll(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (joint==createVocab('y','a','w')) + else if (joint==createVocab32('y','a','w')) { slv->clearNeckYaw(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } - else if (joint==createVocab('e','y','e','s')) + else if (joint==createVocab32('e','y','e','s')) { eyesRefGen->clearEyes(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1968,19 +1968,19 @@ class GazeModule: public RFModule } //----------------- - case createVocab('r','e','g','i'): + case createVocab32('r','e','g','i'): { if (command.size()>1) { - int type=command.get(1).asVocab(); - if (type==createVocab('o','n','g','o')) + int type=command.get(1).asVocab32(); + if (type==createVocab32('o','n','g','o')) { if (command.size()>2) { - double checkPoint=command.get(2).asDouble(); + double checkPoint=command.get(2).asFloat64(); if (ctrl->registerMotionOngoingEvent(checkPoint)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -1991,19 +1991,19 @@ class GazeModule: public RFModule } //----------------- - case createVocab('u','n','r','e'): + case createVocab32('u','n','r','e'): { if (command.size()>1) { - int type=command.get(1).asVocab(); - if (type==createVocab('o','n','g','o')) + int type=command.get(1).asVocab32(); + if (type==createVocab32('o','n','g','o')) { if (command.size()>2) { - double checkPoint=command.get(2).asDouble(); + double checkPoint=command.get(2).asFloat64(); if (ctrl->unregisterMotionOngoingEvent(checkPoint)) { - reply.addVocab(ack); + reply.addVocab32(ack); return true; } } @@ -2014,14 +2014,14 @@ class GazeModule: public RFModule } //----------------- - case createVocab('l','i','s','t'): + case createVocab32('l','i','s','t'): { if (command.size()>1) { - int type=command.get(1).asVocab(); - if (type==createVocab('o','n','g','o')) + int type=command.get(1).asVocab32(); + if (type==createVocab32('o','n','g','o')) { - reply.addVocab(ack); + reply.addVocab32(ack); reply.addList()=ctrl->listMotionOngoingEvents(); return true; } @@ -2031,29 +2031,29 @@ class GazeModule: public RFModule } //----------------- - case createVocab('s','u','s','p'): + case createVocab32('s','u','s','p'): { ctrl->suspend(); eyesRefGen->suspend(); slv->suspend(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } //----------------- - case createVocab('r','u','n'): + case createVocab32('r','u','n'): { slv->resume(); eyesRefGen->resume(); ctrl->resume(); - reply.addVocab(ack); + reply.addVocab32(ack); return true; } //----------------- - case createVocab('s','t','a','t'): + case createVocab32('s','t','a','t'): { - reply.addVocab(ack); + reply.addVocab32(ack); if (ctrl->isSuspended()) reply.addString("suspended"); else @@ -2067,7 +2067,7 @@ class GazeModule: public RFModule } } - reply.addVocab(nack); + reply.addVocab32(nack); return true; } diff --git a/src/modules/iKinGazeCtrl/src/utils.cpp b/src/modules/iKinGazeCtrl/src/utils.cpp index d0f9a7e8de..0267b08968 100644 --- a/src/modules/iKinGazeCtrl/src/utils.cpp +++ b/src/modules/iKinGazeCtrl/src/utils.cpp @@ -71,7 +71,7 @@ void xdPort::onRead(Bottle &b) size_t n=std::min(b.size(),xd.length()); for (size_t i=0; isize()) && (cntget(cnt).asDouble(); + HN(i,j)=bH->get(cnt).asFloat64(); if (++j>=HN.cols()) { i++; diff --git a/src/modules/learningMachine/include/iCub/learningMachine/PredictEventListener.h b/src/modules/learningMachine/include/iCub/learningMachine/PredictEventListener.h index 7f11a20004..891889dafb 100644 --- a/src/modules/learningMachine/include/iCub/learningMachine/PredictEventListener.h +++ b/src/modules/learningMachine/include/iCub/learningMachine/PredictEventListener.h @@ -40,7 +40,7 @@ class PredictEventListener : public IPortEventListener { protected: void vectorToBottle(const yarp::sig::Vector& vec, yarp::os::Bottle& bot) { for(size_t i = 0; i < vec.size(); i++) { - bot.addDouble(vec[i]); + bot.addFloat64(vec[i]); } } diff --git a/src/modules/learningMachine/include/iCub/learningMachine/TrainEventListener.h b/src/modules/learningMachine/include/iCub/learningMachine/TrainEventListener.h index 6a005730dd..5c61a127a0 100644 --- a/src/modules/learningMachine/include/iCub/learningMachine/TrainEventListener.h +++ b/src/modules/learningMachine/include/iCub/learningMachine/TrainEventListener.h @@ -40,7 +40,7 @@ class TrainEventListener : public IPortEventListener { protected: void vectorToBottle(const yarp::sig::Vector& vec, yarp::os::Bottle& bot) { for(size_t i = 0; i < vec.size(); i++) { - bot.addDouble(vec[i]); + bot.addFloat64(vec[i]); } } diff --git a/src/modules/learningMachine/src/DispatcherManager.cpp b/src/modules/learningMachine/src/DispatcherManager.cpp index 44883235db..aead137b40 100644 --- a/src/modules/learningMachine/src/DispatcherManager.cpp +++ b/src/modules/learningMachine/src/DispatcherManager.cpp @@ -39,9 +39,9 @@ bool DispatcherManager::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& r bool success = false; try { - switch(cmd.get(0).asVocab()) { - case yarp::os::createVocab('h','e','l','p'): // print help information - reply.add(yarp::os::Value::makeVocab("help")); + switch(cmd.get(0).asVocab32()) { + case yarp::os::createVocab32('h','e','l','p'): // print help information + reply.add(yarp::os::Value::makeVocab32("help")); reply.addString("Event Manager configuration options"); reply.addString(" help Displays this message"); @@ -53,9 +53,9 @@ bool DispatcherManager::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& r success = true; break; - case yarp::os::createVocab('l','i','s','t'): // print list of available event listeners + case yarp::os::createVocab32('l','i','s','t'): // print list of available event listeners { - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::vector keys = FactoryT::instance().getKeys(); for(unsigned int i = 0; i < keys.size(); i++) { reply.addString((std::string(" ") + keys[i]).c_str()); @@ -64,7 +64,7 @@ bool DispatcherManager::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& r break; } - case yarp::os::createVocab('a','d','d'): // add + case yarp::os::createVocab32('a','d','d'): // add { // prevent identifier initialization to cross borders of case yarp::os::Bottle list = cmd.tail(); for(int i = 0; i < list.size(); i++) { @@ -77,11 +77,11 @@ bool DispatcherManager::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& r break; } - case yarp::os::createVocab('r','e','m','o'): // remove - case yarp::os::createVocab('d','e','l'): // del(ete) + case yarp::os::createVocab32('r','e','m','o'): // remove + case yarp::os::createVocab32('d','e','l'): // del(ete) { // prevent identifier initialization to cross borders of case - if(cmd.get(1).isInt() && cmd.get(1).asInt() >= 1 && cmd.get(1).asInt() <= this->dispatcher->countListeners()) { - this->dispatcher->removeListener(cmd.get(1).asInt()-1); + if(cmd.get(1).isInt32() && cmd.get(1).asInt32() >= 1 && cmd.get(1).asInt32() <= this->dispatcher->countListeners()) { + this->dispatcher->removeListener(cmd.get(1).asInt32()-1); reply.addString("Successfully removed listener."); success = true; } else if(cmd.get(1).asString() == "all") { @@ -94,16 +94,16 @@ bool DispatcherManager::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& r break; } - case yarp::os::createVocab('s','e','t'): // set + case yarp::os::createVocab32('s','e','t'): // set { // prevent identifier initialization to cross borders of case yarp::os::Bottle property; property.addList() = cmd.tail().tail(); // see comment in TrainModule std::string replymsg = "Setting configuration option "; - if(cmd.get(1).isInt() && cmd.get(1).asInt() >= 1 && - cmd.get(1).asInt() <= this->dispatcher->countListeners()) { + if(cmd.get(1).isInt32() && cmd.get(1).asInt32() >= 1 && + cmd.get(1).asInt32() <= this->dispatcher->countListeners()) { - bool ok = this->dispatcher->getAt(cmd.get(1).asInt()-1).configure(property); + bool ok = this->dispatcher->getAt(cmd.get(1).asInt32()-1).configure(property); replymsg += ok ? "succeeded" : "failed; please check key and value type."; reply.addString(replymsg.c_str()); @@ -126,10 +126,10 @@ bool DispatcherManager::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& r break; } - case yarp::os::createVocab('i','n','f','o'): // information - case yarp::os::createVocab('s','t','a','t'): // statistics + case yarp::os::createVocab32('i','n','f','o'): // information + case yarp::os::createVocab32('s','t','a','t'): // statistics { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::ostringstream buffer; buffer << "Event Manager Information (" << this->dispatcher->countListeners() << " listeners)"; reply.addString(buffer.str().c_str()); diff --git a/src/modules/learningMachine/src/PredictModule.cpp b/src/modules/learningMachine/src/PredictModule.cpp index 4637775094..06bd5cbd25 100644 --- a/src/modules/learningMachine/src/PredictModule.cpp +++ b/src/modules/learningMachine/src/PredictModule.cpp @@ -152,10 +152,10 @@ bool PredictModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply bool success = false; try { - switch(cmd.get(0).asVocab()) { - case yarp::os::createVocab('h','e','l','p'): // print help information + switch(cmd.get(0).asVocab32()) { + case yarp::os::createVocab32('h','e','l','p'): // print help information { - reply.addVocab(yarp::os::Vocab::encode("help")); + reply.addVocab32("help"); reply.addString("Training module configuration options"); reply.addString(" help Displays this message"); @@ -168,10 +168,10 @@ bool PredictModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply break; } - case yarp::os::createVocab('c','l','e','a'): // clear the machine - case yarp::os::createVocab('c','l','r'): - case yarp::os::createVocab('r','e','s','e'): - case yarp::os::createVocab('r','s','t'): + case yarp::os::createVocab32('c','l','e','a'): // clear the machine + case yarp::os::createVocab32('c','l','r'): + case yarp::os::createVocab32('r','e','s','e'): + case yarp::os::createVocab32('r','s','t'): { this->getMachine().reset(); reply.addString("Machine reset."); @@ -179,19 +179,19 @@ bool PredictModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply break; } - case yarp::os::createVocab('i','n','f','o'): // information - case yarp::os::createVocab('s','t','a','t'): // print statistics + case yarp::os::createVocab32('i','n','f','o'): // information + case yarp::os::createVocab32('s','t','a','t'): // print statistics { - reply.addVocab(yarp::os::Vocab::encode("help")); + reply.addVocab32("help"); reply.addString("Machine Information: "); reply.addString(this->getMachine().getInfo().c_str()); success = true; break; } - case yarp::os::createVocab('l','o','a','d'): // load + case yarp::os::createVocab32('l','o','a','d'): // load { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg = std::string("Loading machine from '") + cmd.get(1).asString().c_str() + "'... " ; if(!cmd.get(1).isString()) { @@ -205,10 +205,10 @@ bool PredictModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply break; } - case yarp::os::createVocab('c','m','d'): // cmd - case yarp::os::createVocab('c','o','m','m'): // command + case yarp::os::createVocab32('c','m','d'): // cmd + case yarp::os::createVocab32('c','o','m','m'): // command { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg; if(!cmd.get(1).isString()) { replymsg = "Please supply a valid filename."; diff --git a/src/modules/learningMachine/src/TrainModule.cpp b/src/modules/learningMachine/src/TrainModule.cpp index 9fee7ab466..e8c63e4eff 100644 --- a/src/modules/learningMachine/src/TrainModule.cpp +++ b/src/modules/learningMachine/src/TrainModule.cpp @@ -177,9 +177,9 @@ bool TrainModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply) bool success = false; try { - switch(cmd.get(0).asVocab()) { - case yarp::os::createVocab('h','e','l','p'): // print help information - reply.add(yarp::os::Value::makeVocab("help")); + switch(cmd.get(0).asVocab32()) { + case yarp::os::createVocab32('h','e','l','p'): // print help information + reply.add(yarp::os::Value::makeVocab32("help")); reply.addString("Training module configuration options"); reply.addString(" help Displays this message"); @@ -198,52 +198,52 @@ bool TrainModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply) success = true; break; - case yarp::os::createVocab('t','r','a','i'): // train the machine, implies sending model + case yarp::os::createVocab32('t','r','a','i'): // train the machine, implies sending model this->getMachine().train(); reply.addString("Training completed."); - case yarp::os::createVocab('m','o','d','e'): // send model + case yarp::os::createVocab32('m','o','d','e'): // send model this->model_out.write(this->machinePortable); reply.addString("The model has been written to the port."); success = true; break; - case yarp::os::createVocab('c','l','e','a'): // clear machine - case yarp::os::createVocab('c','l','r'): - case yarp::os::createVocab('r','e','s','e'): // reset - case yarp::os::createVocab('r','s','t'): + case yarp::os::createVocab32('c','l','e','a'): // clear machine + case yarp::os::createVocab32('c','l','r'): + case yarp::os::createVocab32('r','e','s','e'): // reset + case yarp::os::createVocab32('r','s','t'): this->getMachine().reset(); reply.addString("Machine cleared."); success = true; break; - case yarp::os::createVocab('p','a','u','s'): // pause sample stream - case yarp::os::createVocab('d','i','s','a'): // disable + case yarp::os::createVocab32('p','a','u','s'): // pause sample stream + case yarp::os::createVocab32('d','i','s','a'): // disable this->trainProcessor.setEnabled(false); reply.addString("Sample stream to machine disabled."); success = true; break; - case yarp::os::createVocab('c','o','n','t'): // continue sample stream - case yarp::os::createVocab('e','n','a','b'): // enable + case yarp::os::createVocab32('c','o','n','t'): // continue sample stream + case yarp::os::createVocab32('e','n','a','b'): // enable this->trainProcessor.setEnabled(true); reply.addString("Sample stream to machine enabled."); success = true; break; - case yarp::os::createVocab('i','n','f','o'): // information - case yarp::os::createVocab('s','t','a','t'): // statistics + case yarp::os::createVocab32('i','n','f','o'): // information + case yarp::os::createVocab32('s','t','a','t'): // statistics { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); reply.addString("Machine Information: "); reply.addString(this->getMachine().getInfo().c_str()); success = true; break; } - case yarp::os::createVocab('l','o','a','d'): // load + case yarp::os::createVocab32('l','o','a','d'): // load { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg = std::string("Loading machine from '") + cmd.get(1).asString().c_str() + "'... " ; if(!cmd.get(1).isString()) { @@ -257,9 +257,9 @@ bool TrainModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply) break; } - case yarp::os::createVocab('s','a','v','e'): // save + case yarp::os::createVocab32('s','a','v','e'): // save { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg = std::string("Saving machine to '") + cmd.get(1).asString().c_str() + "'... " ; if(!cmd.get(1).isString()) { @@ -273,7 +273,7 @@ bool TrainModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply) break; } - case yarp::os::createVocab('s','e','t'): // set a configuration option for the machine + case yarp::os::createVocab32('s','e','t'): // set a configuration option for the machine { // prevent identifier initialization to cross borders of case yarp::os::Bottle property; /* @@ -292,16 +292,16 @@ bool TrainModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& reply) break; } - case yarp::os::createVocab('e','v','e','n'): // event + case yarp::os::createVocab32('e','v','e','n'): // event { // prevent identifier initialization to cross borders of case success = this->dmanager.respond(cmd.tail(), reply); break; } - case yarp::os::createVocab('c','m','d'): // cmd - case yarp::os::createVocab('c','o','m','m'): // command + case yarp::os::createVocab32('c','m','d'): // cmd + case yarp::os::createVocab32('c','o','m','m'): // command { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg; if(!cmd.get(1).isString()) { replymsg = "Please supply a valid filename."; diff --git a/src/modules/learningMachine/src/TransformModule.cpp b/src/modules/learningMachine/src/TransformModule.cpp index 7496c7ecc7..27eba953a0 100644 --- a/src/modules/learningMachine/src/TransformModule.cpp +++ b/src/modules/learningMachine/src/TransformModule.cpp @@ -219,9 +219,9 @@ bool TransformModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& rep bool success = false; try { - switch(cmd.get(0).asVocab()) { - case yarp::os::createVocab('h','e','l','p'): // print help information - reply.add(yarp::os::Value::makeVocab("help")); + switch(cmd.get(0).asVocab32()) { + case yarp::os::createVocab32('h','e','l','p'): // print help information + reply.add(yarp::os::Value::makeVocab32("help")); reply.addString("Transform module configuration options"); reply.addString(" help Displays this message"); @@ -235,26 +235,26 @@ bool TransformModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& rep success = true; break; - case yarp::os::createVocab('c','l','e','a'): // clear the machine - case yarp::os::createVocab('c','l','r'): - case yarp::os::createVocab('r','e','s','e'): - case yarp::os::createVocab('r','s','t'): + case yarp::os::createVocab32('c','l','e','a'): // clear the machine + case yarp::os::createVocab32('c','l','r'): + case yarp::os::createVocab32('r','e','s','e'): + case yarp::os::createVocab32('r','s','t'): this->getTransformer().reset(); reply.addString("Transformer reset."); success = true; break; - case yarp::os::createVocab('i','n','f','o'): // information - case yarp::os::createVocab('s','t','a','t'): // print statistics + case yarp::os::createVocab32('i','n','f','o'): // information + case yarp::os::createVocab32('s','t','a','t'): // print statistics { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); reply.addString("Transformer Information: "); reply.addString(this->getTransformer().getInfo().c_str()); success = true; break; } - case yarp::os::createVocab('s','e','t'): // set a configuration option for the machine + case yarp::os::createVocab32('s','e','t'): // set a configuration option for the machine { // prevent identifier initialization to cross borders of case yarp::os::Bottle property; /* @@ -273,9 +273,9 @@ bool TransformModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& rep break; } - case yarp::os::createVocab('l','o','a','d'): // load + case yarp::os::createVocab32('l','o','a','d'): // load { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg = std::string("Loading transformer from '") + cmd.get(1).asString().c_str() + "'... " ; if(!cmd.get(1).isString()) { @@ -289,9 +289,9 @@ bool TransformModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& rep break; } - case yarp::os::createVocab('s','a','v','e'): // save + case yarp::os::createVocab32('s','a','v','e'): // save { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg = std::string("Saving transformer to '") + cmd.get(1).asString().c_str() + "'... " ; if(!cmd.get(1).isString()) { @@ -305,10 +305,10 @@ bool TransformModule::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& rep break; } - case yarp::os::createVocab('c','m','d'): // cmd - case yarp::os::createVocab('c','o','m','m'): // command + case yarp::os::createVocab32('c','m','d'): // cmd + case yarp::os::createVocab32('c','o','m','m'): // command { // prevent identifier initialization to cross borders of case - reply.add(yarp::os::Value::makeVocab("help")); + reply.add(yarp::os::Value::makeVocab32("help")); std::string replymsg; if(!cmd.get(1).isString()) { replymsg = "Please supply a valid filename."; diff --git a/src/modules/learningMachine/src/bin/merge.cpp b/src/modules/learningMachine/src/bin/merge.cpp index 6386b73800..b092415270 100644 --- a/src/modules/learningMachine/src/bin/merge.cpp +++ b/src/modules/learningMachine/src/bin/merge.cpp @@ -831,8 +831,8 @@ class MergeModule : public RFModule { if (opt.check("frequency", val)) { - if (val->isDouble() || val->isInt()) { - this->setFrequency(val->asDouble()); + if (val->isFloat64() || val->isInt32()) { + this->setFrequency(val->asFloat64()); } } @@ -871,10 +871,10 @@ class MergeModule : public RFModule { bool success = false; try { - switch (cmd.get(0).asVocab()) { - case yarp::os::createVocab('h','e','l','p'): // print help information + switch (cmd.get(0).asVocab32()) { + case yarp::os::createVocab32('h','e','l','p'): // print help information success = true; - reply.add(Value::makeVocab("help")); + reply.add(Value::makeVocab32("help")); reply.addString("Merge module configuration options"); reply.addString(" help Displays this message"); @@ -882,19 +882,19 @@ class MergeModule : public RFModule { reply.addString(" freq f Sampling frequency in Hertz (0 for disabled)"); break; - case yarp::os::createVocab('i','n','f','o'): // print information + case yarp::os::createVocab32('i','n','f','o'): // print information { - reply.add(Value::makeVocab("help")); + reply.add(Value::makeVocab32("help")); success = true; reply.addString(this->dataSelector->toString().c_str()); break; } - case yarp::os::createVocab('f','r','e','q'): // set sampling frequency + case yarp::os::createVocab32('f','r','e','q'): // set sampling frequency { - if (cmd.size() > 1 && (cmd.get(1).isInt() || cmd.get(1).isDouble())) { + if (cmd.size() > 1 && (cmd.get(1).isInt32() || cmd.get(1).isFloat64())) { success = true; - this->setDesiredPeriod(1. / cmd.get(1).asDouble()); + this->setDesiredPeriod(1. / cmd.get(1).asFloat64()); //reply.addString((std::string("Current frequency: ") + cmd.get(1).toString().c_str()).c_str()); } break; diff --git a/src/modules/learningMachine/src/bin/test.cpp b/src/modules/learningMachine/src/bin/test.cpp index 34620808ed..b201b4793e 100644 --- a/src/modules/learningMachine/src/bin/test.cpp +++ b/src/modules/learningMachine/src/bin/test.cpp @@ -344,12 +344,12 @@ class MachineLearnerTestModule : public RFModule { if(val->isList()) { Bottle* inputs = val->asList(); for(int i = 0; i < inputs->size(); i++) { - if(inputs->get(i).isInt()) { - this->dataset.addInputColumn(inputs->get(i).asInt()); + if(inputs->get(i).isInt32()) { + this->dataset.addInputColumn(inputs->get(i).asInt32()); } } - } else if(val->isInt()) { - this->dataset.addInputColumn(val->asInt()); + } else if(val->isInt32()) { + this->dataset.addInputColumn(val->asInt32()); } } else { this->dataset.addInputColumn(1); @@ -361,12 +361,12 @@ class MachineLearnerTestModule : public RFModule { if(val->isList()) { Bottle* outputs = val->asList(); for(int i = 0; i < outputs->size(); i++) { - if(outputs->get(i).isInt()) { - this->dataset.addOutputColumn(outputs->get(i).asInt()); + if(outputs->get(i).isInt32()) { + this->dataset.addOutputColumn(outputs->get(i).asInt32()); } } - } else if(val->isInt()) { - this->dataset.addOutputColumn(val->asInt()); + } else if(val->isInt32()) { + this->dataset.addOutputColumn(val->asInt32()); } } else { this->dataset.addOutputColumn(2); @@ -374,7 +374,7 @@ class MachineLearnerTestModule : public RFModule { // check for port specifier: portSuffix if(opt.check("frequency", val)) { - this->frequency = val->asInt(); + this->frequency = val->asInt32(); } else { this->frequency = 0; } @@ -408,10 +408,10 @@ class MachineLearnerTestModule : public RFModule { bool success = false; try { - switch(cmd.get(0).asVocab()) { - case yarp::os::createVocab('h','e','l','p'): // print help information + switch(cmd.get(0).asVocab32()) { + case yarp::os::createVocab32('h','e','l','p'): // print help information success = true; - reply.add(Value::makeVocab("help")); + reply.add(Value::makeVocab32("help")); reply.addString("Testing module configuration options"); reply.addString(" help Displays this message"); @@ -424,19 +424,19 @@ class MachineLearnerTestModule : public RFModule { reply.addString(" open fname Opens a datafile"); reply.addString(" freq f Sampling frequency in Hertz (0 for disabled)"); break; - case yarp::os::createVocab('c','o','n','f'): // print the configuration + case yarp::os::createVocab32('c','o','n','f'): // print the configuration { success = true; this->printConfig(); break; } - case yarp::os::createVocab('s','k','i','p'): // skip some training sample(s) + case yarp::os::createVocab32('s','k','i','p'): // skip some training sample(s) { success = true; int noSamples = 1; - if(cmd.get(1).isInt()) { - noSamples = cmd.get(1).asInt(); + if(cmd.get(1).isInt32()) { + noSamples = cmd.get(1).asInt32(); } for(int i = 0; i < noSamples; i++) { @@ -448,13 +448,13 @@ class MachineLearnerTestModule : public RFModule { break; } - case yarp::os::createVocab('t','r','a','i'): // send training sample(s) + case yarp::os::createVocab32('t','r','a','i'): // send training sample(s) { - reply.add(Value::makeVocab("help")); + reply.add(Value::makeVocab32("help")); success = true; int noSamples = 1; - if(cmd.get(1).isInt()) { - noSamples = cmd.get(1).asInt(); + if(cmd.get(1).isInt32()) { + noSamples = cmd.get(1).asInt32(); } //double start = yarp::os::Time::now(); @@ -475,13 +475,13 @@ class MachineLearnerTestModule : public RFModule { break; } - case yarp::os::createVocab('p','r','e','d'): // send prediction sample(s) + case yarp::os::createVocab32('p','r','e','d'): // send prediction sample(s) { - reply.add(Value::makeVocab("help")); + reply.add(Value::makeVocab32("help")); success = true; int noSamples = 1; - if(cmd.get(1).isInt()) { - noSamples = cmd.get(1).asInt(); + if(cmd.get(1).isInt32()) { + noSamples = cmd.get(1).asInt32(); } // initiate error vector (not completely failsafe!) @@ -544,13 +544,13 @@ class MachineLearnerTestModule : public RFModule { break; } - case yarp::os::createVocab('s','h','o','o'): + case yarp::os::createVocab32('s','h','o','o'): { success = true; Vector input; for(int i = 1; i <= cmd.size(); i++) { - if(cmd.get(i).isDouble() || cmd.get(i).isInt()) { - input.push_back(cmd.get(i).asDouble()); + if(cmd.get(i).isFloat64() || cmd.get(i).isInt32()) { + input.push_back(cmd.get(i).asFloat64()); } } Prediction prediction = this->sendPredictSample(input); @@ -560,7 +560,7 @@ class MachineLearnerTestModule : public RFModule { break; } - case yarp::os::createVocab('o','p','e','n'): + case yarp::os::createVocab32('o','p','e','n'): success = true; if(cmd.get(1).isString()) { std::cout << "Open..." << std::endl; @@ -569,24 +569,24 @@ class MachineLearnerTestModule : public RFModule { reply.addString((std::string("Opened dataset: ") + cmd.get(1).asString().c_str()).c_str()); break; - case yarp::os::createVocab('r','e','s','e'): - case yarp::os::createVocab('r','s','t'): + case yarp::os::createVocab32('r','e','s','e'): + case yarp::os::createVocab32('r','s','t'): success = true; this->dataset.reset(); reply.addString("Dataset reset to beginning"); break; - case yarp::os::createVocab('f','r','e','q'): // set sampling frequency + case yarp::os::createVocab32('f','r','e','q'): // set sampling frequency { - if(cmd.size() > 1 && cmd.get(1).isInt()) { + if(cmd.size() > 1 && cmd.get(1).isInt32()) { success = true; - this->frequency = cmd.get(1).asInt(); + this->frequency = cmd.get(1).asInt32(); reply.addString((std::string("Current frequency: ") + inttostring(this->frequency)).c_str()); } break; } - case yarp::os::createVocab('s','e','t'): // set some configuration options + case yarp::os::createVocab32('s','e','t'): // set some configuration options // implement some options break; diff --git a/src/modules/motionCUT/main.cpp b/src/modules/motionCUT/main.cpp index cc68f02ec9..d2f33670f0 100644 --- a/src/modules/motionCUT/main.cpp +++ b/src/modules/motionCUT/main.cpp @@ -111,14 +111,14 @@ class ProcessThread : public Thread bool threadInit() { name=rf.check("name",Value("motionCUT")).asString(); - coverXratio=rf.check("coverXratio",Value(0.75)).asDouble(); - coverYratio=rf.check("coverYratio",Value(0.75)).asDouble(); - nodesStep=rf.check("nodesStep",Value(6)).asInt(); - winSize=rf.check("winSize",Value(15)).asInt(); - recogThres=rf.check("recogThres",Value(0.01)).asDouble(); - adjNodesThres=rf.check("adjNodesThres",Value(4)).asInt(); - blobMinSizeThres=rf.check("blobMinSizeThres",Value(10)).asInt(); - framesPersistence=rf.check("framesPersistence",Value(3)).asInt(); + coverXratio=rf.check("coverXratio",Value(0.75)).asFloat64(); + coverYratio=rf.check("coverYratio",Value(0.75)).asFloat64(); + nodesStep=rf.check("nodesStep",Value(6)).asInt32(); + winSize=rf.check("winSize",Value(15)).asInt32(); + recogThres=rf.check("recogThres",Value(0.01)).asFloat64(); + adjNodesThres=rf.check("adjNodesThres",Value(4)).asInt32(); + blobMinSizeThres=rf.check("blobMinSizeThres",Value(10)).asInt32(); + framesPersistence=rf.check("framesPersistence",Value(3)).asInt32(); verbosity=rf.check("verbosity"); cropSize=0; @@ -126,7 +126,7 @@ class ProcessThread : public Thread { Value &vCropSize=rf.find("cropSize"); if (!vCropSize.isString()) - cropSize=vCropSize.asInt(); + cropSize=vCropSize.asInt32(); } recogThresAbs=recogThres*((256*winSize*winSize)/100.0); @@ -254,7 +254,7 @@ class ProcessThread : public Thread Bottle &nodesStepBottle=nodesBottle.addList(); nodesStepBottle.addString("nodesStep"); - nodesStepBottle.addInt(nodesStep); + nodesStepBottle.addInt32(nodesStep); // purge the content of variables activeNodesIndexSet.clear(); @@ -285,8 +285,8 @@ class ProcessThread : public Thread circle(imgMonoOptMat,node,1,Scalar(255),2); Bottle &nodeBottle=nodesBottle.addList(); - nodeBottle.addInt((int)nodesPrev[i].x); - nodeBottle.addInt((int)nodesPrev[i].y); + nodeBottle.addInt32((int)nodesPrev[i].x); + nodeBottle.addInt32((int)nodesPrev[i].y); // update the active nodes set activeNodesIndexSet.insert((int)i); @@ -325,8 +325,8 @@ class ProcessThread : public Thread circle(imgMonoOptMat,node,1,Scalar(255),2); Bottle &nodeBottle=nodesBottle.addList(); - nodeBottle.addInt((int)nodesPrev[i].x); - nodeBottle.addInt((int)nodesPrev[i].y); + nodeBottle.addInt32((int)nodesPrev[i].x); + nodeBottle.addInt32((int)nodesPrev[i].y); // update the active nodes set activeNodesIndexSet.insert((int)i); @@ -350,9 +350,9 @@ class ProcessThread : public Thread Point centroid=Point(blob.centroid.x,blob.centroid.y); Bottle &blobBottle=blobsBottle.addList(); - blobBottle.addInt(centroid.x); - blobBottle.addInt(centroid.y); - blobBottle.addInt(blob.size); + blobBottle.addInt32(centroid.x); + blobBottle.addInt32(centroid.y); + blobBottle.addInt32(blob.size); circle(imgBgrOutMat,centroid,4,Scalar(blueLev,0,redLev),3); } @@ -391,9 +391,9 @@ class ProcessThread : public Thread if ((cropPort.getOutputCount()>0) && (blobsBottle.size()>0)) { Bottle &blob=*blobsBottle.get(0).asList(); - int x=blob.get(0).asInt(); - int y=blob.get(1).asInt(); - int d=(cropSize>0)?cropSize:(int)(nodesStep*sqrt((double)blob.get(2).asInt())); + int x=blob.get(0).asInt32(); + int y=blob.get(1).asInt32(); + int d=(cropSize>0)?cropSize:(int)(nodesStep*sqrt((double)blob.get(2).asInt32())); int d2=d>>1; Point tl=Point(std::max(x-d2,0),std::max(y-d2,0)); @@ -522,35 +522,35 @@ class ProcessThread : public Thread if (subcmd=="winSize") { - winSize=req.get(2).asInt(); + winSize=req.get(2).asInt32(); reply.addString("ack"); } else if (subcmd=="recogThres") { - recogThres=req.get(2).asDouble(); + recogThres=req.get(2).asFloat64(); recogThresAbs=recogThres*((256*winSize*winSize)/100.0); reply.addString("ack"); } else if (subcmd=="adjNodesThres") { - adjNodesThres=req.get(2).asInt(); + adjNodesThres=req.get(2).asInt32(); reply.addString("ack"); } else if (subcmd=="blobMinSizeThres") { - blobMinSizeThres=req.get(2).asInt(); + blobMinSizeThres=req.get(2).asInt32(); reply.addString("ack"); } else if (subcmd=="framesPersistence") { - framesPersistence=req.get(2).asInt(); + framesPersistence=req.get(2).asInt32(); reply.addString("ack"); } else if (subcmd=="cropSize") { Value &vCropSize=req.get(2); if (!vCropSize.isString()) - cropSize=vCropSize.asInt(); + cropSize=vCropSize.asInt32(); else cropSize=0; @@ -577,19 +577,19 @@ class ProcessThread : public Thread string subcmd=req.get(1).asString(); if (subcmd=="winSize") - reply.addInt(winSize); + reply.addInt32(winSize); else if (subcmd=="recogThres") - reply.addDouble(recogThres); + reply.addFloat64(recogThres); else if (subcmd=="adjNodesThres") - reply.addInt(adjNodesThres); + reply.addInt32(adjNodesThres); else if (subcmd=="blobMinSizeThres") - reply.addInt(blobMinSizeThres); + reply.addInt32(blobMinSizeThres); else if (subcmd=="framesPersistence") - reply.addInt(framesPersistence); + reply.addInt32(framesPersistence); else if (subcmd=="cropSize") { if (cropSize>0) - reply.addInt(cropSize); + reply.addInt32(cropSize); else reply.addString("auto"); } diff --git a/src/modules/objectsPropertiesCollector/main.cpp b/src/modules/objectsPropertiesCollector/main.cpp index 42f1e8952d..a500841a88 100644 --- a/src/modules/objectsPropertiesCollector/main.cpp +++ b/src/modules/objectsPropertiesCollector/main.cpp @@ -268,26 +268,26 @@ reply: [ack] (id (1)) using namespace std; using namespace yarp::os; -#define CMD_ADD createVocab('a','d','d') -#define CMD_DEL createVocab('d','e','l') -#define CMD_GET createVocab('g','e','t') -#define CMD_SET createVocab('s','e','t') -#define CMD_LOCK createVocab('l','o','c','k') -#define CMD_UNLOCK createVocab('u','n','l','o') -#define CMD_OWNER createVocab('o','w','n','e') -#define CMD_TIME createVocab('t','i','m','e') -#define CMD_DUMP createVocab('d','u','m','p') -#define CMD_ASK createVocab('a','s','k') -#define CMD_SYNC createVocab('s','y','n','c') -#define CMD_ASYNC createVocab('a','s','y','n') -#define CMD_QUIT createVocab('q','u','i','t') -#define CMD_BYE createVocab('b','y','e') +#define CMD_ADD createVocab32('a','d','d') +#define CMD_DEL createVocab32('d','e','l') +#define CMD_GET createVocab32('g','e','t') +#define CMD_SET createVocab32('s','e','t') +#define CMD_LOCK createVocab32('l','o','c','k') +#define CMD_UNLOCK createVocab32('u','n','l','o') +#define CMD_OWNER createVocab32('o','w','n','e') +#define CMD_TIME createVocab32('t','i','m','e') +#define CMD_DUMP createVocab32('d','u','m','p') +#define CMD_ASK createVocab32('a','s','k') +#define CMD_SYNC createVocab32('s','y','n','c') +#define CMD_ASYNC createVocab32('a','s','y','n') +#define CMD_QUIT createVocab32('q','u','i','t') +#define CMD_BYE createVocab32('b','y','e') -#define REP_ACK createVocab('a','c','k') -#define REP_NACK createVocab('n','a','c','k') -#define REP_UNKNOWN createVocab('u','n','k','n') +#define REP_ACK createVocab32('a','c','k') +#define REP_NACK createVocab32('n','a','c','k') +#define REP_UNKNOWN createVocab32('u','n','k','n') -#define OPT_ALL createVocab('a','l','l') +#define OPT_ALL createVocab32('a','l','l') #define OPT_DISABLED (-1.0) #define OPT_OWNERSHIP_ALL ("all") @@ -312,10 +312,10 @@ bool alwaysTrue(Value &a, Value &b) /************************************************************************/ bool greater(Value &a, Value &b) { - if (a.isDouble() && b.isDouble()) - return (a.asDouble()>b.asDouble()); - else if (a.isInt() && b.isInt()) - return (a.asInt()>b.asInt()); + if (a.isFloat64() && b.isFloat64()) + return (a.asFloat64()>b.asFloat64()); + else if (a.isInt32() && b.isInt32()) + return (a.asInt32()>b.asInt32()); else return false; } @@ -324,10 +324,10 @@ bool greater(Value &a, Value &b) /************************************************************************/ bool greaterEqual(Value &a, Value &b) { - if (a.isDouble() && b.isDouble()) - return (a.asDouble()>=b.asDouble()); - else if (a.isInt() && b.isInt()) - return (a.asInt()>=b.asInt()); + if (a.isFloat64() && b.isFloat64()) + return (a.asFloat64()>=b.asFloat64()); + else if (a.isInt32() && b.isInt32()) + return (a.asInt32()>=b.asInt32()); else return false; } @@ -336,10 +336,10 @@ bool greaterEqual(Value &a, Value &b) /************************************************************************/ bool lower(Value &a, Value &b) { - if (a.isDouble() && b.isDouble()) - return (a.asDouble()get(1).asInt(); + int id=b2->get(1).asInt32(); itemsMap[id].prop=new Property(b3->toString().c_str()); if (idCnt<=id) @@ -675,7 +675,7 @@ class DataBase : public PeriodicThread Bottle &idList=item.addList(); idList.addString(PROP_ID); - idList.addInt(it->first); + idList.addInt32(it->first); } pBroadcastPort->writeStrict(); @@ -710,9 +710,9 @@ class DataBase : public PeriodicThread if (content->size()==1) { - if (content->get(0).isVocab() || content->get(0).isString()) + if (content->get(0).isVocab32() || content->get(0).isString()) { - if (content->get(0).asVocab()==OPT_ALL) + if (content->get(0).asVocab32()==OPT_ALL) { lock_guard lck(mtx); clear(); @@ -728,7 +728,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -763,7 +763,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -806,7 +806,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -856,7 +856,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -885,7 +885,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -914,7 +914,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -941,7 +941,7 @@ class DataBase : public PeriodicThread return false; } - int id=content->find(PROP_ID).asInt(); + int id=content->find(PROP_ID).asInt32(); lock_guard lck(mtx); map::iterator it=itemsMap.find(id); @@ -949,11 +949,11 @@ class DataBase : public PeriodicThread { response.clear(); if (it->second.lastUpdate<0.0) - response.addDouble(it->second.lastUpdate); + response.addFloat64(it->second.lastUpdate); else { double dt=Time::now()-it->second.lastUpdate; - response.addDouble(dt); + response.addFloat64(dt); } return true; } @@ -970,14 +970,14 @@ class DataBase : public PeriodicThread lock_guard lck(mtx); if (content->size()==1) { - if (content->get(0).isVocab() || content->get(0).isString()) + if (content->get(0).isVocab32() || content->get(0).isString()) { - if (content->get(0).asVocab()==OPT_ALL) + if (content->get(0).asVocab32()==OPT_ALL) { response.clear(); for (map::iterator it=itemsMap.begin(); it!=itemsMap.end(); it++) - response.addInt(it->first); + response.addInt32(it->first); return true; } @@ -1067,7 +1067,7 @@ class DataBase : public PeriodicThread // do recursion and keep only the item that // satisfies the whole list of conditions if (recursiveCheck(it->second.prop,condList,opList)) - response.addInt(it->first); + response.addInt32(it->first); } return true; @@ -1083,7 +1083,7 @@ class DataBase : public PeriodicThread Property *pProp=it->second.prop; if (pProp->check(PROP_LIFETIMER)) { - double lifeTimer=pProp->find(PROP_LIFETIMER).asDouble()-dt; + double lifeTimer=pProp->find(PROP_LIFETIMER).asFloat64()-dt; if (lifeTimer<=0.0) { eraseItem(it); @@ -1115,12 +1115,12 @@ class DataBase : public PeriodicThread string agent=connection.getRemoteContact().getName(); if (command.size()<1) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); return; } reply.clear(); - int cmd=command.get(0).asVocab(); + int cmd=command.get(0).asVocab32(); switch(cmd) { //----------------- @@ -1128,24 +1128,24 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } Bottle *content=command.get(1).asList(); if (add(content)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); Bottle &b=reply.addList(); b.addString(PROP_ID); - b.addInt(idCnt); + b.addInt32(idCnt); idCnt++; if (asyncBroadcast) broadcast(BCTAG_ASYNC); } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1155,19 +1155,19 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } Bottle *content=command.get(1).asList(); if (remove(content)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); if (asyncBroadcast) broadcast(BCTAG_ASYNC); } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1177,7 +1177,7 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1185,11 +1185,11 @@ class DataBase : public PeriodicThread Bottle *content=command.get(1).asList(); if (get(content,response)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); reply.addList()=response; } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1199,19 +1199,19 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } Bottle *content=command.get(1).asList(); if (set(content,agent)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); if (asyncBroadcast) broadcast(BCTAG_ASYNC); } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1221,15 +1221,15 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } Bottle *content=command.get(1).asList(); if (lock(content,agent)) - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1239,15 +1239,15 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } Bottle *content=command.get(1).asList(); if (unlock(content,agent)) - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1257,7 +1257,7 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1265,11 +1265,11 @@ class DataBase : public PeriodicThread Bottle *content=command.get(1).asList(); if (owner(content,response)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); reply.addList()=response; } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1279,7 +1279,7 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1287,11 +1287,11 @@ class DataBase : public PeriodicThread Bottle *content=command.get(1).asList(); if (time(content,response)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); reply.addList()=response; } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1300,7 +1300,7 @@ class DataBase : public PeriodicThread case CMD_DUMP: { dump(); - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); break; } @@ -1309,32 +1309,32 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } - int opt=command.get(1).asVocab(); - if (opt==Vocab::encode("start")) + int opt=command.get(1).asVocab32(); + if (opt==Vocab32::encode("start")) { if (command.size()>=3) - setPeriod(command.get(2).asDouble()); + setPeriod(command.get(2).asFloat64()); if (!isRunning()) start(); else if (isSuspended()) resume(); - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); } - else if (opt==Vocab::encode("stop")) + else if (opt==Vocab32::encode("stop")) { if (isRunning() && !isSuspended()) suspend(); - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1344,23 +1344,23 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } - int opt=command.get(1).asVocab(); - if (opt==Vocab::encode("on")) + int opt=command.get(1).asVocab32(); + if (opt==Vocab32::encode("on")) { asyncBroadcast=true; - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); } - else if (opt==Vocab::encode("off")) + else if (opt==Vocab32::encode("off")) { asyncBroadcast=false; - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1370,7 +1370,7 @@ class DataBase : public PeriodicThread { if (command.size()<2) { - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1378,13 +1378,13 @@ class DataBase : public PeriodicThread Bottle *content=command.get(1).asList(); if (ask(content,response)) { - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); Bottle &b=reply.addList(); b.addString(PROP_ID); b.addList()=response; } else - reply.addVocab(REP_NACK); + reply.addVocab32(REP_NACK); break; } @@ -1394,7 +1394,7 @@ class DataBase : public PeriodicThread case CMD_BYE: { quitting=true; - reply.addVocab(REP_ACK); + reply.addVocab32(REP_ACK); break; } @@ -1402,7 +1402,7 @@ class DataBase : public PeriodicThread default: { yWarning("received unknown command!"); - reply.addVocab(REP_UNKNOWN); + reply.addVocab32(REP_UNKNOWN); } } } @@ -1433,7 +1433,7 @@ class DataBase : public PeriodicThread { if (idList->get(0).asString()==PROP_ID) { - int id=idList->get(1).asInt(); + int id=idList->get(1).asInt32(); itemsMap[id].prop=new Property(item->tail().toString().c_str()); if (idCnt<=id) diff --git a/src/modules/positionDirectControl/main.cpp b/src/modules/positionDirectControl/main.cpp index 48f17adc2d..9b1ad0dce7 100644 --- a/src/modules/positionDirectControl/main.cpp +++ b/src/modules/positionDirectControl/main.cpp @@ -41,7 +41,7 @@ class VelControlModule: public RFModule { { if (command.get(0).asString()=="help") { - reply.addVocab(Vocab::encode("many")); + reply.addVocab32("many"); reply.addString("Available commands:"); reply.addString("currently nothing"); return true; @@ -127,11 +127,11 @@ class VelControlModule: public RFModule { double target_limiter = 1.0; //deg if (options.check("joints_limiter")) { - joints_limiter = options.find("joints_limiter").asDouble(); + joints_limiter = options.find("joints_limiter").asFloat64(); } if (options.check("target_limiter")) { - target_limiter = options.find("target_limiter").asDouble(); + target_limiter = options.find("target_limiter").asFloat64(); } yDebug() << "joints_limiter:" << joints_limiter; @@ -147,7 +147,7 @@ class VelControlModule: public RFModule { ///starting the thread int period = CONTROL_PERIOD; if(options.check("period")) - period = options.find("period").asInt(); + period = options.find("period").asInt32(); yInfo("control rate is %d ms",period); diff --git a/src/modules/positionDirectControl/positionDirectThread.cpp b/src/modules/positionDirectControl/positionDirectThread.cpp index 0fc2cc3695..decaa67168 100644 --- a/src/modules/positionDirectControl/positionDirectThread.cpp +++ b/src/modules/positionDirectControl/positionDirectThread.cpp @@ -54,7 +54,7 @@ void positionDirectControlThread::run() prev_targets=targets; for (unsigned int i=0; i< control_joints; i++) { - targets[i] = bot->get(i).asDouble(); + targets[i] = bot->get(i).asFloat64(); } } else @@ -174,9 +174,9 @@ bool positionDirectControlThread::init(PolyDriver *d, std::string moduleName, st control_joints_list = new int [control_joints]; for (unsigned int i=0; i< control_joints; i++) { - if (jointsList->get(i).isInt() && jointsList->get(i).asInt()>=0) + if (jointsList->get(i).isInt32() && jointsList->get(i).asInt32()>=0) { - control_joints_list[i] = jointsList->get(i).asInt(); + control_joints_list[i] = jointsList->get(i).asInt32(); } else { diff --git a/src/modules/skinManager/src/compensationThread.cpp b/src/modules/skinManager/src/compensationThread.cpp index 250a7940fe..30acb369d4 100644 --- a/src/modules/skinManager/src/compensationThread.cpp +++ b/src/modules/skinManager/src/compensationThread.cpp @@ -153,9 +153,9 @@ bool CompensationThread::threadInit() sendDebugMsg(msg.str()); }else{ FOR_ALL_PORTS(i){ - // cout<< "Skin part "<< SkinPart_s[skinPartList->get(i).asInt()]<< endl; - yDebug("Skin part %s",SkinPart_s[skinPartList->get(i).asInt()].c_str()); - compensators[i]->setSkinPart((SkinPart)skinPartList->get(i).asInt()); + // cout<< "Skin part "<< SkinPart_s[skinPartList->get(i).asInt32()]<< endl; + yDebug("Skin part %s",SkinPart_s[skinPartList->get(i).asInt32()].c_str()); + compensators[i]->setSkinPart((SkinPart)skinPartList->get(i).asInt32()); } } } @@ -171,7 +171,7 @@ bool CompensationThread::threadInit() sendDebugMsg(msg.str()); } else{ - maxNeighDist = skinEventsConf.check("maxNeighborDist", Value(MAX_NEIGHBOR_DISTANCE)).asDouble(); + maxNeighDist = skinEventsConf.check("maxNeighborDist", Value(MAX_NEIGHBOR_DISTANCE)).asFloat64(); yInfo("Max neighbor distance: %f m\n", maxNeighDist); FOR_ALL_PORTS(i){ @@ -399,7 +399,7 @@ Bottle CompensationThread::getInfo(){ if(!compWorking[i]) compName = compName + " (NOT WORKING)"; portB.addString(compName.c_str()); - portB.addInt(compensators[i]->getNumTaxels()); + portB.addInt32(compensators[i]->getNumTaxels()); } }else{ res.addString("Module initialization has not been completed yet."); diff --git a/src/modules/skinManager/src/skinManager.cpp b/src/modules/skinManager/src/skinManager.cpp index dd0367c0de..18dc8a7fe2 100644 --- a/src/modules/skinManager/src/skinManager.cpp +++ b/src/modules/skinManager/src/skinManager.cpp @@ -56,22 +56,22 @@ bool skinManager::configure(yarp::os::ResourceFinder &rf) { /* get some other values from the configuration file */ int period = (int)rf.check("period", Value(PERIOD_DEFAULT), - "Period of the thread in ms (positive int)").asInt(); + "Period of the thread in ms (positive int)").asInt32(); float minBaseline = (float)rf.check("minBaseline", Value(MIN_BASELINE_DEFAULT), - "If the baseline reaches this value then, if allowed, a calibration is executed (float in [0,255])").asDouble(); + "If the baseline reaches this value then, if allowed, a calibration is executed (float in [0,255])").asFloat64(); float compGain = (float)rf.check("compensationGain", Value(COMPENSATION_GAIN_DEFAULT), - "Gain of the compensation algorithm (float)").asDouble(); + "Gain of the compensation algorithm (float)").asFloat64(); float contCompGain = (float)rf.check("contactCompensationGain", Value(CONTACT_COMPENSATION_GAIN_DEFAULT), - "Gain of the compensation algorithm during contact (float)").asDouble(); + "Gain of the compensation algorithm during contact (float)").asFloat64(); int addThreshold = (int)rf.check("addThreshold", Value(ADD_THRESHOLD_DEFAULT), - "Value added to all the touch thresholds (positive int)").asInt(); + "Value added to all the touch thresholds (positive int)").asInt32(); bool zeroUpRawData = rf.check("zeroUpRawData", Value(ZERO_UP_RAW_DATA_DEFAULT), "if true the raw data are considered from zero up, otherwise from 255 down (bool)").asBool(); bool smoothFilter = rf.check("smoothFilter", Value(SMOOTH_FILTER_DEFAULT), "if true then the smoothing filter is active (bool)").asBool(); float smoothFactor = (float) rf.check("smoothFactor", Value(SMOOTH_FACTOR_DEFAULT), - "Determine the smoothing intensity (float in [0,1])").asDouble(); + "Determine the smoothing intensity (float in [0,1])").asFloat64(); bool binarization = rf.check("binarization", Value(BINARIZATION_DEFAULT), "if true then the binarization is active (bool)").asBool(); @@ -142,9 +142,9 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { SkinManagerCommand com; Bottle params; - if(command.get(0).isInt()){ + if(command.get(0).isInt32()){ // if first value is int then it is the id of the command - com = (SkinManagerCommand)command.get(0).asInt(); + com = (SkinManagerCommand)command.get(0).asInt32(); yInfo("[rpc] Command received: %s", SkinManagerCommandList[com].c_str()); params = command.tail(); } @@ -159,7 +159,7 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { return false; case help: - reply.addVocab(Vocab::encode("many")); // print every string added to the bottle on a new line + reply.addVocab32("many"); // print every string added to the bottle on a new line reply.addString((string(getName().c_str()) + " commands are: ").c_str()); for(unsigned int i=0; i< SkinManagerCommandSize; i++){ reply.addString( ("- "+SkinManagerCommandList[i]+": "+SkinManagerCommandDesc[i]).c_str() ); @@ -174,7 +174,7 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { { Vector touchThreshold = myThread->getTouchThreshold(); for(size_t i=0; i< touchThreshold.size(); i++) - reply.addDouble(touchThreshold[i]); + reply.addFloat64(touchThreshold[i]); return true; } @@ -230,109 +230,109 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { case set_smooth_factor: { - if(params.size()<1 || (!params.get(0).isDouble() && !params.get(0).isInt())){ + if(params.size()<1 || (!params.get(0).isFloat64() && !params.get(0).isInt32())){ reply.addString("New smooth factor value missing or not a number! Smooth factor not updated."); return true; } stringstream temp; - if(myThread->setSmoothFactor((float)params.get(0).asDouble())){ - temp<< "New smooth factor set: "<< params.get(0).asDouble(); + if(myThread->setSmoothFactor((float)params.get(0).asFloat64())){ + temp<< "New smooth factor set: "<< params.get(0).asFloat64(); } else{ - temp<< "ERROR in setting new smooth factor: "<< params.get(0).asDouble(); + temp<< "ERROR in setting new smooth factor: "<< params.get(0).asFloat64(); } reply.addString( temp.str().c_str()); return true; } case get_smooth_factor: - reply.addDouble(myThread->getSmoothFactor()); + reply.addFloat64(myThread->getSmoothFactor()); return true; case set_threshold: { - if(params.size()<1 || (!params.get(0).isInt())){ + if(params.size()<1 || (!params.get(0).isInt32())){ reply.addString("New threshold value missing or not an integer! Threshold not updated."); return true; } stringstream temp; - if(myThread->setAddThreshold(params.get(0).asInt())){ - temp<< "New threshold set: "<< params.get(0).asInt(); + if(myThread->setAddThreshold(params.get(0).asInt32())){ + temp<< "New threshold set: "<< params.get(0).asInt32(); } else{ - temp<< "ERROR in setting new threshold: "<< params.get(0).asInt(); + temp<< "ERROR in setting new threshold: "<< params.get(0).asInt32(); } reply.addString( temp.str().c_str()); return true; } case get_threshold: - reply.addInt(myThread->getAddThreshold()); + reply.addInt32(myThread->getAddThreshold()); return true; case set_gain: { - if(params.size()<1 || (!params.get(0).isDouble())){ + if(params.size()<1 || (!params.get(0).isFloat64())){ reply.addString("New gain value missing or not a double! Gain not updated."); return true; } stringstream temp; - if(myThread->setCompensationGain(params.get(0).asDouble())){ - temp<< "New gain set: "<< params.get(0).asDouble(); + if(myThread->setCompensationGain(params.get(0).asFloat64())){ + temp<< "New gain set: "<< params.get(0).asFloat64(); } else{ - temp<< "ERROR in setting new gain: "<< params.get(0).asDouble(); + temp<< "ERROR in setting new gain: "<< params.get(0).asFloat64(); } reply.addString( temp.str().c_str()); return true; } case get_gain: - reply.addDouble(myThread->getCompensationGain()); + reply.addFloat64(myThread->getCompensationGain()); return true; case set_cont_gain: { - if(params.size()<1 || (!params.get(0).isDouble())){ + if(params.size()<1 || (!params.get(0).isFloat64())){ reply.addString("New gain value missing or not a double! Contact gain not updated."); return true; } stringstream temp; - if(myThread->setContactCompensationGain(params.get(0).asDouble())){ - temp<< "New contact gain set: "<< params.get(0).asDouble(); + if(myThread->setContactCompensationGain(params.get(0).asFloat64())){ + temp<< "New contact gain set: "<< params.get(0).asFloat64(); } else{ - temp<< "ERROR in setting new contact gain: "<< params.get(0).asDouble(); + temp<< "ERROR in setting new contact gain: "<< params.get(0).asFloat64(); } reply.addString( temp.str().c_str()); return true; } case get_cont_gain: - reply.addDouble(myThread->getContactCompensationGain()); + reply.addFloat64(myThread->getContactCompensationGain()); return true; case get_max_neigh_dist: - reply.addDouble(myThread->getMaxNeighborDistance()); + reply.addFloat64(myThread->getMaxNeighborDistance()); return true; case set_max_neigh_dist: { - if(params.size()<1 || (!params.get(0).isDouble())){ + if(params.size()<1 || (!params.get(0).isFloat64())){ reply.addString("New max neighbor distance value missing or not a double! Not updated."); return true; } stringstream temp; - if(myThread->setMaxNeighborDistance(params.get(0).asDouble())){ - temp<< "New max neighbor distance set: "<< params.get(0).asDouble(); + if(myThread->setMaxNeighborDistance(params.get(0).asFloat64())){ + temp<< "New max neighbor distance set: "<< params.get(0).asFloat64(); } else{ - temp<< "ERROR in setting new max neighbor distance: "<< params.get(0).asDouble(); + temp<< "ERROR in setting new max neighbor distance: "<< params.get(0).asFloat64(); } reply.addString( temp.str().c_str()); return true; @@ -342,40 +342,40 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { { vector spl = myThread->getSkinParts(); for(vector::const_iterator it=spl.begin(); it!=spl.end(); it++){ - reply.addInt(*it); + reply.addInt32(*it); reply.addString(SkinPart_s[*it].c_str()); } return true; } case enable_skin_part: - if(!(params.size()>0 && params.get(0).isInt())){ + if(!(params.size()>0 && params.get(0).isInt32())){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - if(myThread->enableSkinPart((SkinPart)params.get(0).asInt())) + if(myThread->enableSkinPart((SkinPart)params.get(0).asInt32())) reply.addString("SkinPart enabled"); else reply.addString("SkinPart not found"); return true; case disable_skin_part: - if(!(params.size()>0 && params.get(0).isInt())){ + if(!(params.size()>0 && params.get(0).isInt32())){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - if(myThread->disableSkinPart((SkinPart)params.get(0).asInt())) + if(myThread->disableSkinPart((SkinPart)params.get(0).asInt32())) reply.addString("SkinPart disabled"); else reply.addString("SkinPart not found"); return true; case is_skin_enabled: - if(!(params.size()>0 && params.get(0).isInt())){ + if(!(params.size()>0 && params.get(0).isInt32())){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - if(myThread->isSkinEnabled((SkinPart)params.get(0).asInt())) + if(myThread->isSkinEnabled((SkinPart)params.get(0).asInt32())) reply.addString("yes"); else reply.addString("no"); @@ -390,13 +390,13 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { case get_pose: { - if(!(params.size()>0 && params.get(0).isInt())){ + if(!(params.size()>0 && params.get(0).isInt32())){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - SkinPart sp = (SkinPart) params.get(0).asInt(); - if(params.size()>1 && params.get(1).isInt()){ - unsigned int taxelId = params.get(1).asInt(); + SkinPart sp = (SkinPart) params.get(0).asInt32(); + if(params.size()>1 && params.get(1).isInt32()){ + unsigned int taxelId = params.get(1).asInt32(); Vector res = myThread->getTaxelPose(sp, taxelId); if(res.size()>0) addToBottle(reply, res); @@ -412,22 +412,22 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { case set_pose: { - if(!(params.size()>6 && params.get(0).isInt() )){ + if(!(params.size()>6 && params.get(0).isInt32() )){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - SkinPart sp = (SkinPart) params.get(0).asInt(); - if(params.get(1).isInt()){ - unsigned int taxelId = params.get(1).asInt(); + SkinPart sp = (SkinPart) params.get(0).asInt32(); + if(params.get(1).isInt32()){ + unsigned int taxelId = params.get(1).asInt32(); Vector pose; if(!bottleToVector(params.tail().tail(), pose)){ reply.addString("ERROR while reading the taxel pose"); return true; } if(myThread->setTaxelPose(sp, taxelId, pose)) - reply.addInt(skin_manager_ok); + reply.addInt32(skin_manager_ok); else{ - reply.addInt(skin_manager_error); + reply.addInt32(skin_manager_error); reply.addString("ERROR: pose was not set"); } } @@ -438,9 +438,9 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { return true; } if(myThread->setTaxelPoses(sp, poses)) - reply.addInt(skin_manager_ok); + reply.addInt32(skin_manager_ok); else{ - reply.addInt(skin_manager_error); + reply.addInt32(skin_manager_error); reply.addString("ERROR: pose was not set"); } } @@ -448,13 +448,13 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { } case get_position: { - if(!(params.size()>0 && params.get(0).isInt())){ + if(!(params.size()>0 && params.get(0).isInt32())){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - SkinPart sp = (SkinPart) params.get(0).asInt(); - if(params.size()>1 && params.get(1).isInt()){ - unsigned int taxelId = params.get(1).asInt(); + SkinPart sp = (SkinPart) params.get(0).asInt32(); + if(params.size()>1 && params.get(1).isInt32()){ + unsigned int taxelId = params.get(1).asInt32(); Vector res = myThread->getTaxelPosition(sp, taxelId); if(res.size()>0) addToBottle(reply, res); @@ -472,22 +472,22 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { } case set_position: { - if(!(params.size()>3 && params.get(0).isInt() )){ + if(!(params.size()>3 && params.get(0).isInt32() )){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - SkinPart sp = (SkinPart) params.get(0).asInt(); - if(params.get(1).isInt()){ - unsigned int taxelId = params.get(1).asInt(); + SkinPart sp = (SkinPart) params.get(0).asInt32(); + if(params.get(1).isInt32()){ + unsigned int taxelId = params.get(1).asInt32(); Vector pose; if(!bottleToVector(params.tail().tail(), pose)){ reply.addString("ERROR while reading the taxel position"); return true; } if(myThread->setTaxelPosition(sp, taxelId, pose)) - reply.addInt(skin_manager_ok); + reply.addInt32(skin_manager_ok); else{ - reply.addInt(skin_manager_error); + reply.addInt32(skin_manager_error); reply.addString("ERROR: position was not set"); } } @@ -498,9 +498,9 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { return true; } if(myThread->setTaxelPositions(sp, poses)) - reply.addInt(skin_manager_ok); + reply.addInt32(skin_manager_ok); else{ - reply.addInt(skin_manager_error); + reply.addInt32(skin_manager_error); reply.addString("ERROR: position was not set"); } } @@ -508,15 +508,15 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { } case get_confidence: { - if(!(params.size()>0 && params.get(0).isInt())){ + if(!(params.size()>0 && params.get(0).isInt32())){ reply.addString(("ERROR: SkinPart is not specified. Params read are: "+string(params.toString().c_str())).c_str()); return true; } - SkinPart sp = (SkinPart) params.get(0).asInt(); - if(params.size()>1 && params.get(1).isInt()){ - unsigned int taxelId = params.get(1).asInt(); + SkinPart sp = (SkinPart) params.get(0).asInt32(); + if(params.size()>1 && params.get(1).isInt32()){ + unsigned int taxelId = params.get(1).asInt32(); double res = myThread->getPoseConfidence(sp, taxelId); - reply.addDouble(res); + reply.addFloat64(res); } else{ Vector res = myThread->getPoseConfidences(sp); @@ -544,19 +544,19 @@ bool skinManager::respond(const Bottle& command, Bottle& reply) { void skinManager::addToBottle(Bottle& b, const Vector& v){ for(unsigned int i=0; i& v){ for(unsigned int i=0; i0) { - switch(command.get(index).asVocab()) + switch(command.get(index).asVocab32()) { - case yarp::os::createVocab('s','u','s','p'): - reply.addVocab(Vocab::encode("ack")); + case yarp::os::createVocab32('s','u','s','p'): + reply.addVocab32("ack"); vc->halt(); cmdSize--; index++; break; - case yarp::os::createVocab('r','u','n'): - reply.addVocab(Vocab::encode("ack")); + case yarp::os::createVocab32('r','u','n'): + reply.addVocab32("ack"); vc->go(); cmdSize--; index++; break; //this set current position reference - case yarp::os::createVocab('s','e','t'): + case yarp::os::createVocab32('s','e','t'): if (command.size()>=3) { - int i=command.get(index+1).asInt(); - double pos=command.get(index+2).asDouble(); + int i=command.get(index+1).asInt32(); + double pos=command.get(index+2).asFloat64(); vc->setRef(i, pos); index +=3; cmdSize-=3; @@ -176,46 +176,46 @@ class VelControlModule: public RFModule { index++; yError("Invalid set message, ignoring\n"); } - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); break; //this set maximum velocity (limiter) - case yarp::os::createVocab('s','v','e','l'): + case yarp::os::createVocab32('s','v','e','l'): if(command.size()>=3) { - int i=command.get(index+1).asInt(); - double vel = command.get(index+2).asDouble(); + int i=command.get(index+1).asInt32(); + double vel = command.get(index+2).asFloat64(); vc->setVel(i,vel); index += 3; cmdSize-=3;; - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else { cmdSize--; index++; yError("Invalid set vel message, ignoring\n"); - reply.addVocab(Vocab::encode("fail")); + reply.addVocab32("fail"); } break; - case yarp::os::createVocab('g','a','i','n'): + case yarp::os::createVocab32('g','a','i','n'): if(command.size()>=3) { - int i=command.get(index+1).asInt(); - double gain = command.get(index+2).asDouble(); + int i=command.get(index+1).asInt32(); + double gain = command.get(index+2).asFloat64(); vc->setGain(i,gain); index+=3; cmdSize-=3; - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else { cmdSize--; index++; yError("Invalid set gain message, ignoring\n"); - reply.addVocab(Vocab::encode("fail")); + reply.addVocab32("fail"); } break; - case yarp::os::createVocab('h','e','l','p'): + case yarp::os::createVocab32('h','e','l','p'): fprintf(stdout,"VelocityControl module, valid commands are:\n"); fprintf(stdout,"- [susp] suspend the controller (command zero velocity)\n"); fprintf(stdout,"- [run] start (and resume after being suspended) the controller\n"); @@ -226,8 +226,8 @@ class VelControlModule: public RFModule { fprintf(stdout,"- [help] to get this help\n"); fprintf(stdout,"\n typical commands:\n gain 0 10\n svel 0 10\n run\n set 0 x\n\n"); - reply.addVocab(Vocab::encode("many")); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("many"); + reply.addVocab32("ack"); reply.addString("VelocityControl module, valid commands are:"); reply.addString("- [susp] suspend the controller (command zero velocity)"); reply.addString("- [run] start (and resume after being suspended) the controller"); @@ -240,7 +240,7 @@ class VelControlModule: public RFModule { break; default: yError("Invalid command, ignoring\n"); - reply.addVocab(Vocab::encode("fail")); + reply.addVocab32("fail"); //cmdSize--; //index++; //return respond(command, reply); // call default @@ -301,7 +301,7 @@ class VelControlModule: public RFModule { ///we start the thread int period = CONTROL_RATE; if(options.check("period")) - period = options.find("period").asInt(); + period = options.find("period").asInt32(); yInfo("control rate is %d ms",period); diff --git a/src/modules/velocityControl/velControlThread.cpp b/src/modules/velocityControl/velControlThread.cpp index 3e57cf27a8..b2c97b40e1 100644 --- a/src/modules/velocityControl/velControlThread.cpp +++ b/src/modules/velocityControl/velControlThread.cpp @@ -56,14 +56,14 @@ void velControlThread::run() int size = bot->size()/2; for(int i=0;iget(2*i).asInt(); + int ind = bot->get(2*i).asInt32(); if(ind < VELOCITY_INDEX_OFFSET) {//this is a position command - targets(ind) = bot->get(2*i+1).asDouble(); + targets(ind) = bot->get(2*i+1).asFloat64(); } else {//this is a velocity command - ffVelocities(ind - VELOCITY_INDEX_OFFSET) = bot->get(2*i+1).asDouble(); + ffVelocities(ind - VELOCITY_INDEX_OFFSET) = bot->get(2*i+1).asFloat64(); } //fprintf(stderr, "for joint *%d, received %f, \t", ind, targets(ind)); } @@ -79,7 +79,7 @@ void velControlThread::run() if (vec!=NULL) { for(int k=0;kget(k).asDouble(); + targets(k)=vec->get(k).asFloat64(); } static int count=0; @@ -282,7 +282,7 @@ void velControlThread::go() imod->getControlMode(k, &mode); if (mode!=VOCAB_CM_MIXED && mode!=VOCAB_CM_VELOCITY) { - std::string s = yarp::os::Vocab::decode(mode); + std::string s = yarp::os::Vocab32::decode(mode); yWarning("Joint (%d) is in mode (%s) and does not accepts velocty commands. You have first to set either VOCAB_CM_VELOCITY or VOCAB_CM_MIXED control mode\n", k, s.c_str()); } } diff --git a/src/modules/velocityObserver/main.cpp b/src/modules/velocityObserver/main.cpp index 1bc271ba26..59e18c430c 100644 --- a/src/modules/velocityObserver/main.cpp +++ b/src/modules/velocityObserver/main.cpp @@ -190,7 +190,7 @@ class dataCollector : public BufferedPort Vector x(sz); for (unsigned int i=0; i void inverseDynamics::broadcastData(T& _values, BufferedPort< void inverseDynamics::writeTorque(Vector _values, int _address, BufferedPort *_port) { Bottle a; - a.addInt(_address); + a.addInt32(_address); for(size_t i=0;i<_values.length();i++) - a.addDouble(_values(i)); + a.addFloat64(_values(i)); _port->prepare() = a; _port->write(); } diff --git a/src/simulators/iCubSimulation/EyeLidsController.cpp b/src/simulators/iCubSimulation/EyeLidsController.cpp index 9a00b4906a..e8daf0c2c9 100644 --- a/src/simulators/iCubSimulation/EyeLidsController.cpp +++ b/src/simulators/iCubSimulation/EyeLidsController.cpp @@ -60,7 +60,7 @@ void EyeLids::checkPort() { Bottle *bot = port.read(false); if (bot!=NULL){ - eyeLidsRotation = (float)bot->get(0).asDouble(); + eyeLidsRotation = (float)bot->get(0).asFloat64(); yDebug("Message received: %s\n",bot->toString().c_str()); bot->clear(); } diff --git a/src/simulators/iCubSimulation/odesdl/VideoTexture.cpp b/src/simulators/iCubSimulation/odesdl/VideoTexture.cpp index ef8bce032f..f6bb029da6 100644 --- a/src/simulators/iCubSimulation/odesdl/VideoTexture.cpp +++ b/src/simulators/iCubSimulation/odesdl/VideoTexture.cpp @@ -78,7 +78,7 @@ void TextureInput::setName(string name) { bool TextureInput::open(Searchable& config) { textureIndex = config.check("textureIndex",Value(-1), - "texture index").asInt(); + "texture index").asInt32(); string texturePort = config.check("port",Value("/texture"),"local port name").asString(); diff --git a/src/simulators/iCubSimulation/odesdl/iCub.cpp b/src/simulators/iCubSimulation/odesdl/iCub.cpp index 1a25f99300..44ef1fd155 100644 --- a/src/simulators/iCubSimulation/odesdl/iCub.cpp +++ b/src/simulators/iCubSimulation/odesdl/iCub.cpp @@ -1358,8 +1358,8 @@ bool ICubSim::loadJointPosition(const char *joints_path){ for(int j=0; j<3; j++) { - jP_leftLeg[5-i][j]=leftJoint->get(j).asDouble(); - jP_rightLeg[5-i][j]=rightJoint->get(j).asDouble(); + jP_leftLeg[5-i][j]=leftJoint->get(j).asFloat64(); + jP_rightLeg[5-i][j]=rightJoint->get(j).asFloat64(); } } @@ -1415,7 +1415,7 @@ bool ICubSim::loadJointPosition(const char *joints_path){ Bottle *headJoint=bHead.get(i+1).asList(); for(int j=0; j<3; j++) - jP_head[i][j]=headJoint->get(j).asDouble(); + jP_head[i][j]=headJoint->get(j).asFloat64(); } /*---- eyes ----*/ @@ -1432,8 +1432,8 @@ bool ICubSim::loadJointPosition(const char *joints_path){ for(int j=0; j<3; j++) { - jP_leftEye[i][j]=leftJoint->get(j).asDouble(); - jP_rightEye[i][j]=rightJoint->get(j).asDouble(); + jP_leftEye[i][j]=leftJoint->get(j).asFloat64(); + jP_rightEye[i][j]=rightJoint->get(j).asFloat64(); } } /*---- inertial ----*/ @@ -1443,7 +1443,7 @@ bool ICubSim::loadJointPosition(const char *joints_path){ for(int j=0; j<3; j++) { - jP_inertial[j] = inertialJP->get(j).asDouble(); + jP_inertial[j] = inertialJP->get(j).asFloat64(); } return true; } @@ -4022,7 +4022,7 @@ void ICubSim::initSkinActivationBottles() } emptySkinActivationHand.clear(); //clear the bottle for(i=0;ihead)[2]; //Add Euler angles roll pitch yaw - inertialReport.addDouble( -yaw * 180/M_PI);// yaw - inertialReport.addDouble( -pitch * 180/M_PI);// pitch - inertialReport.addDouble( roll * 180/M_PI);// roll + inertialReport.addFloat64( -yaw * 180/M_PI);// yaw + inertialReport.addFloat64( -pitch * 180/M_PI);// pitch + inertialReport.addFloat64( roll * 180/M_PI);// roll /*//in order to calculate linear acceleration (make sure of body) Inertial Measurement Unit IMU LinearVel[0] = dBodyGetLinearVel(odeinit._iCub->inertialBody)[0]; @@ -985,19 +985,19 @@ void OdeSdlSimulation::retreiveInertialData(Bottle& inertialReport) { grav3[1]=grav2[0]*sin(theta)+grav2[1]*cos(theta); grav3[2]=grav2[2]; - inertialReport.addDouble( grav3[0] ); - inertialReport.addDouble( grav3[1] ); - inertialReport.addDouble( grav3[2] ); + inertialReport.addFloat64( grav3[0] ); + inertialReport.addFloat64( grav3[1] ); + inertialReport.addFloat64( grav3[2] ); //Add angular velocity - inertialReport.addDouble(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[2]*CTRL_RAD2DEG); - inertialReport.addDouble(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[0]*CTRL_RAD2DEG); - inertialReport.addDouble( dBodyGetAngularVel(odeinit._iCub->inertialBody)[1]*CTRL_RAD2DEG); + inertialReport.addFloat64(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[2]*CTRL_RAD2DEG); + inertialReport.addFloat64(-dBodyGetAngularVel(odeinit._iCub->inertialBody)[0]*CTRL_RAD2DEG); + inertialReport.addFloat64( dBodyGetAngularVel(odeinit._iCub->inertialBody)[1]*CTRL_RAD2DEG); //Add magnetic fields - inertialReport.addDouble(0.0); - inertialReport.addDouble(0.0); - inertialReport.addDouble(0.0); + inertialReport.addFloat64(0.0); + inertialReport.addFloat64(0.0); + inertialReport.addFloat64(0.0); } int OdeSdlSimulation::thread_ode(void *unused) { @@ -1432,21 +1432,21 @@ void OdeSdlSimulation::init(RobotStreamer *streamer, //left Bottle &bCalibLeft=rf_camcalib.findGroup("CAMERA_CALIBRATION_LEFT"); - width_left=bCalibLeft.check("w",Value(320)).asInt(); - height_left=bCalibLeft.check("h",Value(240)).asInt(); + width_left=bCalibLeft.check("w",Value(320)).asInt32(); + height_left=bCalibLeft.check("h",Value(240)).asInt32(); cameraSizeWidth=width_left; cameraSizeHeight=height_left; - double focal_length_left=bCalibLeft.check("fy",Value(257.34)).asDouble(); + double focal_length_left=bCalibLeft.check("fy",Value(257.34)).asFloat64(); fov_left=2*atan2((double)height_left,2*focal_length_left)*180.0/M_PI; //right Bottle &bCalibRight=rf_camcalib.findGroup("CAMERA_CALIBRATION_RIGHT"); - width_right=bCalibRight.check("w",Value(320)).asInt(); - height_right=bCalibRight.check("h",Value(240)).asInt(); + width_right=bCalibRight.check("w",Value(320)).asInt32(); + height_right=bCalibRight.check("h",Value(240)).asInt32(); - double focal_length_right=bCalibRight.check("fy",Value(257.34)).asDouble(); + double focal_length_right=bCalibRight.check("fy",Value(257.34)).asFloat64(); fov_right=2*atan2((double)height_right,2*focal_length_right)*180.0/M_PI; //--------------------------------------// @@ -1625,7 +1625,7 @@ bool OdeSdlSimulation::checkSync(bool reset) { bool OdeSdlSimulation::getTrqData(Bottle data) { OdeInit& odeinit = OdeInit::get(); for (int s=0; storqueData[s] = data.get(s).asDouble(); + odeinit._iCub->torqueData[s] = data.get(s).asFloat64(); //yDebug(stdout,"torques... %lf \n",odeinit._iCub->torqueData[s]); } return true; @@ -1869,42 +1869,42 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_LEFT_HAND].indivTaxelResolution){ for (y = 0; y<=59; y++){ if (contactICubSkinEmulMap[SKIN_LEFT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleLeftHand.addDouble(255.0); + bottleLeftHand.addFloat64(255.0); } else{ - bottleLeftHand.addDouble(0.0); + bottleLeftHand.addFloat64(0.0); } } } else{ //we fill them all for (y = 0; y<=59; y++){ - bottleLeftHand.addDouble(255); //we ignore the thermal pad positions which should be 0s for now + bottleLeftHand.addFloat64(255); //we ignore the thermal pad positions which should be 0s for now } } //zero padding - the port output: 61-96 zeros; taxel IDs 60-95 for (y = 60; y<=95; y++){ - bottleLeftHand.addDouble(0.0); + bottleLeftHand.addFloat64(0.0); } //pam - positions 97-144 palm taxels; taxel IDs have index by one lower (inside these, IDs 107, 119, 131, and 139 are thermal pads ~ 0s); if (contactICubSkinEmulMap[SKIN_LEFT_HAND].indivTaxelResolution){ for (y = 96; y<=143; y++){ if (contactICubSkinEmulMap[SKIN_LEFT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleLeftHand.addDouble(255.0); + bottleLeftHand.addFloat64(255.0); } else{ - bottleLeftHand.addDouble(0.0); + bottleLeftHand.addFloat64(0.0); } } } else{ //we fill the whole palm for (int y = 96; y<=143; y++){ - bottleLeftHand.addDouble(255.0); //we ignore the thermal pad positions, which should be 0s, for now + bottleLeftHand.addFloat64(255.0); //we ignore the thermal pad positions, which should be 0s, for now } } //filling the rest: 145-192 zeros. IDs: 144-191 for (int y = 144; y<=191; y++){ - bottleLeftHand.addDouble(0.0); + bottleLeftHand.addFloat64(0.0); } } else{ @@ -1922,42 +1922,42 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].indivTaxelResolution){ for (y = 0; y<=59; y++){ if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleRightHand.addDouble(255.0); + bottleRightHand.addFloat64(255.0); } else{ - bottleRightHand.addDouble(0.0); + bottleRightHand.addFloat64(0.0); } } } else{ //we fill them all for (y = 0; y<=59; y++){ - bottleRightHand.addDouble(255); //we ignore the thermal pad positions which should be 0s for now + bottleRightHand.addFloat64(255); //we ignore the thermal pad positions which should be 0s for now } } //zero padding - the port output: 61-96 zeros; taxel IDs 60-95 for (y = 60; y<=95; y++){ - bottleRightHand.addDouble(0.0); + bottleRightHand.addFloat64(0.0); } //pam - positions 97-144 palm taxels; taxel IDs have index by one lower (inside these, IDs 107, 119, 131, and 139 are thermal pads ~ 0s); if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].indivTaxelResolution){ for (y = 96; y<=143; y++){ if (contactICubSkinEmulMap[SKIN_RIGHT_HAND].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleRightHand.addDouble(255.0); + bottleRightHand.addFloat64(255.0); } else{ - bottleRightHand.addDouble(0.0); + bottleRightHand.addFloat64(0.0); } } } else{ //we fill the whole palm for (int y = 96; y<=143; y++){ - bottleRightHand.addDouble(255.0); //we ignore the thermal pad positions, which should be 0s, for now + bottleRightHand.addFloat64(255.0); //we ignore the thermal pad positions, which should be 0s, for now } } //filling the rest: 145-192 zeros. IDs: 144-191 for (int y = 144; y<=191; y++){ - bottleRightHand.addDouble(0.0); + bottleRightHand.addFloat64(0.0); } } else{ @@ -1975,10 +1975,10 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].indivTaxelResolution){ for (int y = 0; y<=767; y++){ if (contactICubSkinEmulMap[SKIN_LEFT_UPPER_ARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleLeftArm.addDouble(255.0); + bottleLeftArm.addFloat64(255.0); } else{ - bottleLeftArm.addDouble(0.0); + bottleLeftArm.addFloat64(0.0); } } } @@ -1997,10 +1997,10 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_LEFT_FOREARM].indivTaxelResolution){ for (int y = 0; y<=383; y++){ if (contactICubSkinEmulMap[SKIN_LEFT_FOREARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleLeftForearm.addDouble(255.0); + bottleLeftForearm.addFloat64(255.0); } else{ - bottleLeftForearm.addDouble(0.0); + bottleLeftForearm.addFloat64(0.0); } } } @@ -2019,10 +2019,10 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].indivTaxelResolution){ for (int y = 0; y<=767; y++){ if (contactICubSkinEmulMap[SKIN_RIGHT_UPPER_ARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleRightArm.addDouble(255.0); + bottleRightArm.addFloat64(255.0); } else{ - bottleRightArm.addDouble(0.0); + bottleRightArm.addFloat64(0.0); } } } @@ -2041,10 +2041,10 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].indivTaxelResolution){ for (int y = 0; y<=383; y++){ if (contactICubSkinEmulMap[SKIN_RIGHT_FOREARM].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleRightForearm.addDouble(255.0); + bottleRightForearm.addFloat64(255.0); } else{ - bottleRightForearm.addDouble(0.0); + bottleRightForearm.addFloat64(0.0); } } } @@ -2063,10 +2063,10 @@ void OdeSdlSimulation::inspectWholeBodyContactsAndSendTouch() if (contactICubSkinEmulMap[SKIN_FRONT_TORSO].indivTaxelResolution){ for (int y = 0; y<=767; y++){ if (contactICubSkinEmulMap[SKIN_FRONT_TORSO].taxelsTouched.count(y)){ // if element (taxel ID) is in the set, count returns 1 - bottleTorso.addDouble(255.0); + bottleTorso.addFloat64(255.0); } else{ - bottleTorso.addDouble(0.0); + bottleTorso.addFloat64(0.0); } } } diff --git a/src/simulators/iCubSimulation/wrapper/SimConfig.cpp b/src/simulators/iCubSimulation/wrapper/SimConfig.cpp index 656696dd3e..ea8c884e08 100644 --- a/src/simulators/iCubSimulation/wrapper/SimConfig.cpp +++ b/src/simulators/iCubSimulation/wrapper/SimConfig.cpp @@ -61,7 +61,7 @@ static string configureFinder(int argc, char *argv[], yInfo() << "default module name: " << moduleName; } if ( finder.check( "verbosity" ) ) { - verbosity = finder.find( "verbosity" ).asInt(); + verbosity = finder.find( "verbosity" ).asInt32(); yInfo() << "custom verbosity level: " << verbosity; } else { diff --git a/src/simulators/iCubSimulation/wrapper/SimConfig.h b/src/simulators/iCubSimulation/wrapper/SimConfig.h index ea4b97ec41..be406a57a2 100644 --- a/src/simulators/iCubSimulation/wrapper/SimConfig.h +++ b/src/simulators/iCubSimulation/wrapper/SimConfig.h @@ -155,21 +155,21 @@ class SimConfig : public yarp::os::ResourceFinder, public RobotConfig { Bottle &bParamContacts = bParams.findGroup("CONTACTS"); Bottle &bParamJoints = bParams.findGroup("JOINTS"); - p.worldTimestep = bParamWorld.check("timestep", Value(10)).asInt(); - p.worldCFM = bParamWorld.check("worldCFM", Value(0.00001)).asDouble(); - p.worldERP = bParamWorld.check("worldERP", Value(0.2)).asDouble(); + p.worldTimestep = bParamWorld.check("timestep", Value(10)).asInt32(); + p.worldCFM = bParamWorld.check("worldCFM", Value(0.00001)).asFloat64(); + p.worldERP = bParamWorld.check("worldERP", Value(0.2)).asFloat64(); - p.maxContactCorrectingVel = bParamContacts.check("maxContactCorrectingVel", Value(1e6)).asDouble(); - p.contactFrictionCoefficient = bParamContacts.check("contactFrictionCoefficient",Value(1.0)).asDouble(); - p.contactSurfaceLayer = bParamContacts.check("contactSurfaceLayer", Value(0.0)).asDouble(); - - p.fudgeFactor = bParamJoints.check("fudgeFactor", Value(0.02)).asDouble(); - p.jointCFM = bParamJoints.check("jointCFM", Value(1e-5)).asDouble(); - p.stopCFM = bParamJoints.check("stopCFM", Value(1e-5)).asDouble(); - p.stopERP = bParamJoints.check("stopERP", Value(0.2)).asDouble(); - p.motorMaxTorque = bParamJoints.check("motorMaxTorque", Value(1e3)).asDouble(); - p.motorDryFriction = bParamJoints.check("motorDryFriction", Value(0.1)).asDouble(); - p.jointStopBouncyness = bParamJoints.check("jointStopBouncyness", Value(0.1)).asDouble(); + p.maxContactCorrectingVel = bParamContacts.check("maxContactCorrectingVel", Value(1e6)).asFloat64(); + p.contactFrictionCoefficient = bParamContacts.check("contactFrictionCoefficient",Value(1.0)).asFloat64(); + p.contactSurfaceLayer = bParamContacts.check("contactSurfaceLayer", Value(0.0)).asFloat64(); + + p.fudgeFactor = bParamJoints.check("fudgeFactor", Value(0.02)).asFloat64(); + p.jointCFM = bParamJoints.check("jointCFM", Value(1e-5)).asFloat64(); + p.stopCFM = bParamJoints.check("stopCFM", Value(1e-5)).asFloat64(); + p.stopERP = bParamJoints.check("stopERP", Value(0.2)).asFloat64(); + p.motorMaxTorque = bParamJoints.check("motorMaxTorque", Value(1e3)).asFloat64(); + p.motorDryFriction = bParamJoints.check("motorDryFriction", Value(0.1)).asFloat64(); + p.jointStopBouncyness = bParamJoints.check("jointStopBouncyness", Value(0.1)).asFloat64(); odeParamRead = true; } diff --git a/src/simulators/iCubSimulation/wrapper/WorldManager.cpp b/src/simulators/iCubSimulation/wrapper/WorldManager.cpp index 985193833a..d70be336fd 100644 --- a/src/simulators/iCubSimulation/wrapper/WorldManager.cpp +++ b/src/simulators/iCubSimulation/wrapper/WorldManager.cpp @@ -67,17 +67,17 @@ class ManagerState { bool consume(WorldOpTriplet& x, const char *msg) { if (failed) return false; - bool ok0 = (get(offset).isDouble()||get(offset).isInt()); - bool ok1 = (get(offset+1).isDouble()||get(offset+1).isInt()); - bool ok2 = (get(offset+2).isDouble()||get(offset+2).isInt()); + bool ok0 = (get(offset).isFloat64()||get(offset).isInt32()); + bool ok1 = (get(offset+1).isFloat64()||get(offset+1).isInt32()); + bool ok2 = (get(offset+2).isFloat64()||get(offset+2).isInt32()); x.valid = false; if (!(ok0&&ok1&&ok2)) { fail(msg); return false; } - x.x[0] = get(offset).asDouble(); - x.x[1] = get(offset+1).asDouble(); - x.x[2] = get(offset+2).asDouble(); + x.x[0] = get(offset).asFloat64(); + x.x[1] = get(offset+1).asFloat64(); + x.x[2] = get(offset+2).asFloat64(); x.valid = true; offset += 3; return true; @@ -85,13 +85,13 @@ class ManagerState { bool consume(WorldOpIndex& x, const char *msg) { if (failed) return false; - bool ok = (get(offset).isInt()); + bool ok = (get(offset).isInt32()); x.valid = false; if (!ok) { fail(msg); return false; } - x.index = get(offset).asInt(); + x.index = get(offset).asInt32(); x.valid = true; offset++; return true; @@ -113,13 +113,13 @@ class ManagerState { bool consume(WorldOpScalar& x, const char *msg) { if (failed) return false; - bool ok = (get(offset).isDouble()||get(offset).isInt()); + bool ok = (get(offset).isFloat64()||get(offset).isInt32()); x.valid = false; if (!ok) { fail(msg); return false; } - x.val = get(offset).asDouble(); + x.val = get(offset).asFloat64(); x.valid = true; offset++; return true; @@ -150,7 +150,7 @@ class ManagerState { ok = false; } else - ok = (get(offset).isInt()); + ok = (get(offset).isInt32()); x.valid = false; if (!ok) { @@ -162,7 +162,7 @@ class ManagerState { x.setting = getBool?true:false; } else - x.setting = get(offset).asInt()?true:false; + x.setting = get(offset).asInt32()?true:false; x.valid = true; offset++; @@ -177,61 +177,61 @@ class ManagerState { void consumeKind(ManagerState& state) { state.op.kind = WorldOpName(state.command.get(2).asString()); - int kind = state.command.get(2).asVocab(); + int kind = state.command.get(2).asVocab32(); state.offset++; bool static_obj = false; - //bool mustCollide = state.command.get(2).asVocab() + //bool mustCollide = state.command.get(2).asVocab32() switch (kind) { - case yarp::os::createVocab('s','b','o','x'): + case yarp::os::createVocab32('s','b','o','x'): static_obj = true; - case yarp::os::createVocab('b','o','x'): + case yarp::os::createVocab32('b','o','x'): state.op.kind = "box"; state.op.dynamic = WorldOpFlag(!static_obj); state.needIndex = true; break; - case yarp::os::createVocab('s','c','y','l'): + case yarp::os::createVocab32('s','c','y','l'): static_obj = true; - case yarp::os::createVocab('c','y','l'): + case yarp::os::createVocab32('c','y','l'): state.op.kind = "cyl"; state.op.dynamic = WorldOpFlag(!static_obj); state.needIndex = true; break; - case yarp::os::createVocab('s','s','p','h'): + case yarp::os::createVocab32('s','s','p','h'): static_obj = true; - case yarp::os::createVocab('s','p','h'): + case yarp::os::createVocab32('s','p','h'): state.op.kind = "sph"; state.op.dynamic = WorldOpFlag(!static_obj); state.needIndex = true; break; - case yarp::os::createVocab('s','m','o','d'): + case yarp::os::createVocab32('s','m','o','d'): static_obj = true; - case yarp::os::createVocab('m','o','d','e'): + case yarp::os::createVocab32('m','o','d','e'): state.op.kind = "model"; state.op.dynamic = WorldOpFlag(!static_obj); state.needIndex = true; break; - case yarp::os::createVocab('l','h','a','n'): + case yarp::os::createVocab32('l','h','a','n'): state.op.kind = WorldOpName("hand"); //state.op.name = WorldOpName("icub_left_hand"); state.op.index = WorldOpIndex(1); state.op.dynamic = WorldOpFlag(true); state.op.rightHanded = WorldOpFlag(false); break; - case yarp::os::createVocab('r','h','a','n'): + case yarp::os::createVocab32('r','h','a','n'): state.op.kind = WorldOpName("hand"); //state.op.name = WorldOpName("icub_right_hand"); state.op.index = WorldOpIndex(2); state.op.dynamic = WorldOpFlag(true); state.op.rightHanded = WorldOpFlag(true); break; - case yarp::os::createVocab('m','d','i','r'): + case yarp::os::createVocab32('m','d','i','r'): state.op.parameter = WorldOpFlag(true); break; - case yarp::os::createVocab('t','a','b','l'): - case yarp::os::createVocab('c','u','b','e'): - case yarp::os::createVocab('b','a','l','l'): - case yarp::os::createVocab('s','c','r','e'): - case yarp::os::createVocab('a','l','l'): + case yarp::os::createVocab32('t','a','b','l'): + case yarp::os::createVocab32('c','u','b','e'): + case yarp::os::createVocab32('b','a','l','l'): + case yarp::os::createVocab32('s','c','r','e'): + case yarp::os::createVocab32('a','l','l'): break; default: state.failed = true; @@ -378,7 +378,7 @@ bool WorldManager::respond(const yarp::os::Bottle& command, ManagerState state(command,op,result,*this); reply.clear(); - op.cmd = (WORLD_OP)command.get(1).asVocab(); + op.cmd = (WORLD_OP)command.get(1).asVocab32(); switch (op.cmd) { case WORLD_OP_GET: doGet(state); @@ -413,7 +413,7 @@ bool WorldManager::respond(const yarp::os::Bottle& command, state.debug(); if (!result.success) { if (reply.size()==0) { - reply.addVocab(yarp::os::createVocab('f','a','i','l')); + reply.addVocab32(yarp::os::createVocab32('f','a','i','l')); } if (state.failed) { reply.addString(state.why.c_str()); @@ -427,23 +427,23 @@ bool WorldManager::respond(const yarp::os::Bottle& command, } else { if (reply.size()==0) { if (result.location.isValid()) { - reply.addDouble(result.location.get(0)); - reply.addDouble(result.location.get(1)); - reply.addDouble(result.location.get(2)); + reply.addFloat64(result.location.get(0)); + reply.addFloat64(result.location.get(1)); + reply.addFloat64(result.location.get(2)); } else if (result.rotation.isValid()) { - reply.addDouble(result.rotation.get(0)); - reply.addDouble(result.rotation.get(1)); - reply.addDouble(result.rotation.get(2)); + reply.addFloat64(result.rotation.get(0)); + reply.addFloat64(result.rotation.get(1)); + reply.addFloat64(result.rotation.get(2)); } else if (result.color.isValid()) { - reply.addDouble(result.color.get(0)); - reply.addDouble(result.color.get(1)); - reply.addDouble(result.color.get(2)); + reply.addFloat64(result.color.get(0)); + reply.addFloat64(result.color.get(1)); + reply.addFloat64(result.color.get(2)); } else if (result.count.isValid()) { - reply.addInt(result.count.get()); + reply.addInt32(result.count.get()); } else if (result.path.isValid()) { reply.addString(result.path.get().c_str()); } else { - reply.addVocab(yarp::os::createVocab('o','k')); + reply.addVocab32(yarp::os::createVocab32('o','k')); } } } diff --git a/src/simulators/iCubSimulation/wrapper/WorldOp.cpp b/src/simulators/iCubSimulation/wrapper/WorldOp.cpp index eb0b0108a2..b244dab4de 100644 --- a/src/simulators/iCubSimulation/wrapper/WorldOp.cpp +++ b/src/simulators/iCubSimulation/wrapper/WorldOp.cpp @@ -71,7 +71,7 @@ void show(const WorldOpName& x) { void WorldOp::show() const { yDebug("Operation:\n"); - yDebug(" cmd?: %s\n", yarp::os::Vocab::decode(cmd).c_str()); + yDebug(" cmd?: %s\n", yarp::os::Vocab32::decode(cmd).c_str()); yDebug(" kind: "); ::show(kind); yDebug(" name: "); diff --git a/src/simulators/iCubSimulation/wrapper/WorldOp.h b/src/simulators/iCubSimulation/wrapper/WorldOp.h index 7c0eecfca7..d6c1eed458 100644 --- a/src/simulators/iCubSimulation/wrapper/WorldOp.h +++ b/src/simulators/iCubSimulation/wrapper/WorldOp.h @@ -27,14 +27,14 @@ enum WORLD_OP { WORLD_OP_NULL, - WORLD_OP_GET = yarp::os::createVocab('g','e','t'), - WORLD_OP_SET = yarp::os::createVocab('s','e','t'), - WORLD_OP_MK = yarp::os::createVocab('m','k'), - WORLD_OP_GRAB = yarp::os::createVocab('g','r','a','b'), - WORLD_OP_ROT = yarp::os::createVocab('r','o','t'), - WORLD_OP_DEL = yarp::os::createVocab('d','e','l'), - WORLD_OP_COL = yarp::os::createVocab('c','o','l'), - WORLD_OP_NUM = yarp::os::createVocab('n','u','m'), + WORLD_OP_GET = yarp::os::createVocab32('g','e','t'), + WORLD_OP_SET = yarp::os::createVocab32('s','e','t'), + WORLD_OP_MK = yarp::os::createVocab32('m','k'), + WORLD_OP_GRAB = yarp::os::createVocab32('g','r','a','b'), + WORLD_OP_ROT = yarp::os::createVocab32('r','o','t'), + WORLD_OP_DEL = yarp::os::createVocab32('d','e','l'), + WORLD_OP_COL = yarp::os::createVocab32('c','o','l'), + WORLD_OP_NUM = yarp::os::createVocab32('n','u','m'), }; class WorldOpDatum { diff --git a/src/simulators/iCubSimulation/wrapper/iCubSimulationControl.cpp b/src/simulators/iCubSimulation/wrapper/iCubSimulationControl.cpp index 1b20c099f8..80cf857651 100644 --- a/src/simulators/iCubSimulation/wrapper/iCubSimulationControl.cpp +++ b/src/simulators/iCubSimulation/wrapper/iCubSimulationControl.cpp @@ -94,13 +94,13 @@ bool iCubSimulationControl::open(yarp::os::Searchable& config) { } int TypeArm = p.findGroup("GENERAL").check("Type",Value(1), - "what did the user select?").asInt(); + "what did the user select?").asInt32(); int numTOTjoints = p.findGroup("GENERAL").check("TotalJoints",Value(1), - "Number of total joints").asInt(); + "Number of total joints").asInt32(); double velocity = p.findGroup("GENERAL").check("Vel",Value(1), - "Default velocity").asDouble(); + "Default velocity").asFloat64(); _mutex.lock(); partSelec = TypeArm; @@ -192,37 +192,37 @@ bool iCubSimulationControl::open(yarp::os::Searchable& config) { yError("AxisMap does not have the right number of entries\n"); return false; } - for (int i = 1; i < xtmp.size(); i++) axisMap[i-1] = xtmp.get(i).asInt(); + for (int i = 1; i < xtmp.size(); i++) axisMap[i-1] = xtmp.get(i).asInt32(); xtmp = p.findGroup("GENERAL").findGroup("Encoder","a list of scales for the encoders"); if (xtmp.size() != njoints+1) { yError("Encoder does not have the right number of entries\n"); return false; } - for (int i = 1; i < xtmp.size(); i++) angleToEncoder[i-1] = xtmp.get(i).asDouble(); + for (int i = 1; i < xtmp.size(); i++) angleToEncoder[i-1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("GENERAL").findGroup("fullscalePWM", "a list of scales for the fullscalePWM param"); if (xtmp.size() != njoints + 1) { yError("fullscalePWM does not have the right number of entries\n"); return false; } - for (int i = 1; i < xtmp.size(); i++) dutycycleToPwm[i - 1] = xtmp.get(i).asDouble()/100.0; + for (int i = 1; i < xtmp.size(); i++) dutycycleToPwm[i - 1] = xtmp.get(i).asFloat64()/100.0; xtmp = p.findGroup("GENERAL").findGroup("ampsToSensor", "a list of scales for the ampsToSensor param"); if (xtmp.size() != njoints + 1) { yError("ampsToSensor does not have the right number of entries\n"); return false; } - for (int i = 1; i < xtmp.size(); i++) ampsToSensor[i - 1] = xtmp.get(i).asDouble(); + for (int i = 1; i < xtmp.size(); i++) ampsToSensor[i - 1] = xtmp.get(i).asFloat64(); xtmp = p.findGroup("GENERAL").findGroup("Zeros","a list of offsets for the zero point"); if (xtmp.size() != njoints+1) { yError("Zeros does not have the right number of entries\n"); return false; } - for (int i = 1; i < xtmp.size(); i++) zeros[i-1] = xtmp.get(i).asDouble(); + for (int i = 1; i < xtmp.size(); i++) zeros[i-1] = xtmp.get(i).asFloat64(); - int mj_size = p.findGroup("GENERAL").check("Kinematic_mj_size",Value(0),"Default velocity").asInt(); + int mj_size = p.findGroup("GENERAL").check("Kinematic_mj_size",Value(0),"Default velocity").asInt32(); if (mj_size>0) { xtmp = p.findGroup("GENERAL").findGroup("Kinematic_mj"); @@ -234,7 +234,7 @@ bool iCubSimulationControl::open(yarp::os::Searchable& config) { for (int r = 0; r < mj_size; r++) { int e=r+c*mj_size+1; - kinematic_mj[r][c] = xtmp.get(e).asDouble(); + kinematic_mj[r][c] = xtmp.get(e).asFloat64(); } } @@ -254,7 +254,7 @@ bool iCubSimulationControl::open(yarp::os::Searchable& config) { return false; } for( int i =1;iget(i).asDouble(); + rotToEncoder[i] = bval->get(i).asFloat64(); return true; } else if (key == "gearbox") { - for (int i = 0; i < njoints; i++) gearbox[i] = bval->get(i).asDouble(); return true; + for (int i = 0; i < njoints; i++) gearbox[i] = bval->get(i).asFloat64(); return true; } else if (key == "zeros") { - for (int i = 0; i < njoints; i++) zeros[i] = bval->get(i).asDouble(); return true; + for (int i = 0; i < njoints; i++) zeros[i] = bval->get(i).asFloat64(); return true; } yWarning("setRemoteVariable(): Unknown variable %s", key.c_str()); return false; @@ -2153,7 +2153,7 @@ bool iCubSimulationControl::setControlModeRaw(const int j, const int mode) tmp = ControlModes_yarp2iCubSIM(mode); if(tmp == MODE_UNKNOWN) { - yError() << "setControlModeRaw: unknown control mode " << yarp::os::Vocab::decode(mode); + yError() << "setControlModeRaw: unknown control mode " << yarp::os::Vocab32::decode(mode); } else if (controlMode[j] == VOCAB_CM_HW_FAULT && mode != VOCAB_CM_FORCE_IDLE) { diff --git a/src/simulators/simFaceExpressions/simFaceExp.cpp b/src/simulators/simFaceExpressions/simFaceExp.cpp index 45cb879dcf..2e59ac808b 100644 --- a/src/simulators/simFaceExpressions/simFaceExp.cpp +++ b/src/simulators/simFaceExpressions/simFaceExp.cpp @@ -42,11 +42,11 @@ bool simFaceExp::configure(yarp::os::ResourceFinder &rf) width = options.check("width", Value(512), - "mask width").asInt(); + "mask width").asInt32(); height = options.check("height", Value(512), - "mask height").asInt(); + "mask height").asInt32(); maskPath = rf.findFile("mask"); @@ -118,7 +118,7 @@ bool simFaceExp::updateModule() if ((bot.toString().c_str())[0]=='S') { bot.clear(); - bot.addInt((int)eyeLidPos); + bot.addInt32((int)eyeLidPos); eyeLidsPos.write(bot); yInfo("Eye lids position sent: %s\n",bot.toString().c_str()); } diff --git a/src/tools/canLoader/canLoaderLib/downloader.cpp b/src/tools/canLoader/canLoaderLib/downloader.cpp index 4c3d14d629..d71a24fdb3 100755 --- a/src/tools/canLoader/canLoaderLib/downloader.cpp +++ b/src/tools/canLoader/canLoaderLib/downloader.cpp @@ -162,7 +162,7 @@ int cDownloader::initdriver(Searchable &config, bool verbose) #else m_idriver = new eDriver; #endif - tmp = config.check("canid")?config.find("canid").asInt():CanPacket::everyCANbus; + tmp = config.check("canid")?config.find("canid").asInt32():CanPacket::everyCANbus; if((1 != tmp) && (2 != tmp)) { tmp = CanPacket::everyCANbus; @@ -175,7 +175,7 @@ int cDownloader::initdriver(Searchable &config, bool verbose) #else m_idriver = new cDriver; #endif - tmp = config.check("canDeviceNum")?config.find("canDeviceNum").asInt():99; + tmp = config.check("canDeviceNum")?config.find("canDeviceNum").asInt32():99; } if (0 != (ret = m_idriver->init(config, _verbose))) diff --git a/src/tools/canLoader/canLoaderLib/driver.cpp b/src/tools/canLoader/canLoaderLib/driver.cpp index 7741061a41..e5bdea578f 100644 --- a/src/tools/canLoader/canLoaderLib/driver.cpp +++ b/src/tools/canLoader/canLoaderLib/driver.cpp @@ -205,7 +205,7 @@ eDriver2::~eDriver2() int eDriver2::init(yarp::os::Searchable &config, bool verbose) { - ACE_UINT32 local=(ACE_UINT32)config.find("local").asInt(); + ACE_UINT32 local=(ACE_UINT32)config.find("local").asInt32(); _verbose = verbose; @@ -217,9 +217,9 @@ int eDriver2::init(yarp::os::Searchable &config, bool verbose) return -1; } - mBoardAddr=(ACE_UINT32)config.find("remote").asInt(); + mBoardAddr=(ACE_UINT32)config.find("remote").asInt32(); -// mCanBusId=config.check("canid")?config.find("canid").asInt():0; +// mCanBusId=config.check("canid")?config.find("canid").asInt32():0; //////////////////////////////////// timestart = yarp::os::Time::now(); @@ -608,7 +608,7 @@ void cDriver::destroyBuffer(yarp::dev::CanBuffer &buff) int eDriver::init(yarp::os::Searchable &config) { - ACE_UINT32 local=(ACE_UINT32)config.find("local").asInt(); + ACE_UINT32 local=(ACE_UINT32)config.find("local").asInt32(); if (!mSocket.create(3334,local)) { @@ -616,9 +616,9 @@ void cDriver::destroyBuffer(yarp::dev::CanBuffer &buff) return -1; } - mBoardAddr=(ACE_UINT32)config.find("remote").asInt(); + mBoardAddr=(ACE_UINT32)config.find("remote").asInt32(); - mCanBusId=config.check("canid")?config.find("canid").asInt():0; + mCanBusId=config.check("canid")?config.find("canid").asInt32():0; //////////////////////////////////// timestart = yarp::os::Time::now(); diff --git a/src/tools/controlBoardDumper/dumperThread.cpp b/src/tools/controlBoardDumper/dumperThread.cpp index 81568ff551..4877ceb218 100644 --- a/src/tools/controlBoardDumper/dumperThread.cpp +++ b/src/tools/controlBoardDumper/dumperThread.cpp @@ -160,7 +160,7 @@ void boardDumperThread::run() //for (int i = 0; i < numberOfJointsRead; i++) // { // dataRead[i] = data[dataMap[i]]; - // bData.addDouble(dataRead[i]); + // bData.addFloat64(dataRead[i]); // } //port->write(bData); @@ -176,7 +176,7 @@ void boardDumperThread::run() { //printf("%.2f \n", data[dataMap[i]]); dataRead[i] = data[dataMap[i]]; - bData.addDouble(dataRead[i]); + bData.addFloat64(dataRead[i]); } if (getter->getStamp(stmp)) diff --git a/src/tools/controlBoardDumper/main.cpp b/src/tools/controlBoardDumper/main.cpp index b81077efef..c2b7629275 100644 --- a/src/tools/controlBoardDumper/main.cpp +++ b/src/tools/controlBoardDumper/main.cpp @@ -207,7 +207,7 @@ void getRate(ResourceFinder &rf, int &r) else { Value& rate = rf.find("rate"); - r = rate.asInt(); + r = rate.asInt32(); } } @@ -253,7 +253,7 @@ int getUsedJointsMap(ResourceFinder &rf, int n, int* thetaMap) for (int i = 0; i < n; i++) { - thetaMap[i] = pJoints->get(i).asInt(); + thetaMap[i] = pJoints->get(i).asInt32(); } return 1; } @@ -266,7 +266,7 @@ int getNumberConstraints(ResourceFinder &rf, int &n) return 0; } Value& nJoints = rf.find("nConstr"); - n = nJoints.asInt(); + n = nJoints.asInt32(); return 1; } diff --git a/src/tools/depth2kin/src/main.cpp b/src/tools/depth2kin/src/main.cpp index 0deab87635..aafabe0fc6 100644 --- a/src/tools/depth2kin/src/main.cpp +++ b/src/tools/depth2kin/src/main.cpp @@ -33,7 +33,7 @@ int main(int argc, char *argv[]) rf.setDefault("calibrationFile","calibration_data.ini"); rf.configure(argc,argv); - int test=rf.check("test",Value(-1)).asInt(); + int test=rf.check("test",Value(-1)).asInt32(); if (test<0) { if (!yarp.checkNetwork()) diff --git a/src/tools/depth2kin/src/methods.cpp b/src/tools/depth2kin/src/methods.cpp index 9573c26291..55e495068c 100644 --- a/src/tools/depth2kin/src/methods.cpp +++ b/src/tools/depth2kin/src/methods.cpp @@ -132,13 +132,13 @@ bool Calibrator::toProperty(Property &info) const Bottle data; Bottle &values=data.addList(); values.addString(spatialCompetence.extrapolation?"true":"false"); - values.addDouble(spatialCompetence.scale); - values.addDouble(spatialCompetence.c[0]); - values.addDouble(spatialCompetence.c[1]); - values.addDouble(spatialCompetence.c[2]); + values.addFloat64(spatialCompetence.scale); + values.addFloat64(spatialCompetence.c[0]); + values.addFloat64(spatialCompetence.c[1]); + values.addFloat64(spatialCompetence.c[2]); for (int r=0; rget(0).asString()=="true"); - spatialCompetence.scale=values->get(1).asDouble(); - spatialCompetence.c[0]=values->get(2).asDouble(); - spatialCompetence.c[1]=values->get(3).asDouble(); - spatialCompetence.c[2]=values->get(4).asDouble(); + spatialCompetence.scale=values->get(1).asFloat64(); + spatialCompetence.c[0]=values->get(2).asFloat64(); + spatialCompetence.c[1]=values->get(3).asFloat64(); + spatialCompetence.c[2]=values->get(4).asFloat64(); int r=0; int c=0; for (int i=5; isize(); i++) { - spatialCompetence.A(r,c)=values->get(i).asDouble(); + spatialCompetence.A(r,c)=values->get(i).asFloat64(); if (++c>=spatialCompetence.A.cols()) { c=0; @@ -294,10 +294,10 @@ bool MatrixCalibrator::toProperty(Property &info) const { Bottle data; Bottle &values=data.addList(); - values.addDouble(scale); + values.addFloat64(scale); for (int r=0; rget(0).asDouble(); + scale=values->get(0).asFloat64(); int r=0; int c=0; for (int i=1; isize(); i++) { - H(r,c)=values->get(i).asDouble(); + H(r,c)=values->get(i).asFloat64(); if (++c>=H.cols()) { c=0; diff --git a/src/tools/depth2kin/src/module.cpp b/src/tools/depth2kin/src/module.cpp index 067edb70ff..78204c0a09 100644 --- a/src/tools/depth2kin/src/module.cpp +++ b/src/tools/depth2kin/src/module.cpp @@ -232,7 +232,7 @@ double CalibModule::getMinVer() const { Bottle info; igaze->getInfo(info); - return info.find("min_allowed_vergence").asDouble(); + return info.find("min_allowed_vergence").asFloat64(); } @@ -252,7 +252,7 @@ bool CalibModule::getGazeParams(const string &eye, const string &type, Matrix &M int cnt=0; for (int r=0; rget(cnt++).asDouble(); + M(r,c)=pB->get(cnt++).asFloat64(); return true; } @@ -273,7 +273,7 @@ bool CalibModule::pushExtrinsics(const string &eye, const Matrix &H) Bottle &val=ext.addList(); for (int r=0; rtweakSet(options); } @@ -283,8 +283,8 @@ bool CalibModule::pushExtrinsics(const string &eye, const Matrix &H) bool CalibModule::getDepth(const Vector &px, Vector &x, Vector &pxr) { Bottle cmd,reply; - cmd.addInt((int)px[0]); - cmd.addInt((int)px[1]); + cmd.addInt32((int)px[0]); + cmd.addInt32((int)px[1]); depthRpcPort.write(cmd,reply); if (reply.size()<5) @@ -292,11 +292,11 @@ bool CalibModule::getDepth(const Vector &px, Vector &x, Vector &pxr) x.resize(3); pxr.resize(2); - x[0]=reply.get(0).asDouble(); - x[1]=reply.get(1).asDouble(); - x[2]=reply.get(2).asDouble(); - pxr[0]=reply.get(3).asInt(); - pxr[1]=reply.get(4).asInt(); + x[0]=reply.get(0).asFloat64(); + x[1]=reply.get(1).asFloat64(); + x[2]=reply.get(2).asFloat64(); + pxr[0]=reply.get(3).asInt32(); + pxr[1]=reply.get(4).asInt32(); return (norm(x)>0.0); } @@ -892,13 +892,13 @@ bool CalibModule::configure(ResourceFinder &rf) string robot=rf.check("robot",Value("icub")).asString(); string name=rf.check("name",Value("depth2kin")).asString(); string type=rf.check("type",Value("se3+scale")).asString(); - test=rf.check("test",Value(-1)).asInt(); - max_dist=fabs(rf.check("max_dist",Value(0.25)).asDouble()); - roi_side=abs(rf.check("roi_side",Value(100)).asInt()); - block_eyes=fabs(rf.check("block_eyes",Value(5.0)).asDouble()); - exploration_wait=fabs(rf.check("exploration_wait",Value(0.5)).asDouble()); - exploration_intargettol=fabs(rf.check("exploration_intargettol",Value(0.01)).asDouble()); - touch_intargettol=fabs(rf.check("touch_intargettol",Value(0.001)).asDouble()); + test=rf.check("test",Value(-1)).asInt32(); + max_dist=fabs(rf.check("max_dist",Value(0.25)).asFloat64()); + roi_side=abs(rf.check("roi_side",Value(100)).asInt32()); + block_eyes=fabs(rf.check("block_eyes",Value(5.0)).asFloat64()); + exploration_wait=fabs(rf.check("exploration_wait",Value(0.5)).asFloat64()); + exploration_intargettol=fabs(rf.check("exploration_intargettol",Value(0.01)).asFloat64()); + touch_intargettol=fabs(rf.check("touch_intargettol",Value(0.001)).asFloat64()); motorExplorationAsyncStop=false; motorExplorationState=motorExplorationStateIdle; @@ -1774,7 +1774,7 @@ bool CalibModule::updateModule() if (Bottle *touchData=touchInPort.read(false)) { if (touchData->size()>=2) - touch(touchData->get(0).asInt(),touchData->get(1).asInt()); + touch(touchData->get(0).asInt32(),touchData->get(1).asInt32()); } return !closing; diff --git a/src/tools/embObjProtoTools/boardTransceiver/boardTransceiver.cpp b/src/tools/embObjProtoTools/boardTransceiver/boardTransceiver.cpp index 12b4395751..032c2f868e 100644 --- a/src/tools/embObjProtoTools/boardTransceiver/boardTransceiver.cpp +++ b/src/tools/embObjProtoTools/boardTransceiver/boardTransceiver.cpp @@ -108,7 +108,7 @@ bool BoardTransceiver::configure(yarp::os::ResourceFinder &rf) yDebug() << " I have all params I need!!"; Bottle parameter1( rf.find("PC104IpAddress").asString() ); - int port = rf.find("port").asInt(); // .get(1).asInt(); + int port = rf.find("port").asInt32(); // .get(1).asInt32(); strcpy(_fId.PC104ipAddr.string, parameter1.toString().c_str()); _fId.PC104ipAddr.port = port; @@ -837,12 +837,12 @@ const eOnvset_DEVcfg_t * BoardTransceiver::getNVset_DEVcfg(yarp::os::Searchable else { // ok, retrieve the numbers ... - number = config.find("endpointManagementIsSupported").asInt(); + number = config.find("endpointManagementIsSupported").asInt32(); protcfg.ep_management_is_present = (0 == number) ? (eobool_false) : (eobool_true); if(eobool_true == protcfg.ep_management_is_present) { - protcfg.en_mn_entity_comm_numberof = config.find("entityMNcommunicationNumberOf").asInt(); - protcfg.en_mn_entity_appl_numberof = config.find("entityMNapplicationNumberOf").asInt(); + protcfg.en_mn_entity_comm_numberof = config.find("entityMNcommunicationNumberOf").asInt32(); + protcfg.en_mn_entity_appl_numberof = config.find("entityMNapplicationNumberOf").asInt32(); } else { @@ -874,13 +874,13 @@ const eOnvset_DEVcfg_t * BoardTransceiver::getNVset_DEVcfg(yarp::os::Searchable } else { - number = config.find("endpointMotionControlIsSupported").asInt(); + number = config.find("endpointMotionControlIsSupported").asInt32(); protcfg.ep_motioncontrol_is_present = (0 == number) ? (eobool_false) : (eobool_true); if(eobool_true == protcfg.ep_motioncontrol_is_present) { - protcfg.en_mc_entity_joint_numberof = config.find("entityMCjointNumberOf").asInt(); - protcfg.en_mc_entity_motor_numberof = config.find("entityMCmotorNumberOf").asInt(); - protcfg.en_mc_entity_controller_numberof = config.find("entityMCcontrollerNumberOf").asInt(); + protcfg.en_mc_entity_joint_numberof = config.find("entityMCjointNumberOf").asInt32(); + protcfg.en_mc_entity_motor_numberof = config.find("entityMCmotorNumberOf").asInt32(); + protcfg.en_mc_entity_controller_numberof = config.find("entityMCcontrollerNumberOf").asInt32(); } else { @@ -914,13 +914,13 @@ const eOnvset_DEVcfg_t * BoardTransceiver::getNVset_DEVcfg(yarp::os::Searchable } else { - number = config.find("endpointAnalogSensorsIsSupported").asInt(); + number = config.find("endpointAnalogSensorsIsSupported").asInt32(); protcfg.ep_analogsensors_is_present = (0 == number) ? (eobool_false) : (eobool_true); if(eobool_true == protcfg.ep_analogsensors_is_present) { - protcfg.en_as_entity_strain_numberof = config.find("entityASstrainNumberOf").asInt(); - protcfg.en_as_entity_mais_numberof = config.find("entityASmaisNumberOf").asInt(); - protcfg.en_as_entity_extorque_numberof = config.find("entityASextorqueNumberOf").asInt(); + protcfg.en_as_entity_strain_numberof = config.find("entityASstrainNumberOf").asInt32(); + protcfg.en_as_entity_mais_numberof = config.find("entityASmaisNumberOf").asInt32(); + protcfg.en_as_entity_extorque_numberof = config.find("entityASextorqueNumberOf").asInt32(); } else { @@ -951,11 +951,11 @@ const eOnvset_DEVcfg_t * BoardTransceiver::getNVset_DEVcfg(yarp::os::Searchable } else { - number = config.find("endpointSkinIsSupported").asInt(); + number = config.find("endpointSkinIsSupported").asInt32(); protcfg.ep_skin_is_present = (0 == number) ? (eobool_false) : (eobool_true); if(eobool_true == protcfg.ep_skin_is_present) { - protcfg.en_sk_entity_skin_numberof = config.find("entitySKskinNumberOf").asInt(); + protcfg.en_sk_entity_skin_numberof = config.find("entitySKskinNumberOf").asInt32(); } else { diff --git a/src/tools/fingersTuner/main.cpp b/src/tools/fingersTuner/main.cpp index 2ff5a37f39..6f34c3bda8 100644 --- a/src/tools/fingersTuner/main.cpp +++ b/src/tools/fingersTuner/main.cpp @@ -198,13 +198,13 @@ class Tuner joint<<"joint_"<size(); j++) { - int k=bIdlingJoints->get(j).asInt(); + int k=bIdlingJoints->get(j).asInt32(); int l; for (l=0; lget(0).asDouble()); - pid.st_down=floor(pResults.find("stiction").asList()->get(1).asDouble()); + pid.st_up=floor(pResults.find("stiction").asList()->get(0).asFloat64()); + pid.st_down=floor(pResults.find("stiction").asList()->get(1).asFloat64()); yInfo("Stiction values: up = %g; down = %g",pid.st_up,pid.st_down); IControlMode *imod; @@ -420,7 +420,7 @@ class Tuner name=bGeneral.check("name",Value("fingersTuner")).asString(); robot=bGeneral.check("robot",Value("icub")).asString(); - double ping_robot_tmo=bGeneral.check("ping_robot_tmo",Value(0.0)).asDouble(); + double ping_robot_tmo=bGeneral.check("ping_robot_tmo",Value(0.0)).asFloat64(); device=bPart.find("device").asString(); if (Bottle *rj=bGeneral.find("relevantJoints").asList()) @@ -431,7 +431,7 @@ class Tuner return false; } - int numAlias=bGeneral.check("numAlias",Value(0)).asInt(); + int numAlias=bGeneral.check("numAlias",Value(0)).asInt32(); for (int i=0; i::iterator it=alias.find(sel.asString()); @@ -490,7 +490,7 @@ class Tuner for (int i=0; i::iterator it=pids.find(j); if (it==pids.end()) continue; @@ -519,8 +519,8 @@ class Tuner bool tune(const Value &sel) { Bottle joints; - if (sel.isInt()) - joints.addInt(sel.asInt()); + if (sel.isInt32()) + joints.addInt32(sel.asInt32()); else if (sel.isString()) { map::iterator it=alias.find(sel.asString()); @@ -534,7 +534,7 @@ class Tuner for (int i=0; i::iterator it=pids.find(j); if (it==pids.end()) continue; @@ -568,7 +568,7 @@ class Tuner for (int i=0; iheight(); if (Window->check("PosX",val)||Window->check("x",val)){ - posX = val->asInt(); + posX = val->asInt32(); } if (Window->check("PosY",val)||Window->check("y",val)){ - posY = val->asInt(); + posY = val->asInt32(); } if (Window->check("width",val)){ - width = val->asInt(); + width = val->asInt32(); } if (Window->check("height",val)){ - height = val->asInt(); + height = val->asInt32(); } window->resize(width,height); diff --git a/src/tools/iCubGui/src/animationview.cpp b/src/tools/iCubGui/src/animationview.cpp index 3a32957547..ce78b1ccf3 100644 --- a/src/tools/iCubGui/src/animationview.cpp +++ b/src/tools/iCubGui/src/animationview.cpp @@ -77,10 +77,10 @@ void AnimationView::init(yarp::os::ResourceFinder& config) if (!skinParams.isNull()) { ForceArrow::setParams( - skinParams.find("force_gain").asDouble(), - skinParams.find("force_thr").asDouble(), - skinParams.find("torque_gain").asDouble(), - skinParams.find("torque_thr").asDouble() + skinParams.find("force_gain").asFloat64(), + skinParams.find("force_thr").asFloat64(), + skinParams.find("torque_gain").asFloat64(), + skinParams.find("torque_thr").asFloat64() ); } diff --git a/src/tools/iCubGui/src/main.cpp b/src/tools/iCubGui/src/main.cpp index 55f01fd013..d781ec1661 100644 --- a/src/tools/iCubGui/src/main.cpp +++ b/src/tools/iCubGui/src/main.cpp @@ -53,27 +53,27 @@ * * // object dimensions in millimiters * // (it will be displayed as an ellipsoid with the tag "my_object_name") -* obj.addDouble(dimX); -* obj.addDouble(dimY); -* obj.addDouble(dimZ); +* obj.addFloat64(dimX); +* obj.addFloat64(dimY); +* obj.addFloat64(dimZ); * * // object position in millimiters * // reference frame: X=fwd, Y=left, Z=up -* obj.addDouble(posX); -* obj.addDouble(posY); -* obj.addDouble(posZ); +* obj.addFloat64(posX); +* obj.addFloat64(posY); +* obj.addFloat64(posZ); * * // object orientation (roll, pitch, yaw) in degrees -* obj.addDouble(rotX); -* obj.addDouble(rotY); -* obj.addDouble(rotZ); +* obj.addFloat64(rotX); +* obj.addFloat64(rotY); +* obj.addFloat64(rotZ); * * // object color (0-255) -* obj.addInt(R); -* obj.addInt(G); -* obj.addInt(B); +* obj.addInt32(R); +* obj.addInt32(G); +* obj.addInt32(B); * // transparency (0.0=invisible 1.0=solid) -* obj.addDouble(alpha); +* obj.addFloat64(alpha); * \endcode * * To delete an object: diff --git a/src/tools/iCubGui/src/objectsthread.h b/src/tools/iCubGui/src/objectsthread.h index 5b804f3cee..d87acc1bad 100644 --- a/src/tools/iCubGui/src/objectsthread.h +++ b/src/tools/iCubGui/src/objectsthread.h @@ -277,23 +277,23 @@ void ObjectsManager::manage(yarp::os::Bottle *msg) std::string name(msg->get(idd++).asString().c_str()); std::string label(cmd=="object_with_label"?msg->get(idd++).asString().c_str():""); - double dx=msg->get(idd++).asDouble(); - double dy=msg->get(idd++).asDouble(); - double dz=msg->get(idd++).asDouble(); + double dx=msg->get(idd++).asFloat64(); + double dy=msg->get(idd++).asFloat64(); + double dz=msg->get(idd++).asFloat64(); - double px=msg->get(idd++).asDouble(); - double py=msg->get(idd++).asDouble(); - double pz=msg->get(idd++).asDouble(); + double px=msg->get(idd++).asFloat64(); + double py=msg->get(idd++).asFloat64(); + double pz=msg->get(idd++).asFloat64(); - double rx=msg->get(idd++).asDouble(); - double ry=msg->get(idd++).asDouble(); - double rz=msg->get(idd++).asDouble(); + double rx=msg->get(idd++).asFloat64(); + double ry=msg->get(idd++).asFloat64(); + double rz=msg->get(idd++).asFloat64(); - int r=msg->get(idd++).asInt(); - int g=msg->get(idd++).asInt(); - int b=msg->get(idd++).asInt(); + int r=msg->get(idd++).asInt32(); + int g=msg->get(idd++).asInt32(); + int b=msg->get(idd++).asInt32(); - double alpha=msg->get(idd++).asDouble(); + double alpha=msg->get(idd++).asFloat64(); for (int i=0; i<(int)mObjectsRoot.size(); ++i) { @@ -332,15 +332,15 @@ void ObjectsManager::manage(yarp::os::Bottle *msg) std::string name(msg->get(1).asString().c_str()); std::string label(msg->get(2).asString().c_str()); - int bufflen=msg->get(3).asInt(); - double persistence=msg->get(4).asDouble(); + int bufflen=msg->get(3).asInt32(); + double persistence=msg->get(4).asFloat64(); - int R=msg->get(5).asInt(); - int G=msg->get(6).asInt(); - int B=msg->get(7).asInt(); + int R=msg->get(5).asInt32(); + int G=msg->get(6).asInt32(); + int B=msg->get(7).asInt32(); - double alpha=msg->get(8).asDouble(); - GLfloat width=(GLfloat)msg->get(9).asDouble(); + double alpha=msg->get(8).asFloat64(); + GLfloat width=(GLfloat)msg->get(9).asFloat64(); for (int i=0; i<(int)mTrajectoriesRoot.size(); ++i) { @@ -378,9 +378,9 @@ void ObjectsManager::manage(yarp::os::Bottle *msg) { std::string name(msg->get(1).asString().c_str()); - double x=msg->get(2).asDouble(); - double y=msg->get(3).asDouble(); - double z=msg->get(4).asDouble(); + double x=msg->get(2).asFloat64(); + double y=msg->get(3).asFloat64(); + double z=msg->get(4).asFloat64(); for (int i=0; i<(int)mTrajectoriesRoot.size(); ++i) { diff --git a/src/tools/iCubGui/src/qavimator.cpp b/src/tools/iCubGui/src/qavimator.cpp index b64e833b5a..216156e2fd 100644 --- a/src/tools/iCubGui/src/qavimator.cpp +++ b/src/tools/iCubGui/src/qavimator.cpp @@ -64,10 +64,10 @@ qavimator::qavimator(yarp::os::ResourceFinder &config, QWidget *parent) : GUI_NAME=std::string("/")+GUI_NAME; } if (config.check("width")){ - width=config.find("width").asInt(); + width=config.find("width").asInt32(); } if (config.check("height")){ - height=config.find("height").asInt(); + height=config.find("height").asInt32(); } //sanity check @@ -82,10 +82,10 @@ qavimator::qavimator(yarp::os::ResourceFinder &config, QWidget *parent) : int xpos=32,ypos=32; if (config.check("xpos")){ - xpos=config.find("xpos").asInt(); + xpos=config.find("xpos").asInt32(); } if (config.check("ypos")){ - ypos=config.find("ypos").asInt(); + ypos=config.find("ypos").asInt32(); } this->move(xpos,ypos); diff --git a/src/tools/iCubSkinGui/plugin/SkinMeshThreadPort.cpp b/src/tools/iCubSkinGui/plugin/SkinMeshThreadPort.cpp index 60a4cba8cf..496b31044c 100644 --- a/src/tools/iCubSkinGui/plugin/SkinMeshThreadPort.cpp +++ b/src/tools/iCubSkinGui/plugin/SkinMeshThreadPort.cpp @@ -48,8 +48,8 @@ SkinMeshThreadPort::SkinMeshThreadPort(Searchable& config,int period) : Periodic skin_port_virtual.open(part_virtual); } - int width =config.find("width" ).asInt(); - int height=config.find("height").asInt(); + int width =config.find("width" ).asInt32(); + int height=config.find("height").asInt32(); bool useCalibration = config.check("useCalibration"); if (useCalibration==true) yInfo("Using calibrated skin values (0-255)"); @@ -59,15 +59,15 @@ SkinMeshThreadPort::SkinMeshThreadPort(Searchable& config,int period) : Periodic unsigned char r=255, g=0, b=0; if(color) { - if(color->size()<3 || !color->get(0).isInt() || !color->get(1).isInt() || !color->get(2).isInt()) + if(color->size()<3 || !color->get(0).isInt32() || !color->get(1).isInt32() || !color->get(2).isInt32()) { yError("Error while reading the parameter color: three integer values should be specified (%s).", color->toString().c_str()); } else { - r = color->get(0).asInt(); - g = color->get(1).asInt(); - b = color->get(2).asInt(); + r = color->get(0).asInt32(); + g = color->get(1).asInt32(); + b = color->get(2).asInt32(); yInfo("Using specified color: %d %d %d", r, g, b); } } @@ -79,7 +79,7 @@ SkinMeshThreadPort::SkinMeshThreadPort(Searchable& config,int period) : Periodic defaultColor.push_back(g); defaultColor.push_back(b); - skinThreshold = config.check("skinThreshold")?config.find("skinThreshold").asDouble():SKIN_THRESHOLD; + skinThreshold = config.check("skinThreshold")?config.find("skinThreshold").asFloat64():SKIN_THRESHOLD; yDebug("Skin Threshold set to %g", skinThreshold); yarp::os::Bottle sensorSetConfig=config.findGroup("SENSORS").tail(); @@ -104,13 +104,13 @@ SkinMeshThreadPort::SkinMeshThreadPort(Searchable& config,int period) : Periodic type == "cer_sh_td" || type == "cer_sh_tp") { - int id=sensorConfig.get(1).asInt(); - double xc=sensorConfig.get(2).asDouble(); - double yc=sensorConfig.get(3).asDouble(); - double th=sensorConfig.get(4).asDouble(); - double gain=sensorConfig.get(5).asDouble(); - int lrMirror=sensorConfig.get(6).asInt(); - int layoutNum=sensorConfig.get(7).asInt(); + int id=sensorConfig.get(1).asInt32(); + double xc=sensorConfig.get(2).asFloat64(); + double yc=sensorConfig.get(3).asFloat64(); + double th=sensorConfig.get(4).asFloat64(); + double gain=sensorConfig.get(5).asFloat64(); + int lrMirror=sensorConfig.get(6).asInt32(); + int layoutNum=sensorConfig.get(7).asInt32(); yDebug("%s %d %f",type.c_str(),id,gain); @@ -244,7 +244,7 @@ void SkinMeshThreadPort::run() skin_value.resize(input->size(),0.0); for (int i=0; isize(); i++) { - skin_value[i]=input->get(i).asDouble(); + skin_value[i]=input->get(i).asFloat64(); } } @@ -260,12 +260,12 @@ void SkinMeshThreadPort::run() for (int i=0; isize(); i++) { - skin_value_virtual[i] = data_virtual->get(i).asDouble(); + skin_value_virtual[i] = data_virtual->get(i).asFloat64(); } for (int i = 0; isize(); i++) { - skin_color_virtual.push_back(color_virtual->get(i).asInt()); + skin_color_virtual.push_back(color_virtual->get(i).asInt32()); } yTrace("Virtual contacts: %s",skin_value_virtual.toString(3,3).c_str()); diff --git a/src/tools/iCubSkinGui/plugin/include/SkinMeshThreadCan.h b/src/tools/iCubSkinGui/plugin/include/SkinMeshThreadCan.h index a48e46ae9a..0b5123d48f 100644 --- a/src/tools/iCubSkinGui/plugin/include/SkinMeshThreadCan.h +++ b/src/tools/iCubSkinGui/plugin/include/SkinMeshThreadCan.h @@ -62,14 +62,14 @@ class SkinMeshThreadCan : public PeriodicThread } netId=7; deviceName="cfw2can"; - cardId=0x300 | (config.find("cardid").asInt() << 4); - netId=config.find("CanDeviceNum").asInt(); + cardId=0x300 | (config.find("cardid").asInt32() << 4); + netId=config.find("CanDeviceNum").asInt32(); deviceName=config.find("CanDeviceName").asString(); std::string part="/skinGui/"; part.append(config.find("robotPart").asString()); part.append(":i"); - int width =config.find("width" ).asInt(); - int height=config.find("height").asInt(); + int width =config.find("width" ).asInt32(); + int height=config.find("height").asInt32(); bool useCalibration = config.check("useCalibration"); if (useCalibration==true) { @@ -90,13 +90,13 @@ class SkinMeshThreadCan : public PeriodicThread std::string type(sensorConfig.get(0).asString()); if (type == "triangle" || type == "fingertip" || type == "fingertip2L" || type == "cer_sh_pdl" || type == "fingertip2R" || type == "triangle_10pad" || type == "quad16" || type == "palmR" || type == "palmL") { - int id=sensorConfig.get(1).asInt(); - double xc=sensorConfig.get(2).asDouble(); - double yc=sensorConfig.get(3).asDouble(); - double th=sensorConfig.get(4).asDouble(); - double gain=sensorConfig.get(5).asDouble(); - int lrMirror=sensorConfig.get(6).asInt(); - int layoutNum=sensorConfig.get(7).asInt(); + int id=sensorConfig.get(1).asInt32(); + double xc=sensorConfig.get(2).asFloat64(); + double yc=sensorConfig.get(3).asFloat64(); + double th=sensorConfig.get(4).asFloat64(); + double gain=sensorConfig.get(5).asFloat64(); + int lrMirror=sensorConfig.get(6).asInt32(); + int layoutNum=sensorConfig.get(7).asInt32(); printf("%d %f\n",id,gain); diff --git a/src/tools/iCubSkinGui/plugin/qticubskinguiplugin.cpp b/src/tools/iCubSkinGui/plugin/qticubskinguiplugin.cpp index 0ac5f65dc5..c7fb53f552 100644 --- a/src/tools/iCubSkinGui/plugin/qticubskinguiplugin.cpp +++ b/src/tools/iCubSkinGui/plugin/qticubskinguiplugin.cpp @@ -265,13 +265,13 @@ bool QtICubSkinGuiPlugin::parseParameters(QStringList params) return false; } - gWidth =rf.find("width" ).asInt(); - gHeight=rf.find("height").asInt(); + gWidth =rf.find("width" ).asInt32(); + gHeight=rf.find("height").asInt32(); if (rf.check("xpos")){ - gXpos=rf.find("xpos").asInt(); + gXpos=rf.find("xpos").asInt32(); } if (rf.check("ypos")){ - gYpos=rf.find("ypos").asInt(); + gYpos=rf.find("ypos").asInt32(); } bool useCan = rf.check("useCan"); @@ -329,7 +329,7 @@ void QtICubSkinGuiPlugin::onTimeout() void QtICubSkinGuiPlugin::onInit() { - int period = rf.check("period")?rf.find("period").asInt():50; + int period = rf.check("period")?rf.find("period").asInt32():50; if (TheadType==TYPE_CAN) { diff --git a/src/tools/imageBlender/main.cpp b/src/tools/imageBlender/main.cpp index bca42332d1..3719c6a0c0 100644 --- a/src/tools/imageBlender/main.cpp +++ b/src/tools/imageBlender/main.cpp @@ -93,12 +93,12 @@ int main(int argc, char *argv[]) size_t start_ly = 0; double alpha1 = 0.5; double alpha2 = 0.5; - if (rf.check("rx")) start_rx = (size_t) rf.find("rx").asDouble(); - if (rf.check("ry")) start_ry = (size_t) rf.find("ry").asDouble(); - if (rf.check("lx")) start_lx = (size_t) rf.find("lx").asDouble(); - if (rf.check("ly")) start_ly = (size_t) rf.find("ly").asDouble(); - if (rf.check("alpha1")) alpha1 = rf.find("alpha1").asDouble(); - if (rf.check("alpha2")) alpha2 = rf.find("alpha2").asDouble(); + if (rf.check("rx")) start_rx = (size_t) rf.find("rx").asFloat64(); + if (rf.check("ry")) start_ry = (size_t) rf.find("ry").asFloat64(); + if (rf.check("lx")) start_lx = (size_t) rf.find("lx").asFloat64(); + if (rf.check("ly")) start_ly = (size_t) rf.find("ly").asFloat64(); + if (rf.check("alpha1")) alpha1 = rf.find("alpha1").asFloat64(); + if (rf.check("alpha2")) alpha2 = rf.find("alpha2").asFloat64(); yDebug("left offset:%lu,%lu right offset:%lu,%lu, alpha1:%f, alpha2:%f", start_lx, start_ly, start_rx, start_ry, alpha1, alpha2); if (rf.check("help")) { diff --git a/src/tools/imageCropper/main.cpp b/src/tools/imageCropper/main.cpp index 8c7524784b..7872549634 100644 --- a/src/tools/imageCropper/main.cpp +++ b/src/tools/imageCropper/main.cpp @@ -51,10 +51,10 @@ int main(int argc, char *argv[]) size_t start_y = 0; size_t width = 0; size_t height = 0; - if (rf.check("x_off")) start_x = (size_t) rf.find("x_off").asDouble(); - if (rf.check("y_off")) start_y = (size_t) rf.find("y_off").asDouble(); - if (rf.check("width")) width = (size_t)rf.find("width").asDouble(); - if (rf.check("height")) height = (size_t)rf.find("height").asDouble(); + if (rf.check("x_off")) start_x = (size_t) rf.find("x_off").asFloat64(); + if (rf.check("y_off")) start_y = (size_t) rf.find("y_off").asFloat64(); + if (rf.check("width")) width = (size_t)rf.find("width").asFloat64(); + if (rf.check("height")) height = (size_t)rf.find("height").asFloat64(); yDebug("x_off %lu, y_off %lu, width %lu, height %lu", start_x, start_y, width, height); if (rf.check("help")) { diff --git a/src/tools/joystickCtrl/main.cpp b/src/tools/joystickCtrl/main.cpp index 393e7ec1ef..1bdadd7e84 100644 --- a/src/tools/joystickCtrl/main.cpp +++ b/src/tools/joystickCtrl/main.cpp @@ -196,7 +196,7 @@ class CtrlThread: public PeriodicThread if (rf.findGroup("INPUTS").check("InputsNumber")) { - num_inputs = rf.findGroup("INPUTS").find("InputsNumber").asInt(); + num_inputs = rf.findGroup("INPUTS").find("InputsNumber").asInt32(); inputMax = new double [num_inputs]; inputMin = new double [num_inputs]; outputMax = new double [num_inputs]; @@ -217,44 +217,44 @@ class CtrlThread: public PeriodicThread b = rf.findGroup("INPUTS").findGroup("Reverse"); if (b.size()-1 == num_inputs) { - for (int i = 1; i < b.size(); i++) reverse[i-1] = b.get(i).asInt(); + for (int i = 1; i < b.size(); i++) reverse[i-1] = b.get(i).asInt32(); } else {yError ( "Configuration error: invalid number of entries 'Reverse'\n"); return false;} b = rf.findGroup("INPUTS").findGroup("InputMax"); if (b.size()-1 == num_inputs) { - for (int i = 1; i < b.size(); i++) inputMax[i-1] = b.get(i).asDouble(); + for (int i = 1; i < b.size(); i++) inputMax[i-1] = b.get(i).asFloat64(); } else {yError ( "Configuration error: invalid number of entries 'InputMax'\n"); return false;} b = rf.findGroup("INPUTS").findGroup("InputMin"); if (b.size()-1 == num_inputs) { - for (int i = 1; i < b.size(); i++) inputMin[i-1] = b.get(i).asDouble(); + for (int i = 1; i < b.size(); i++) inputMin[i-1] = b.get(i).asFloat64(); } else {yError ( "Configuration error: invalid number of entries 'InputMin'\n"); return false;} b = rf.findGroup("INPUTS").findGroup("OutputMax"); if (b.size()-1 == num_inputs) { - for (int i = 1; i < b.size(); i++) outputMax[i-1] = b.get(i).asDouble(); + for (int i = 1; i < b.size(); i++) outputMax[i-1] = b.get(i).asFloat64(); } else {yError ( "Configuration error: invalid number of entries 'OutputMax'\n"); return false;} b = rf.findGroup("INPUTS").findGroup("OutputMin"); if (b.size()-1 == num_inputs) { - for (int i = 1; i < b.size(); i++) outputMin[i-1] = b.get(i).asDouble(); + for (int i = 1; i < b.size(); i++) outputMin[i-1] = b.get(i).asFloat64(); } else {yError ( "Configuration error: invalid number of entries 'OutputMin'\n"); return false;} b = rf.findGroup("INPUTS").findGroup("Deadband"); if (b.size()-1 == num_inputs) { - for (int i = 1; i < b.size(); i++) jointDeadband[i-1] = b.get(i).asDouble(); + for (int i = 1; i < b.size(); i++) jointDeadband[i-1] = b.get(i).asFloat64(); } else {yError ( "Configuration error: invalid number of entries 'Deadband'\n"); return false;} if (rf.findGroup("OUTPUTS").check("OutputsNumber")) { - num_outputs = rf.findGroup("OUTPUTS").find("OutputsNumber").asInt(); + num_outputs = rf.findGroup("OUTPUTS").find("OutputsNumber").asInt32(); jointProperties = new struct_jointProperties [num_outputs]; } else @@ -276,15 +276,15 @@ class CtrlThread: public PeriodicThread if (b.get(1).asString()=="polar_r_theta") { jointProperties[i].type=JTYPE_POLAR; - jointProperties[i].param[0]=b.get(2).asInt(); - jointProperties[i].param[1]=b.get(3).asInt(); - jointProperties[i].param[2]=b.get(4).asInt(); + jointProperties[i].param[0]=b.get(2).asInt32(); + jointProperties[i].param[1]=b.get(3).asInt32(); + jointProperties[i].param[2]=b.get(4).asInt32(); } else if (b.get(1).asString()=="cartesian_xyz") { jointProperties[i].type=JTYPE_CARTESIAN; - jointProperties[i].param[0]=b.get(2).asInt(); + jointProperties[i].param[0]=b.get(2).asInt32(); jointProperties[i].param[1]=0; jointProperties[i].param[2]=0; } @@ -292,7 +292,7 @@ class CtrlThread: public PeriodicThread if (b.get(1).asString()=="constant") { jointProperties[i].type=JTYPE_CONSTANT; - jointProperties[i].param[0]=b.get(2).asInt(); + jointProperties[i].param[0]=b.get(2).asInt32(); jointProperties[i].param[1]=0; jointProperties[i].param[2]=0; } @@ -439,7 +439,7 @@ class CtrlThread: public PeriodicThread // choose between multiple joysticks if (rf.findGroup("GENERAL").check("DefaultJoystickNumber")) { - joy_id = rf.findGroup("GENERAL").find("DefaultJoystickNumber").asInt(); + joy_id = rf.findGroup("GENERAL").find("DefaultJoystickNumber").asInt32(); yInfo ( "Multiple joysticks found, using #%d, as specified in the configuration options\n", joy_id); } else @@ -727,15 +727,15 @@ class CtrlThread: public PeriodicThread if ( jointProperties[i].type == JTYPE_STRING) data.addString(jointProperties[i].param_s.c_str()); else - data.addDouble(outAxes[i]); + data.addFloat64(outAxes[i]); } for (int i=0;i \n", Vocab::decode(VOCAB_PWMCONTROL_REF_PWM).c_str()); - printf(" [get] [%s] \n", Vocab::decode(VOCAB_PWMCONTROL_REF_PWM).c_str()); - printf(" [get] [%s]\n", Vocab::decode(VOCAB_PWMCONTROL_PWM_OUTPUT).c_str()); + printf("IPWMControl:\ntype [%s] and one of the following:\n", Vocab32::decode(VOCAB_PWMCONTROL_INTERFACE).c_str()); + printf(" [set] [%s] \n", Vocab32::decode(VOCAB_PWMCONTROL_REF_PWM).c_str()); + printf(" [get] [%s] \n", Vocab32::decode(VOCAB_PWMCONTROL_REF_PWM).c_str()); + printf(" [get] [%s]\n", Vocab32::decode(VOCAB_PWMCONTROL_PWM_OUTPUT).c_str()); printf("\n"); - printf("IControlMode:\ntype [%s] and one of the following:\n", Vocab::decode(VOCAB_ICONTROLMODE).c_str()); + printf("IControlMode:\ntype [%s] and one of the following:\n", Vocab32::decode(VOCAB_ICONTROLMODE).c_str()); printf(" [set] [%s]|[%s]|[%s]|[%s]|[%s]|[%s]|[%s]|[%s]|[%s][%s]|[%s]\n", - Vocab::decode(VOCAB_CM_POSITION).c_str(), - Vocab::decode(VOCAB_CM_POSITION_DIRECT).c_str(), - Vocab::decode(VOCAB_CM_VELOCITY).c_str(), - Vocab::decode(VOCAB_CM_MIXED).c_str(), - Vocab::decode(VOCAB_CM_TORQUE).c_str(), - Vocab::decode(VOCAB_CM_PWM).c_str(), - Vocab::decode(VOCAB_CM_CURRENT).c_str(), - Vocab::decode(VOCAB_CM_IDLE).c_str(), - Vocab::decode(VOCAB_CM_FORCE_IDLE).c_str(), - Vocab::decode(VOCAB_CM_IMPEDANCE_POS).c_str(), - Vocab::decode(VOCAB_CM_IMPEDANCE_VEL).c_str()); - printf(" [get] [%s] \n", Vocab::decode(VOCAB_CM_CONTROL_MODE).c_str()); + Vocab32::decode(VOCAB_CM_POSITION).c_str(), + Vocab32::decode(VOCAB_CM_POSITION_DIRECT).c_str(), + Vocab32::decode(VOCAB_CM_VELOCITY).c_str(), + Vocab32::decode(VOCAB_CM_MIXED).c_str(), + Vocab32::decode(VOCAB_CM_TORQUE).c_str(), + Vocab32::decode(VOCAB_CM_PWM).c_str(), + Vocab32::decode(VOCAB_CM_CURRENT).c_str(), + Vocab32::decode(VOCAB_CM_IDLE).c_str(), + Vocab32::decode(VOCAB_CM_FORCE_IDLE).c_str(), + Vocab32::decode(VOCAB_CM_IMPEDANCE_POS).c_str(), + Vocab32::decode(VOCAB_CM_IMPEDANCE_VEL).c_str()); + printf(" [get] [%s] \n", Vocab32::decode(VOCAB_CM_CONTROL_MODE).c_str()); printf("\n"); - printf("ITorqueControl:\ntype [%s] and one of the following:\n", Vocab::decode(VOCAB_TORQUE).c_str()); - printf(" [get] [%s] to read the measured torque for a single axis\n", Vocab::decode(VOCAB_TRQ).c_str()); - printf(" [get] [%s] to read the measured torque for all axes\n", Vocab::decode(VOCAB_TRQS).c_str()); - printf(" [set] [%s] to set the reference torque for a single axis\n", Vocab::decode(VOCAB_REF).c_str()); - printf(" [set] [%s] to set the reference torque for all axes\n", Vocab::decode(VOCAB_REFS).c_str()); - printf(" [set] [%s] int '('')' '('')' to set the reference torque for a subset of axes axes\n", Vocab::decode(VOCAB_REFG).c_str()); - printf(" [get] [%s] to read the reference torque for a single axis\n", Vocab::decode(VOCAB_REF).c_str()); - printf(" [get] [%s] to read the reference torque for all axes\n", Vocab::decode(VOCAB_REFS).c_str()); + printf("ITorqueControl:\ntype [%s] and one of the following:\n", Vocab32::decode(VOCAB_TORQUE).c_str()); + printf(" [get] [%s] to read the measured torque for a single axis\n", Vocab32::decode(VOCAB_TRQ).c_str()); + printf(" [get] [%s] to read the measured torque for all axes\n", Vocab32::decode(VOCAB_TRQS).c_str()); + printf(" [set] [%s] to set the reference torque for a single axis\n", Vocab32::decode(VOCAB_REF).c_str()); + printf(" [set] [%s] to set the reference torque for all axes\n", Vocab32::decode(VOCAB_REFS).c_str()); + printf(" [set] [%s] int '('')' '('')' to set the reference torque for a subset of axes axes\n", Vocab32::decode(VOCAB_REFG).c_str()); + printf(" [get] [%s] to read the reference torque for a single axis\n", Vocab32::decode(VOCAB_REF).c_str()); + printf(" [get] [%s] to read the reference torque for all axes\n", Vocab32::decode(VOCAB_REFS).c_str()); printf("\n"); - printf("IImpedanceControl:\ntype [%s] and one of the following:\n", Vocab::decode(VOCAB_IMPEDANCE).c_str()); - printf(" [set] [%s] \n", Vocab::decode(VOCAB_IMP_PARAM).c_str()); - printf(" [set] [%s] \n\n", Vocab::decode(VOCAB_IMP_OFFSET).c_str()); - printf(" [get] [%s] \n", Vocab::decode(VOCAB_IMP_PARAM).c_str()); - printf(" [get] [%s] \n", Vocab::decode(VOCAB_IMP_OFFSET).c_str()); + printf("IImpedanceControl:\ntype [%s] and one of the following:\n", Vocab32::decode(VOCAB_IMPEDANCE).c_str()); + printf(" [set] [%s] \n", Vocab32::decode(VOCAB_IMP_PARAM).c_str()); + printf(" [set] [%s] \n\n", Vocab32::decode(VOCAB_IMP_OFFSET).c_str()); + printf(" [get] [%s] \n", Vocab32::decode(VOCAB_IMP_PARAM).c_str()); + printf(" [get] [%s] \n", Vocab32::decode(VOCAB_IMP_OFFSET).c_str()); printf("\n"); - printf("IInteractionMode:\ntype [%s] and one of the following:\n", Vocab::decode(VOCAB_INTERFACE_INTERACTION_MODE).c_str()); - printf(" [set] [%s]|[%s] \n", Vocab::decode(VOCAB_IM_STIFF).c_str(), Vocab::decode(VOCAB_IM_COMPLIANT).c_str()); - printf(" [get] [%s] \n", Vocab::decode(VOCAB_INTERACTION_MODE).c_str()); - printf(" [get] [%s] \n", Vocab::decode(VOCAB_INTERACTION_MODES).c_str()); + printf("IInteractionMode:\ntype [%s] and one of the following:\n", Vocab32::decode(VOCAB_INTERFACE_INTERACTION_MODE).c_str()); + printf(" [set] [%s]|[%s] \n", Vocab32::decode(VOCAB_IM_STIFF).c_str(), Vocab32::decode(VOCAB_IM_COMPLIANT).c_str()); + printf(" [get] [%s] \n", Vocab32::decode(VOCAB_INTERACTION_MODE).c_str()); + printf(" [get] [%s] \n", Vocab32::decode(VOCAB_INTERACTION_MODES).c_str()); printf("\n"); printf("IMotor Interfaces:\n"); printf("type [get] and one of the following:\n"); - printf(" [%s] to read get the number of motors\n", Vocab::decode(VOCAB_MOTORS_NUMBER).c_str()); - printf(" [%s] to read the temperature value for a single motor\n", Vocab::decode(VOCAB_TEMPERATURE).c_str()); - printf(" [%s] to read the temperatures of all motors\n", Vocab::decode(VOCAB_TEMPERATURES).c_str()); - printf(" [%s] to read the temperature limit for a single motor\n", Vocab::decode(VOCAB_TEMPERATURE_LIMIT).c_str()); + printf(" [%s] to read get the number of motors\n", Vocab32::decode(VOCAB_MOTORS_NUMBER).c_str()); + printf(" [%s] to read the temperature value for a single motor\n", Vocab32::decode(VOCAB_TEMPERATURE).c_str()); + printf(" [%s] to read the temperatures of all motors\n", Vocab32::decode(VOCAB_TEMPERATURES).c_str()); + printf(" [%s] to read the temperature limit for a single motor\n", Vocab32::decode(VOCAB_TEMPERATURE_LIMIT).c_str()); printf("type [set] and one of the following:\n"); - printf(" [%s] to set the temperature limit for a single motor\n", Vocab::decode(VOCAB_TEMPERATURE_LIMIT).c_str()); + printf(" [%s] to set the temperature limit for a single motor\n", Vocab32::decode(VOCAB_TEMPERATURE_LIMIT).c_str()); printf("\n"); printf("IMotorEncoder Interfaces:\n"); printf("type [get] and one of the following:\n"); - printf(" [%s] to read the cpr value for a single motor\n", Vocab::decode(VOCAB_MOTOR_CPR).c_str()); - printf(" [%s] to read get the number of motor encoders\n", Vocab::decode(VOCAB_MOTOR_ENCODER_NUMBER).c_str()); - printf(" [%s] to read the motor encoder positions for all motors\n", Vocab::decode(VOCAB_MOTOR_ENCODERS).c_str()); - printf(" [%s] to read the motor encoder speeds for all motors\n", Vocab::decode(VOCAB_MOTOR_ENCODER_SPEEDS).c_str()); - printf(" [%s] to read the motor encoder accelerations for all motors\n", Vocab::decode(VOCAB_MOTOR_ENCODER_ACCELERATIONS).c_str()); + printf(" [%s] to read the cpr value for a single motor\n", Vocab32::decode(VOCAB_MOTOR_CPR).c_str()); + printf(" [%s] to read get the number of motor encoders\n", Vocab32::decode(VOCAB_MOTOR_ENCODER_NUMBER).c_str()); + printf(" [%s] to read the motor encoder positions for all motors\n", Vocab32::decode(VOCAB_MOTOR_ENCODERS).c_str()); + printf(" [%s] to read the motor encoder speeds for all motors\n", Vocab32::decode(VOCAB_MOTOR_ENCODER_SPEEDS).c_str()); + printf(" [%s] to read the motor encoder accelerations for all motors\n", Vocab32::decode(VOCAB_MOTOR_ENCODER_ACCELERATIONS).c_str()); printf("\n"); printf("Standard Interfaces:\n"); printf("type [get] and one of the following:\n"); - printf(" [%s] to read the number of controlled axes\n", Vocab::decode(VOCAB_AXES).c_str()); - printf(" [%s] to read the name of a single axis\n", Vocab::decode(VOCAB_INFO_NAME).c_str()); - printf(" [%s] to read target position for a single axis (iPositionControl)\n", Vocab::decode(VOCAB_POSITION_MOVE).c_str()); - printf(" [%s] to read target positions for all axes (iPositionControl)\n", Vocab::decode(VOCAB_POSITION_MOVES).c_str()); - printf(" [%s] to read reference position for single axis (iPositionDirect)\n", Vocab::decode(VOCAB_POSITION_DIRECT).c_str()); - printf(" [%s] to read reference position for all axes (iPositionDirect)\n", Vocab::decode(VOCAB_POSITION_DIRECTS).c_str()); - printf(" [%s] to read reference velocity for single axis (for velocityMove)\n", Vocab::decode(VOCAB_VELOCITY_MOVE).c_str()); - printf(" [%s] to read reference velocities for all axes (for velocityMove)\n", Vocab::decode(VOCAB_VELOCITY_MOVES).c_str()); - printf(" [%s] to read the encoder value for all axes\n", Vocab::decode(VOCAB_ENCODERS).c_str()); - printf(" [%s] to read the PID values for all axes\n", Vocab::decode(VOCAB_PIDS).c_str()); - printf(" [%s] to read the PID values for a single axis\n", Vocab::decode(VOCAB_PID).c_str()); - printf(" [%s] to read the position limits for a single axis\n", Vocab::decode(VOCAB_LIMITS).c_str()); - printf(" [%s] to read the velocity limits for a single axis\n", Vocab::decode(VOCAB_VEL_LIMITS).c_str()); - printf(" [%s] to read the PID error for all axes\n", Vocab::decode(VOCAB_ERRS).c_str()); - printf(" [%s] to read the PID output for all axes\n", Vocab::decode(VOCAB_OUTPUTS).c_str()); - printf(" [%s] to read the reference position for all axes\n", Vocab::decode(VOCAB_REFERENCES).c_str()); - printf(" [%s] to read the reference position for a single axis\n", Vocab::decode(VOCAB_REFERENCE).c_str()); - printf(" [%s] to read the reference speed for all axes\n", Vocab::decode(VOCAB_REF_SPEEDS).c_str()); - printf(" [%s] to read the reference speed for a single axis\n", Vocab::decode(VOCAB_REF_SPEED).c_str()); - printf(" [%s] to read the reference acceleration for all axes\n", Vocab::decode(VOCAB_REF_ACCELERATIONS).c_str()); - printf(" [%s] to read the reference acceleration for a single axis\n", Vocab::decode(VOCAB_REF_ACCELERATION).c_str()); - printf(" [%s] to read the current consumption for all axes\n", Vocab::decode(VOCAB_AMP_CURRENTS).c_str()); - printf(" [%s] to get the nominal current for a motor\n", Vocab::decode(VOCAB_AMP_NOMINAL_CURRENT).c_str()); - printf(" [%s] to get the peak current for a motor\n", Vocab::decode(VOCAB_AMP_PEAK_CURRENT).c_str()); - printf(" [%s] to get the PWM output for a motor\n", Vocab::decode(VOCAB_AMP_PWM).c_str()); - printf(" [%s] to get the PWM limit for a motor\n", Vocab::decode(VOCAB_AMP_PWM_LIMIT).c_str()); - printf(" [%s] to get the power supply voltage for a single motor\n", Vocab::decode(VOCAB_AMP_VOLTAGE_SUPPLY).c_str()); - printf(" [%s] to get the current limit of single motor\n", Vocab::decode(VOCAB_AMP_MAXCURRENT).c_str()); - printf(" [%s] to check motionDone on a single motor\n", Vocab::decode(VOCAB_MOTION_DONE).c_str()); - printf(" [%s] to check motionDone on all motors \n", Vocab::decode(VOCAB_MOTION_DONES).c_str()); - printf(" [%s] to check motionDone on all motors using multiple functions\n", Vocab::decode(VOCAB_MOTION_DONE_GROUP).c_str()); + printf(" [%s] to read the number of controlled axes\n", Vocab32::decode(VOCAB_AXES).c_str()); + printf(" [%s] to read the name of a single axis\n", Vocab32::decode(VOCAB_INFO_NAME).c_str()); + printf(" [%s] to read target position for a single axis (iPositionControl)\n", Vocab32::decode(VOCAB_POSITION_MOVE).c_str()); + printf(" [%s] to read target positions for all axes (iPositionControl)\n", Vocab32::decode(VOCAB_POSITION_MOVES).c_str()); + printf(" [%s] to read reference position for single axis (iPositionDirect)\n", Vocab32::decode(VOCAB_POSITION_DIRECT).c_str()); + printf(" [%s] to read reference position for all axes (iPositionDirect)\n", Vocab32::decode(VOCAB_POSITION_DIRECTS).c_str()); + printf(" [%s] to read reference velocity for single axis (for velocityMove)\n", Vocab32::decode(VOCAB_VELOCITY_MOVE).c_str()); + printf(" [%s] to read reference velocities for all axes (for velocityMove)\n", Vocab32::decode(VOCAB_VELOCITY_MOVES).c_str()); + printf(" [%s] to read the encoder value for all axes\n", Vocab32::decode(VOCAB_ENCODERS).c_str()); + printf(" [%s] to read the PID values for all axes\n", Vocab32::decode(VOCAB_PIDS).c_str()); + printf(" [%s] to read the PID values for a single axis\n", Vocab32::decode(VOCAB_PID).c_str()); + printf(" [%s] to read the position limits for a single axis\n", Vocab32::decode(VOCAB_LIMITS).c_str()); + printf(" [%s] to read the velocity limits for a single axis\n", Vocab32::decode(VOCAB_VEL_LIMITS).c_str()); + printf(" [%s] to read the PID error for all axes\n", Vocab32::decode(VOCAB_ERRS).c_str()); + printf(" [%s] to read the PID output for all axes\n", Vocab32::decode(VOCAB_OUTPUTS).c_str()); + printf(" [%s] to read the reference position for all axes\n", Vocab32::decode(VOCAB_REFERENCES).c_str()); + printf(" [%s] to read the reference position for a single axis\n", Vocab32::decode(VOCAB_REFERENCE).c_str()); + printf(" [%s] to read the reference speed for all axes\n", Vocab32::decode(VOCAB_REF_SPEEDS).c_str()); + printf(" [%s] to read the reference speed for a single axis\n", Vocab32::decode(VOCAB_REF_SPEED).c_str()); + printf(" [%s] to read the reference acceleration for all axes\n", Vocab32::decode(VOCAB_REF_ACCELERATIONS).c_str()); + printf(" [%s] to read the reference acceleration for a single axis\n", Vocab32::decode(VOCAB_REF_ACCELERATION).c_str()); + printf(" [%s] to read the current consumption for all axes\n", Vocab32::decode(VOCAB_AMP_CURRENTS).c_str()); + printf(" [%s] to get the nominal current for a motor\n", Vocab32::decode(VOCAB_AMP_NOMINAL_CURRENT).c_str()); + printf(" [%s] to get the peak current for a motor\n", Vocab32::decode(VOCAB_AMP_PEAK_CURRENT).c_str()); + printf(" [%s] to get the PWM output for a motor\n", Vocab32::decode(VOCAB_AMP_PWM).c_str()); + printf(" [%s] to get the PWM limit for a motor\n", Vocab32::decode(VOCAB_AMP_PWM_LIMIT).c_str()); + printf(" [%s] to get the power supply voltage for a single motor\n", Vocab32::decode(VOCAB_AMP_VOLTAGE_SUPPLY).c_str()); + printf(" [%s] to get the current limit of single motor\n", Vocab32::decode(VOCAB_AMP_MAXCURRENT).c_str()); + printf(" [%s] to check motionDone on a single motor\n", Vocab32::decode(VOCAB_MOTION_DONE).c_str()); + printf(" [%s] to check motionDone on all motors \n", Vocab32::decode(VOCAB_MOTION_DONES).c_str()); + printf(" [%s] to check motionDone on all motors using multiple functions\n", Vocab32::decode(VOCAB_MOTION_DONE_GROUP).c_str()); printf("\n"); printf("type [set] and one of the following:\n"); - printf(" [%s] to move a single axis\n", Vocab::decode(VOCAB_POSITION_MOVE).c_str()); - printf(" [%s] to accelerate a single axis to a given speed\n", Vocab::decode(VOCAB_VELOCITY_MOVE).c_str()); - printf(" [%s] to set the reference speed for a single axis\n", Vocab::decode(VOCAB_REF_SPEED).c_str()); - printf(" [%s] to set the reference acceleration for a single axis\n", Vocab::decode(VOCAB_REF_ACCELERATION).c_str()); - printf(" [%s] to move multiple axes\n", Vocab::decode(VOCAB_POSITION_MOVES).c_str()); - printf(" [%s] to accelerate multiple axes to a given speed\n", Vocab::decode(VOCAB_VELOCITY_MOVES).c_str()); - printf(" [%s] to set the reference speed for all axes\n", Vocab::decode(VOCAB_REF_SPEEDS).c_str()); - printf(" [%s] to set the reference acceleration for all axes\n", Vocab::decode(VOCAB_REF_ACCELERATIONS).c_str()); - printf(" [%s] to stop a single axis\n", Vocab::decode(VOCAB_STOP).c_str()); - printf(" [%s] to stop all axes\n", Vocab::decode(VOCAB_STOPS).c_str()); - printf(" [%s] to move single axis using position direct\n", Vocab::decode(VOCAB_POSITION_DIRECT).c_str()); - printf(" [%s] to move multiple axes using position direct\n", Vocab::decode(VOCAB_POSITION_DIRECTS).c_str()); - printf(" [%s] to set the PID values for a single axis\n", Vocab::decode(VOCAB_PID).c_str()); - printf(" [%s] to set the limits for a single axis\n", Vocab::decode(VOCAB_LIMITS).c_str()); - printf(" [%s] to disable the PID control for a single axis\n", Vocab::decode(VOCAB_DISABLE).c_str()); - printf(" [%s] to enable the PID control for a single axis\n", Vocab::decode(VOCAB_ENABLE).c_str()); - printf(" [%s] to set the encoder value for a single axis\n", Vocab::decode(VOCAB_ENCODER).c_str()); - printf(" [%s] to set the encoder value for all axes\n", Vocab::decode(VOCAB_ENCODERS).c_str()); - printf(" [%s] to set the current limit for single motor\n", Vocab::decode(VOCAB_AMP_MAXCURRENT).c_str()); - printf(" [%s] to set the peak current for a motor\n", Vocab::decode(VOCAB_AMP_PEAK_CURRENT).c_str()); - printf(" [%s] to set the PWM limit for a motor\n", Vocab::decode(VOCAB_AMP_PWM_LIMIT).c_str()); + printf(" [%s] to move a single axis\n", Vocab32::decode(VOCAB_POSITION_MOVE).c_str()); + printf(" [%s] to accelerate a single axis to a given speed\n", Vocab32::decode(VOCAB_VELOCITY_MOVE).c_str()); + printf(" [%s] to set the reference speed for a single axis\n", Vocab32::decode(VOCAB_REF_SPEED).c_str()); + printf(" [%s] to set the reference acceleration for a single axis\n", Vocab32::decode(VOCAB_REF_ACCELERATION).c_str()); + printf(" [%s] to move multiple axes\n", Vocab32::decode(VOCAB_POSITION_MOVES).c_str()); + printf(" [%s] to accelerate multiple axes to a given speed\n", Vocab32::decode(VOCAB_VELOCITY_MOVES).c_str()); + printf(" [%s] to set the reference speed for all axes\n", Vocab32::decode(VOCAB_REF_SPEEDS).c_str()); + printf(" [%s] to set the reference acceleration for all axes\n", Vocab32::decode(VOCAB_REF_ACCELERATIONS).c_str()); + printf(" [%s] to stop a single axis\n", Vocab32::decode(VOCAB_STOP).c_str()); + printf(" [%s] to stop all axes\n", Vocab32::decode(VOCAB_STOPS).c_str()); + printf(" [%s] to move single axis using position direct\n", Vocab32::decode(VOCAB_POSITION_DIRECT).c_str()); + printf(" [%s] to move multiple axes using position direct\n", Vocab32::decode(VOCAB_POSITION_DIRECTS).c_str()); + printf(" [%s] to set the PID values for a single axis\n", Vocab32::decode(VOCAB_PID).c_str()); + printf(" [%s] to set the limits for a single axis\n", Vocab32::decode(VOCAB_LIMITS).c_str()); + printf(" [%s] to disable the PID control for a single axis\n", Vocab32::decode(VOCAB_DISABLE).c_str()); + printf(" [%s] to enable the PID control for a single axis\n", Vocab32::decode(VOCAB_ENABLE).c_str()); + printf(" [%s] to set the encoder value for a single axis\n", Vocab32::decode(VOCAB_ENCODER).c_str()); + printf(" [%s] to set the encoder value for all axes\n", Vocab32::decode(VOCAB_ENCODERS).c_str()); + printf(" [%s] to set the current limit for single motor\n", Vocab32::decode(VOCAB_AMP_MAXCURRENT).c_str()); + printf(" [%s] to set the peak current for a motor\n", Vocab32::decode(VOCAB_AMP_PEAK_CURRENT).c_str()); + printf(" [%s] to set the PWM limit for a motor\n", Vocab32::decode(VOCAB_AMP_PWM_LIMIT).c_str()); printf("\n"); printf("NOTES: - A list is a sequence of numbers in parenthesis, e.g. (10 2 1 10)\n"); @@ -325,11 +325,11 @@ int main(int argc, char *argv[]) if (options.check("debug")) { - //#define VOCAB_CM_HW_FAULT yarp::os::createVocab('h','w','f','a') - //#define VOCAB_CM_CALIBRATING yarp::os::createVocab('c','a','l') // the joint is calibrating - //#define VOCAB_CM_CALIB_DONE yarp::os::createVocab('c','a','l','d') // calibration succesfully completed - //#define VOCAB_CM_NOT_CONFIGURED yarp::os::createVocab('c','f','g','n') // missing initial configuration (default value at start-up) - //#define VOCAB_CM_CONFIGURED yarp::os::createVocab('c','f','g','y') // initial configuration completed, if any + //#define VOCAB_CM_HW_FAULT yarp::os::createVocab32('h','w','f','a') + //#define VOCAB_CM_CALIBRATING yarp::os::createVocab32('c','a','l') // the joint is calibrating + //#define VOCAB_CM_CALIB_DONE yarp::os::createVocab32('c','a','l','d') // calibration succesfully completed + //#define VOCAB_CM_NOT_CONFIGURED yarp::os::createVocab32('c','f','g','n') // missing initial configuration (default value at start-up) + //#define VOCAB_CM_CONFIGURED yarp::os::createVocab32('c','f','g','y') // initial configuration completed, if any printf("DEBUG NOTES: (hidden debug commands wich may break the robot! do not use!\n"); printf("- icdd set hwfa 1 : will try to force joint 1 in hw fault\n"); printf("- icdd set cal 1 : \n"); @@ -380,7 +380,7 @@ int main(int argc, char *argv[]) } case VOCAB_GET: - switch(p.get(1).asVocab()) + switch(p.get(1).asVocab32()) { case VOCAB_POSITION_MOVE: { @@ -390,7 +390,7 @@ int main(int argc, char *argv[]) break; } double ref; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); bool ret = ipos->getTargetPosition(j, &ref); printf("Ref joint %d is %.2f - [ret val is %s]\n", j, ref, ret?"true":"false"); } @@ -404,7 +404,7 @@ int main(int argc, char *argv[]) break; } bool ret = ipos->getTargetPositions(tmp); - printf ("%s: (", Vocab::decode(VOCAB_POSITION_MOVES).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_POSITION_MOVES).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (") - ret is [%s]\n", ret? "true":"false"); @@ -413,9 +413,9 @@ int main(int argc, char *argv[]) case VOCAB_POSITION_DIRECT: { - ok = iposDir->getRefPosition(p.get(3).asInt(), tmp); - response.addDouble(tmp[0]); - printf("Ref joint %d is %.2f - [ret val is %s]\n", p.get(3).asInt(), tmp[0], ok?"true":"false"); + ok = iposDir->getRefPosition(p.get(3).asInt32(), tmp); + response.addFloat64(tmp[0]); + printf("Ref joint %d is %.2f - [ret val is %s]\n", p.get(3).asInt32(), tmp[0], ok?"true":"false"); } break; @@ -425,7 +425,7 @@ int main(int argc, char *argv[]) Bottle& b = response.addList(); int i; for (i = 0; i < jnts; i++) - b.addDouble(tmp[i]); + b.addFloat64(tmp[i]); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (" - ret is [%s]\n", ok? "true":"false"); @@ -434,9 +434,9 @@ int main(int argc, char *argv[]) case VOCAB_VELOCITY_MOVE: { - ok = vel->getRefVelocity(p.get(2).asInt(), tmp); - response.addDouble(tmp[0]); - printf("Ref vel joint %d is %.2f - [ret val is %s]\n", p.get(3).asInt(), tmp[0], ok?"true":"false"); + ok = vel->getRefVelocity(p.get(2).asInt32(), tmp); + response.addFloat64(tmp[0]); + printf("Ref vel joint %d is %.2f - [ret val is %s]\n", p.get(3).asInt32(), tmp[0], ok?"true":"false"); } break; @@ -446,7 +446,7 @@ int main(int argc, char *argv[]) Bottle& b = response.addList(); int i; for (i = 0; i < jnts; i++) - b.addDouble(tmp[i]); + b.addFloat64(tmp[i]); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (" - ret is [%s]\n", ok? "true":"false"); @@ -455,18 +455,18 @@ int main(int argc, char *argv[]) case VOCAB_INFO_NAME: { - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); if (iInfo == 0) { printf("unavailable interface\n"); break; } std::string tmp_str; iInfo->getAxisName(j,tmp_str); - printf("%s: %d %s\n", Vocab::decode(VOCAB_INFO_NAME).c_str(), j, tmp_str.c_str()); + printf("%s: %d %s\n", Vocab32::decode(VOCAB_INFO_NAME).c_str(), j, tmp_str.c_str()); } break; case VOCAB_AXES: { int nj = 0; enc->getAxes(&nj); - printf ("%s: %d\n", Vocab::decode(VOCAB_AXES).c_str(), nj); + printf ("%s: %d\n", Vocab32::decode(VOCAB_AXES).c_str(), nj); } break; @@ -474,7 +474,7 @@ int main(int argc, char *argv[]) { if (ipos==0) {yError ("unavailable interface iPos\n"); break;} bool b=false; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); ipos->checkMotionDone(j,&b); if (b==true) printf("1"); else printf ("0"); @@ -503,7 +503,7 @@ int main(int argc, char *argv[]) case VOCAB_ENCODERS: { enc->getEncoders(tmp); - printf ("%s: (", Vocab::decode(VOCAB_ENCODERS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_ENCODERS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -513,7 +513,7 @@ int main(int argc, char *argv[]) case VOCAB_MOTOR_ENCODERS: { if (iMotEnc==0) {printf ("unavailable interface\n"); break;} iMotEnc->getMotorEncoders(tmp); - printf ("%s: (", Vocab::decode(VOCAB_MOTOR_ENCODERS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_MOTOR_ENCODERS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -523,7 +523,7 @@ int main(int argc, char *argv[]) case VOCAB_MOTOR_ENCODER_SPEEDS: { if (iMotEnc==0) {printf ("unavailable interface\n"); break;} iMotEnc->getMotorEncoderSpeeds(tmp); - printf ("%s: (", Vocab::decode(VOCAB_MOTOR_ENCODER_SPEEDS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_MOTOR_ENCODER_SPEEDS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -533,7 +533,7 @@ int main(int argc, char *argv[]) case VOCAB_MOTOR_ENCODER_ACCELERATIONS: { if (iMotEnc==0) {printf ("unavailable interface\n"); break;} iMotEnc->getMotorEncoderAccelerations(tmp); - printf ("%s: (", Vocab::decode(VOCAB_MOTOR_ENCODER_ACCELERATIONS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_MOTOR_ENCODER_ACCELERATIONS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -543,10 +543,10 @@ int main(int argc, char *argv[]) case VOCAB_MOTOR_CPR: { if (iMotEnc==0) {printf ("unavailable interface\n"); break;} - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); double v; iMotEnc->getMotorEncoderCountsPerRevolution(j, &v); - printf("%s: ", Vocab::decode(VOCAB_MOTOR_CPR).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_MOTOR_CPR).c_str()); printf("%.2f ", v); printf("\n"); } @@ -555,10 +555,10 @@ int main(int argc, char *argv[]) case VOCAB_AMP_MAXCURRENT: { if (amp==0) {printf ("unavailable interface\n"); break;} - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); double v; amp->getMaxCurrent(j, &v); - printf("%s: ", Vocab::decode(VOCAB_AMP_MAXCURRENT).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_AMP_MAXCURRENT).c_str()); printf("%.2f ", v); printf("\n"); } @@ -569,7 +569,7 @@ int main(int argc, char *argv[]) if (imot==0) {printf ("unavailable interface\n"); break;} int v; imot->getNumberOfMotors(&v); - printf("%s: ", Vocab::decode(VOCAB_MOTORS_NUMBER).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_MOTORS_NUMBER).c_str()); printf("%d ", v); printf("\n"); } @@ -580,7 +580,7 @@ int main(int argc, char *argv[]) if (iMotEnc==0) {printf ("unavailable interface\n"); break;} int v; iMotEnc->getNumberOfMotorEncoders(&v); - printf("%s: ", Vocab::decode(VOCAB_MOTOR_ENCODER_NUMBER).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_MOTOR_ENCODER_NUMBER).c_str()); printf("%d ", v); printf("\n"); } @@ -588,9 +588,9 @@ int main(int argc, char *argv[]) case VOCAB_PID: { Pid pd; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); pid->getPid(VOCAB_PIDTYPE_POSITION, j, &pd); - printf("%s: ", Vocab::decode(VOCAB_PID).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_PID).c_str()); printf("kp %.2f ", pd.kp); printf("kd %.2f ", pd.kd); printf("ki %.2f ", pd.ki); @@ -610,13 +610,13 @@ int main(int argc, char *argv[]) for (i = 0; i < jnts; i++) { Bottle& c = b.addList(); - c.addDouble(p[i].kp); - c.addDouble(p[i].kd); - c.addDouble(p[i].ki); - c.addDouble(p[i].max_int); - c.addDouble(p[i].max_output); - c.addDouble(p[i].offset); - c.addDouble(p[i].scale); + c.addFloat64(p[i].kp); + c.addFloat64(p[i].kd); + c.addFloat64(p[i].ki); + c.addFloat64(p[i].max_int); + c.addFloat64(p[i].max_output); + c.addFloat64(p[i].offset); + c.addFloat64(p[i].scale); } printf("%s\n", b.toString().c_str()); delete[] p; @@ -625,25 +625,25 @@ int main(int argc, char *argv[]) case VOCAB_LIMITS: { double min, max; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); lim->getLimits(j, &min, &max); - printf("%s: ", Vocab::decode(VOCAB_LIMITS).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_LIMITS).c_str()); printf("limits: (%.2f %.2f)\n", min, max); } break; case VOCAB_VEL_LIMITS: { double min, max; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); lim->getVelLimits(j, &min, &max); - printf("%s: ", Vocab::decode(VOCAB_VEL_LIMITS).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_VEL_LIMITS).c_str()); printf("limits: (%.2f %.2f)\n", min, max); } break; case VOCAB_ERRS: { pid->getPidErrors(VOCAB_PIDTYPE_POSITION, tmp); - printf ("%s: (", Vocab::decode(VOCAB_ERRS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_ERRS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -653,7 +653,7 @@ int main(int argc, char *argv[]) case VOCAB_TEMPERATURES: { if (imot==0) {printf ("unavailable interface\n"); break;} imot->getTemperatures(tmp); - printf ("%s: (", Vocab::decode(VOCAB_TEMPERATURES).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_TEMPERATURES).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -662,10 +662,10 @@ int main(int argc, char *argv[]) case VOCAB_TEMPERATURE: { if (imot==0) {printf ("unavailable interface\n"); break;} - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); double v; imot->getTemperature(j, &v); - printf("%s: ", Vocab::decode(VOCAB_TEMPERATURE).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_TEMPERATURE).c_str()); printf("%.2f ", v); printf("\n"); } @@ -673,10 +673,10 @@ int main(int argc, char *argv[]) case VOCAB_TEMPERATURE_LIMIT: { if (imot==0) {printf ("unavailable interface\n"); break;} - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); double v; imot->getTemperatureLimit(j, &v); - printf("%s: ", Vocab::decode(VOCAB_TEMPERATURE_LIMIT).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_TEMPERATURE_LIMIT).c_str()); printf("%.2f ", v); printf("\n"); } @@ -685,7 +685,7 @@ int main(int argc, char *argv[]) case VOCAB_PWMCONTROL_PWM_OUTPUTS: { if (ipwm==0) {printf ("unavailable interface\n"); break;} ipwm->getDutyCycles(tmp); - printf("%s: (", Vocab::decode(VOCAB_PWMCONTROL_PWM_OUTPUTS).c_str()); + printf("%s: (", Vocab32::decode(VOCAB_PWMCONTROL_PWM_OUTPUTS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -696,10 +696,10 @@ int main(int argc, char *argv[]) //case VOCAB_AMP_PWM: { if (ipwm == 0) { printf("unavailable interface\n"); break; } - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); double v; ipwm->getDutyCycle(j, &v); - printf("%s: ", Vocab::decode(VOCAB_PWMCONTROL_PWM_OUTPUT).c_str()); + printf("%s: ", Vocab32::decode(VOCAB_PWMCONTROL_PWM_OUTPUT).c_str()); printf("%.2f ", v); printf("\n"); } @@ -707,9 +707,9 @@ int main(int argc, char *argv[]) case VOCAB_REFERENCE: { double ref_pos; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); pid->getPidReference(VOCAB_PIDTYPE_POSITION, j,&ref_pos); - printf ("%s: (", Vocab::decode(VOCAB_REFERENCE).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_REFERENCE).c_str()); printf ("%.2f ", ref_pos); printf (")\n"); } @@ -717,7 +717,7 @@ int main(int argc, char *argv[]) case VOCAB_REFERENCES: { pid->getPidReferences(VOCAB_PIDTYPE_POSITION, tmp); - printf ("%s: (", Vocab::decode(VOCAB_REFERENCES).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_REFERENCES).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -726,7 +726,7 @@ int main(int argc, char *argv[]) case VOCAB_REF_SPEEDS: { ipos->getRefSpeeds(tmp); - printf ("%s: (", Vocab::decode(VOCAB_REF_SPEEDS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_REF_SPEEDS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -735,9 +735,9 @@ int main(int argc, char *argv[]) case VOCAB_REF_SPEED: { double ref_speed; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); ipos->getRefSpeed(j,&ref_speed); - printf ("%s: (", Vocab::decode(VOCAB_REF_SPEED).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_REF_SPEED).c_str()); printf ("%.2f ", ref_speed); printf (")\n"); } @@ -745,9 +745,9 @@ int main(int argc, char *argv[]) case VOCAB_REF_ACCELERATION: { double ref_acc; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); ipos->getRefAcceleration(j,&ref_acc); - printf ("%s: (", Vocab::decode(VOCAB_REF_ACCELERATION).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_REF_ACCELERATION).c_str()); printf ("%.2f ", ref_acc); printf (")\n"); } @@ -755,7 +755,7 @@ int main(int argc, char *argv[]) case VOCAB_REF_ACCELERATIONS: { ipos->getRefAccelerations(tmp); - printf ("%s: (", Vocab::decode(VOCAB_REF_ACCELERATIONS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_REF_ACCELERATIONS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -764,7 +764,7 @@ int main(int argc, char *argv[]) case VOCAB_AMP_CURRENTS: { amp->getCurrents(tmp); - printf ("%s: (", Vocab::decode(VOCAB_AMP_CURRENTS).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_AMP_CURRENTS).c_str()); for(i = 0; i < jnts; i++) printf ("%.2f ", tmp[i]); printf (")\n"); @@ -773,36 +773,36 @@ int main(int argc, char *argv[]) case VOCAB_AMP_PWM_LIMIT: { - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); amp->getPWMLimit(j, tmp); - printf ("%s: (", Vocab::decode(VOCAB_AMP_PWM_LIMIT).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_AMP_PWM_LIMIT).c_str()); printf ("%.2f )\n", tmp[0]); } break; case VOCAB_AMP_PEAK_CURRENT: { - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); amp->getPeakCurrent(j, tmp); - printf ("%s: (", Vocab::decode(VOCAB_AMP_PEAK_CURRENT).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_AMP_PEAK_CURRENT).c_str()); printf ("%.2f )\n", tmp[0]); } break; case VOCAB_AMP_NOMINAL_CURRENT: { - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); amp->getNominalCurrent(j, tmp); - printf ("%s: (", Vocab::decode(VOCAB_AMP_NOMINAL_CURRENT).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_AMP_NOMINAL_CURRENT).c_str()); printf ("%.2f )\n", tmp[0]); } break; case VOCAB_AMP_VOLTAGE_SUPPLY: { - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); amp->getPowerSupplyVoltage(j, tmp); - printf ("%s: (", Vocab::decode(VOCAB_AMP_VOLTAGE_SUPPLY).c_str()); + printf ("%s: (", Vocab32::decode(VOCAB_AMP_VOLTAGE_SUPPLY).c_str()); printf ("%.2f )\n", tmp[0]); } break; @@ -810,35 +810,35 @@ int main(int argc, char *argv[]) break; case VOCAB_SET: - switch(p.get(1).asVocab()) { + switch(p.get(1).asVocab32()) { case VOCAB_POSITION_MOVE: { - int j = p.get(2).asInt(); - double ref = p.get(3).asDouble(); - printf("%s: moving %d to %.2f\n", Vocab::decode(VOCAB_POSITION_MOVE).c_str(), j, ref); + int j = p.get(2).asInt32(); + double ref = p.get(3).asFloat64(); + printf("%s: moving %d to %.2f\n", Vocab32::decode(VOCAB_POSITION_MOVE).c_str(), j, ref); ipos->positionMove(j, ref); } break; case VOCAB_VELOCITY_MOVE: { - int j = p.get(2).asInt(); - double ref = p.get(3).asDouble(); - printf("%s: accelerating %d to %.2f\n", Vocab::decode(VOCAB_VELOCITY_MOVE).c_str(), j, ref); + int j = p.get(2).asInt32(); + double ref = p.get(3).asFloat64(); + printf("%s: accelerating %d to %.2f\n", Vocab32::decode(VOCAB_VELOCITY_MOVE).c_str(), j, ref); vel->velocityMove(j, ref); } break; case VOCAB_REF_SPEED: { - int j = p.get(2).asInt(); - double ref = p.get(3).asDouble(); - printf("%s: setting speed for %d to %.2f\n", Vocab::decode(VOCAB_REF_SPEED).c_str(), j, ref); + int j = p.get(2).asInt32(); + double ref = p.get(3).asFloat64(); + printf("%s: setting speed for %d to %.2f\n", Vocab32::decode(VOCAB_REF_SPEED).c_str(), j, ref); ipos->setRefSpeed(j, ref); } break; case VOCAB_REF_ACCELERATION: { - int j = p.get(2).asInt(); - double ref = p.get(3).asDouble(); - printf("%s: setting acceleration for %d to %.2f\n", Vocab::decode(VOCAB_REF_ACCELERATION).c_str(), j, ref); + int j = p.get(2).asInt32(); + double ref = p.get(3).asFloat64(); + printf("%s: setting acceleration for %d to %.2f\n", Vocab32::decode(VOCAB_REF_ACCELERATION).c_str(), j, ref); ipos->setRefAcceleration(j, ref); } break; @@ -848,10 +848,10 @@ int main(int argc, char *argv[]) printf("received %s\n", l->toString().c_str()); for (i = 0; i < jnts; i++) { printf("%d - ", i); fflush(stdout); - tmp[i] = l->get(i).asDouble(); + tmp[i] = l->get(i).asFloat64(); printf("tmp[i] %f\n", tmp[i]); fflush(stdout); } - printf("%s: moving all joints\n", Vocab::decode(VOCAB_POSITION_MOVES).c_str()); + printf("%s: moving all joints\n", Vocab32::decode(VOCAB_POSITION_MOVES).c_str()); ipos->positionMove(tmp); } break; @@ -859,9 +859,9 @@ int main(int argc, char *argv[]) case VOCAB_VELOCITY_MOVES: { Bottle *l = p.get(2).asList(); for (i = 0; i < jnts; i++) { - tmp[i] = l->get(i).asDouble(); + tmp[i] = l->get(i).asFloat64(); } - printf("%s: moving all joints\n", Vocab::decode(VOCAB_VELOCITY_MOVES).c_str()); + printf("%s: moving all joints\n", Vocab32::decode(VOCAB_VELOCITY_MOVES).c_str()); vel->velocityMove(tmp); } break; @@ -869,9 +869,9 @@ int main(int argc, char *argv[]) case VOCAB_REF_SPEEDS: { Bottle *l = p.get(2).asList(); for (i = 0; i < jnts; i++) { - tmp[i] = l->get(i).asDouble(); + tmp[i] = l->get(i).asFloat64(); } - printf("%s: setting speed for all joints\n", Vocab::decode(VOCAB_REF_SPEEDS).c_str()); + printf("%s: setting speed for all joints\n", Vocab32::decode(VOCAB_REF_SPEEDS).c_str()); ipos->setRefSpeeds(tmp); } break; @@ -879,47 +879,47 @@ int main(int argc, char *argv[]) case VOCAB_REF_ACCELERATIONS: { Bottle *l = p.get(2).asList(); for (i = 0; i < jnts; i++) { - tmp[i] = l->get(i).asDouble(); + tmp[i] = l->get(i).asFloat64(); } - printf("%s: setting acceleration for all joints\n", Vocab::decode(VOCAB_REF_ACCELERATIONS).c_str()); + printf("%s: setting acceleration for all joints\n", Vocab32::decode(VOCAB_REF_ACCELERATIONS).c_str()); ipos->setRefAccelerations(tmp); } break; case VOCAB_STOP: { - int j = p.get(2).asInt(); - printf("%s: stopping axis %d\n", Vocab::decode(VOCAB_STOP).c_str(), j); + int j = p.get(2).asInt32(); + printf("%s: stopping axis %d\n", Vocab32::decode(VOCAB_STOP).c_str(), j); ipos->stop(j); } break; case VOCAB_STOPS: { - printf("%s: stopping all axes\n", Vocab::decode(VOCAB_STOPS).c_str()); + printf("%s: stopping all axes\n", Vocab32::decode(VOCAB_STOPS).c_str()); ipos->stop(); } break; case VOCAB_POSITION_DIRECT: { - printf("%s: setting position direct reference\n", Vocab::decode(VOCAB_POSITION_DIRECT).c_str()); - iposDir->setPosition(p.get(2).asInt(), p.get(3).asDouble()); + printf("%s: setting position direct reference\n", Vocab32::decode(VOCAB_POSITION_DIRECT).c_str()); + iposDir->setPosition(p.get(2).asInt32(), p.get(3).asFloat64()); } break; case VOCAB_POSITION_DIRECTS: { - printf("%s: setting position direct references to %s\n", Vocab::decode(VOCAB_POSITION_DIRECTS).c_str(), p.toString().c_str() ); + printf("%s: setting position direct references to %s\n", Vocab32::decode(VOCAB_POSITION_DIRECTS).c_str(), p.toString().c_str() ); Bottle *l = p.get(2).asList(); for (i = 0; i < jnts; i++) { - tmp[i] = l->get(i).asDouble(); + tmp[i] = l->get(i).asFloat64(); } iposDir->setPositions(tmp); } break; case VOCAB_ENCODER: { - int j = p.get(2).asInt(); - double ref = p.get(3).asDouble(); - printf("%s: setting the encoder value for %d to %.2f\n", Vocab::decode(VOCAB_ENCODER).c_str(), j, ref); + int j = p.get(2).asInt32(); + double ref = p.get(3).asFloat64(); + printf("%s: setting the encoder value for %d to %.2f\n", Vocab32::decode(VOCAB_ENCODER).c_str(), j, ref); enc->setEncoder(j, ref); } break; @@ -927,16 +927,16 @@ int main(int argc, char *argv[]) case VOCAB_ENCODERS: { Bottle *l = p.get(2).asList(); for (i = 0; i < jnts; i++) { - tmp[i] = l->get(i).asDouble(); + tmp[i] = l->get(i).asFloat64(); } - printf("%s: setting the encoder value for all joints\n", Vocab::decode(VOCAB_ENCODERS).c_str()); + printf("%s: setting the encoder value for all joints\n", Vocab32::decode(VOCAB_ENCODERS).c_str()); enc->setEncoders(tmp); } break; case VOCAB_PID: { Pid pd; - int j = p.get(2).asInt(); + int j = p.get(2).asInt32(); Bottle *l = p.get(3).asList(); if (l==0) { @@ -947,17 +947,17 @@ int main(int argc, char *argv[]) int elems=l->size(); if (elems>=3) { - pd.kp = l->get(0).asDouble(); - pd.kd = l->get(1).asDouble(); - pd.ki = l->get(2).asDouble(); + pd.kp = l->get(0).asFloat64(); + pd.kd = l->get(1).asFloat64(); + pd.ki = l->get(2).asFloat64(); if (elems>=7) { - pd.max_int = l->get(3).asDouble(); - pd.max_output = l->get(4).asDouble(); - pd.offset = l->get(5).asDouble(); - pd.scale = l->get(6).asDouble(); + pd.max_int = l->get(3).asFloat64(); + pd.max_output = l->get(4).asFloat64(); + pd.offset = l->get(5).asFloat64(); + pd.scale = l->get(6).asFloat64(); } - printf("%s: setting PID values for axis %d\n", Vocab::decode(VOCAB_PID).c_str(), j); + printf("%s: setting PID values for axis %d\n", Vocab32::decode(VOCAB_PID).c_str(), j); pid->setPid(VOCAB_PIDTYPE_POSITION, j, pd); } else @@ -970,68 +970,68 @@ int main(int argc, char *argv[]) case VOCAB_TEMPERATURE_LIMIT: { if (imot==0) {printf ("unavailable interface\n"); break;} - int j=p.get(2).asInt(); - double v=p.get(3).asDouble(); + int j=p.get(2).asInt32(); + double v=p.get(3).asFloat64(); imot->setTemperatureLimit(j,v); - printf("%s: setting temperature limit for axis %d to %f\n", Vocab::decode(VOCAB_TEMPERATURE_LIMIT).c_str(), j, v); + printf("%s: setting temperature limit for axis %d to %f\n", Vocab32::decode(VOCAB_TEMPERATURE_LIMIT).c_str(), j, v); } break; case VOCAB_AMP_MAXCURRENT: { - int j=p.get(2).asInt(); - double v=p.get(3).asDouble(); + int j=p.get(2).asInt32(); + double v=p.get(3).asFloat64(); amp->setMaxCurrent(j,v); - printf("%s: setting max current for motor %d to %f\n", Vocab::decode(VOCAB_AMP_MAXCURRENT).c_str(), j, v); + printf("%s: setting max current for motor %d to %f\n", Vocab32::decode(VOCAB_AMP_MAXCURRENT).c_str(), j, v); } break; case VOCAB_DISABLE: { - int j = p.get(2).asInt(); - printf("%s: disabling control for axis %d\n", Vocab::decode(VOCAB_DISABLE).c_str(), j); + int j = p.get(2).asInt32(); + printf("%s: disabling control for axis %d\n", Vocab32::decode(VOCAB_DISABLE).c_str(), j); pid->disablePid(VOCAB_PIDTYPE_POSITION,j); amp->disableAmp(j); } break; case VOCAB_ENABLE: { - int j = p.get(2).asInt(); - printf("%s: enabling control for axis %d\n", Vocab::decode(VOCAB_ENABLE).c_str(), j); + int j = p.get(2).asInt32(); + printf("%s: enabling control for axis %d\n", Vocab32::decode(VOCAB_ENABLE).c_str(), j); amp->enableAmp(j); pid->enablePid(VOCAB_PIDTYPE_POSITION,j); } break; case VOCAB_LIMITS: { - int j = p.get(2).asInt(); - printf("%s: setting limits for axis %d\n", Vocab::decode(VOCAB_LIMITS).c_str(), j); + int j = p.get(2).asInt32(); + printf("%s: setting limits for axis %d\n", Vocab32::decode(VOCAB_LIMITS).c_str(), j); Bottle *l = p.get(3).asList(); - lim->setLimits(j, l->get(0).asDouble(), l->get(1).asDouble()); + lim->setLimits(j, l->get(0).asFloat64(), l->get(1).asFloat64()); } break; case VOCAB_AMP_PWM_LIMIT: { - int j = p.get(2).asInt(); - double lim = p.get(3).asDouble(); + int j = p.get(2).asInt32(); + double lim = p.get(3).asFloat64(); bool ret = amp->setPWMLimit(j, lim); - printf("%s: setting PWM limits for axis %d to %0.2f - ret: %d\n", Vocab::decode(VOCAB_AMP_PWM_LIMIT).c_str(), j, lim, ret); + printf("%s: setting PWM limits for axis %d to %0.2f - ret: %d\n", Vocab32::decode(VOCAB_AMP_PWM_LIMIT).c_str(), j, lim, ret); } break; case VOCAB_AMP_PEAK_CURRENT: { - int j = p.get(2).asInt(); - double lim = p.get(3).asDouble(); + int j = p.get(2).asInt32(); + double lim = p.get(3).asFloat64(); bool ret = amp->setPeakCurrent(j, lim); - printf("%s: setting peak current for axis %d to %0.2f - ret: %d\n", Vocab::decode(VOCAB_AMP_PEAK_CURRENT).c_str(), j, lim, ret); + printf("%s: setting peak current for axis %d to %0.2f - ret: %d\n", Vocab32::decode(VOCAB_AMP_PEAK_CURRENT).c_str(), j, lim, ret); } break; case VOCAB_PWMCONTROL_REF_PWM: { - int j=p.get(2).asInt(); - double v=p.get(3).asDouble(); + int j=p.get(2).asInt32(); + double v=p.get(3).asFloat64(); ipwm->setRefDutyCycle(j,v); - printf("%s: setting pwm for axis %d to %f\n", Vocab::decode(VOCAB_PWMCONTROL_REF_PWM).c_str(), j, v); + printf("%s: setting pwm for axis %d to %f\n", Vocab32::decode(VOCAB_PWMCONTROL_REF_PWM).c_str(), j, v); } break; } @@ -1065,18 +1065,18 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: int controlledJoints; torque->getAxes(&controlledJoints); - int code = cmd.get(1).asVocab(); + int code = cmd.get(1).asVocab32(); switch (code) { case VOCAB_SET: { *rec = true; - switch(cmd.get(2).asVocab()) + switch(cmd.get(2).asVocab32()) { case VOCAB_REF: { - *ok = torque->setRefTorque(cmd.get(3).asInt(), cmd.get(4).asDouble()); + *ok = torque->setRefTorque(cmd.get(3).asInt32(), cmd.get(4).asFloat64()); } break; @@ -1089,7 +1089,7 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: { double *p = new double[njs]; // LATER: optimize to avoid allocation. for (i = 0; i < njs; i++) - p[i] = b.get(i).asDouble(); + p[i] = b.get(i).asFloat64(); *ok = torque->setRefTorques (p); delete[] p; } @@ -1099,7 +1099,7 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: case VOCAB_REFG: { - int n_joint = cmd.get(3).asInt(); + int n_joint = cmd.get(3).asInt32(); Bottle& jointList = *(cmd.get(4).asList()); Bottle& refList = *(cmd.get(5).asList()); @@ -1126,8 +1126,8 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: for (i = 0; i < n_joint; i++) { - joints[i] = jointList.get(i).asInt(); - refs[i] = refList.get(i).asDouble(); + joints[i] = jointList.get(i).asInt32(); + refs[i] = refList.get(i).asFloat64(); } *ok = torque->setRefTorques(n_joint, joints, refs); delete[] joints; @@ -1137,7 +1137,7 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: case VOCAB_LIM: { - *ok = ipid->setPidErrorLimit (VOCAB_PIDTYPE_POSITION, cmd.get(3).asInt(), cmd.get(4).asDouble()); + *ok = ipid->setPidErrorLimit (VOCAB_PIDTYPE_POSITION, cmd.get(3).asInt32(), cmd.get(4).asFloat64()); } break; @@ -1150,7 +1150,7 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: { double *p = new double[njs]; // LATER: optimize to avoid allocation. for (i = 0; i < njs; i++) - p[i] = b.get(i).asDouble(); + p[i] = b.get(i).asFloat64(); *ok = ipid->setPidErrorLimits (VOCAB_PIDTYPE_POSITION, p); delete[] p; } @@ -1160,15 +1160,15 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: case VOCAB_PID: { Pid p; - int j = cmd.get(3).asInt(); + int j = cmd.get(3).asInt32(); Bottle& b = *(cmd.get(4).asList()); - p.kp = b.get(0).asDouble(); - p.kd = b.get(1).asDouble(); - p.ki = b.get(2).asDouble(); - p.max_int = b.get(3).asDouble(); - p.max_output = b.get(4).asDouble(); - p.offset = b.get(5).asDouble(); - p.scale = b.get(6).asDouble(); + p.kp = b.get(0).asFloat64(); + p.kd = b.get(1).asFloat64(); + p.ki = b.get(2).asFloat64(); + p.max_int = b.get(3).asFloat64(); + p.max_output = b.get(4).asFloat64(); + p.offset = b.get(5).asFloat64(); + p.scale = b.get(6).asFloat64(); *ok = ipid->setPid(VOCAB_PIDTYPE_TORQUE,j, p); } break; @@ -1184,13 +1184,13 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: for (i = 0; i < njs; i++) { Bottle& c = *(b.get(i).asList()); - p[i].kp = c.get(0).asDouble(); - p[i].kd = c.get(1).asDouble(); - p[i].ki = c.get(2).asDouble(); - p[i].max_int = c.get(3).asDouble(); - p[i].max_output = c.get(4).asDouble(); - p[i].offset = c.get(5).asDouble(); - p[i].scale = c.get(6).asDouble(); + p[i].kp = c.get(0).asFloat64(); + p[i].kd = c.get(1).asFloat64(); + p[i].ki = c.get(2).asFloat64(); + p[i].max_int = c.get(3).asFloat64(); + p[i].max_output = c.get(4).asFloat64(); + p[i].offset = c.get(5).asFloat64(); + p[i].scale = c.get(6).asFloat64(); } *ok = ipid->setPids(VOCAB_PIDTYPE_TORQUE,p); delete[] p; @@ -1200,19 +1200,19 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: case VOCAB_RESET: { - *ok = ipid->resetPid (VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt()); + *ok = ipid->resetPid (VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32()); } break; case VOCAB_DISABLE: { - *ok = ipid->disablePid (VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt()); + *ok = ipid->disablePid (VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32()); } break; case VOCAB_ENABLE: { - *ok = ipid->enablePid (VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt()); + *ok = ipid->enablePid (VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32()); } break; @@ -1226,23 +1226,23 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: int tmp = 0; double dtmp = 0.0; - response.addVocab(VOCAB_IS); + response.addVocab32(VOCAB_IS); response.add(cmd.get(1)); - switch(cmd.get(2).asVocab()) + switch(cmd.get(2).asVocab32()) { case VOCAB_AXES: { int tmp; *ok = torque->getAxes(&tmp); - response.addInt(tmp); + response.addInt32(tmp); } break; case VOCAB_TRQ: { - *ok = torque->getTorque(cmd.get(3).asInt(), &dtmp); - response.addDouble(dtmp); + *ok = torque->getTorque(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); } break; @@ -1253,15 +1253,15 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: Bottle& b = response.addList(); int i; for (i = 0; i < controlledJoints; i++) - b.addDouble(p[i]); + b.addFloat64(p[i]); delete[] p; } break; case VOCAB_ERR: { - *ok = ipid->getPidError(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt(), &dtmp); - response.addDouble(dtmp); + *ok = ipid->getPidError(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); } break; @@ -1272,15 +1272,15 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: Bottle& b = response.addList(); int i; for (i = 0; i < controlledJoints; i++) - b.addDouble(p[i]); + b.addFloat64(p[i]); delete[] p; } break; case VOCAB_OUTPUT: { - *ok = ipid->getPidOutput(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt(), &dtmp); - response.addDouble(dtmp); + *ok = ipid->getPidOutput(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); } break; @@ -1291,7 +1291,7 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: Bottle& b = response.addList(); int i; for (i = 0; i < controlledJoints; i++) - b.addDouble(p[i]); + b.addFloat64(p[i]); delete[] p; } break; @@ -1299,15 +1299,15 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: case VOCAB_PID: { Pid p; - *ok = ipid->getPid(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt(), &p); + *ok = ipid->getPid(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32(), &p); Bottle& b = response.addList(); - b.addDouble(p.kp); - b.addDouble(p.kd); - b.addDouble(p.ki); - b.addDouble(p.max_int); - b.addDouble(p.max_output); - b.addDouble(p.offset); - b.addDouble(p.scale); + b.addFloat64(p.kp); + b.addFloat64(p.kd); + b.addFloat64(p.ki); + b.addFloat64(p.max_int); + b.addFloat64(p.max_output); + b.addFloat64(p.offset); + b.addFloat64(p.scale); } break; @@ -1320,13 +1320,13 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: for (i = 0; i < controlledJoints; i++) { Bottle& c = b.addList(); - c.addDouble(p[i].kp); - c.addDouble(p[i].kd); - c.addDouble(p[i].ki); - c.addDouble(p[i].max_int); - c.addDouble(p[i].max_output); - c.addDouble(p[i].offset); - c.addDouble(p[i].scale); + c.addFloat64(p[i].kp); + c.addFloat64(p[i].kd); + c.addFloat64(p[i].ki); + c.addFloat64(p[i].max_int); + c.addFloat64(p[i].max_output); + c.addFloat64(p[i].offset); + c.addFloat64(p[i].scale); } delete[] p; } @@ -1334,8 +1334,8 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: case VOCAB_REFERENCE: { - *ok = torque->getRefTorque(cmd.get(3).asInt(), &dtmp); - response.addDouble(dtmp); + *ok = torque->getRefTorque(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); } break; @@ -1346,15 +1346,15 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: Bottle& b = response.addList(); int i; for (i = 0; i < controlledJoints; i++) - b.addDouble(p[i]); + b.addFloat64(p[i]); delete[] p; } break; case VOCAB_LIM: { - *ok = ipid->getPidErrorLimit(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt(), &dtmp); - response.addDouble(dtmp); + *ok = ipid->getPidErrorLimit(VOCAB_PIDTYPE_TORQUE,cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); } break; @@ -1365,7 +1365,7 @@ void handleTorqueMsg(ITorqueControl *torque, IPidControl *ipid, const yarp::os:: Bottle& b = response.addList(); int i; for (i = 0; i < controlledJoints; i++) - b.addDouble(p[i]); + b.addFloat64(p[i]); delete[] p; } break; @@ -1395,23 +1395,23 @@ void handleImpedanceMsg(IImpedanceControl *iimp, const yarp::os::Bottle& cmd, int controlledJoints; iimp->getAxes(&controlledJoints); - int code = cmd.get(1).asVocab(); + int code = cmd.get(1).asVocab32(); switch (code) { case VOCAB_SET: { *rec = true; - switch(cmd.get(2).asVocab()) + switch(cmd.get(2).asVocab32()) { case VOCAB_IMP_PARAM: { - *ok = iimp->setImpedance(cmd.get(3).asInt(), cmd.get(4).asDouble(),cmd.get(5).asDouble()); + *ok = iimp->setImpedance(cmd.get(3).asInt32(), cmd.get(4).asFloat64(),cmd.get(5).asFloat64()); } break; case VOCAB_IMP_OFFSET: { - *ok = iimp->setImpedanceOffset (cmd.get(3).asInt(), cmd.get(4).asDouble()); + *ok = iimp->setImpedanceOffset (cmd.get(3).asInt32(), cmd.get(4).asFloat64()); } break; } @@ -1426,24 +1426,24 @@ void handleImpedanceMsg(IImpedanceControl *iimp, const yarp::os::Bottle& cmd, double dtmp0 = 0.0; double dtmp1 = 0.0; double dtmp2 = 0.0; - response.addVocab(VOCAB_IS); + response.addVocab32(VOCAB_IS); response.add(cmd.get(1)); - switch(cmd.get(2).asVocab()) + switch(cmd.get(2).asVocab32()) { case VOCAB_IMP_PARAM: { - *ok = iimp->getImpedance(cmd.get(3).asInt(), &dtmp0, &dtmp1); - response.addDouble(dtmp0); - response.addDouble(dtmp1); + *ok = iimp->getImpedance(cmd.get(3).asInt32(), &dtmp0, &dtmp1); + response.addFloat64(dtmp0); + response.addFloat64(dtmp1); } break; case VOCAB_IMP_OFFSET: { - *ok = iimp->getImpedanceOffset(cmd.get(3).asInt(), &dtmp0); - response.addDouble(dtmp0); + *ok = iimp->getImpedanceOffset(cmd.get(3).asInt32(), &dtmp0); + response.addFloat64(dtmp0); } break; } @@ -1469,32 +1469,32 @@ void handleControlModeMsg_DEBUG(IControlMode *iMode, const yarp::os::Bottle& cmd return; } - int code = cmd.get(1).asVocab(); + int code = cmd.get(1).asVocab32(); *ok=true; switch(code) { case VOCAB_SET: { - int axis = cmd.get(3).asInt(); + int axis = cmd.get(3).asInt32(); yarp::os::Value mode_vocab=cmd.get(2); - int mode = mode_vocab.asInt(); + int mode = mode_vocab.asInt32(); printf ("setting mode: %s (%d)",mode_vocab.toString().c_str(), mode); *ok = iMode->setControlMode(axis, mode); } case VOCAB_GET: { - if (cmd.get(2).asVocab()==VOCAB_CM_CONTROL_MODE) + if (cmd.get(2).asVocab32()==VOCAB_CM_CONTROL_MODE) { int p=-1; - int axis = cmd.get(3).asInt(); + int axis = cmd.get(3).asInt32(); fprintf(stderr, "Calling getControlMode\n"); *ok = iMode->getControlMode(axis, &p); - response.addVocab(VOCAB_IS); - response.addInt(axis); - response.addVocab(VOCAB_CM_CONTROL_MODE); - response.addVocab(p); + response.addVocab32(VOCAB_IS); + response.addInt32(axis); + response.addVocab32(VOCAB_CM_CONTROL_MODE); + response.addVocab32(p); //fprintf(stderr, "Returning %d\n", p); *rec=true; @@ -1520,15 +1520,15 @@ void handleControlModeMsg(IControlMode *iMode, const yarp::os::Bottle& cmd, return; } - int code = cmd.get(1).asVocab(); + int code = cmd.get(1).asVocab32(); *ok=true; switch(code) { case VOCAB_SET: { - int axis = cmd.get(3).asInt(); - int mode=cmd.get(2).asVocab(); + int axis = cmd.get(3).asInt32(); + int mode=cmd.get(2).asVocab32(); switch (mode) { case VOCAB_CM_POSITION: @@ -1573,17 +1573,17 @@ void handleControlModeMsg(IControlMode *iMode, const yarp::os::Bottle& cmd, break; case VOCAB_GET: { - if (cmd.get(2).asVocab()==VOCAB_CM_CONTROL_MODE) + if (cmd.get(2).asVocab32()==VOCAB_CM_CONTROL_MODE) { int p=-1; - int axis = cmd.get(3).asInt(); + int axis = cmd.get(3).asInt32(); fprintf(stderr, "Calling getControlMode\n"); *ok = iMode->getControlMode(axis, &p); - response.addVocab(VOCAB_IS); - response.addInt(axis); - response.addVocab(VOCAB_CM_CONTROL_MODE); - response.addVocab(p); + response.addVocab32(VOCAB_IS); + response.addInt32(axis); + response.addVocab32(VOCAB_CM_CONTROL_MODE); + response.addVocab32(p); //fprintf(stderr, "Returning %d\n", p); *rec=true; @@ -1611,15 +1611,15 @@ void handleInteractionModeMsg(IInteractionMode *iInteract, const yarp::os::Bottl return; } - int code = cmd.get(1).asVocab(); + int code = cmd.get(1).asVocab32(); *ok=true; switch(code) { case VOCAB_SET: { - int axis = cmd.get(3).asInt(); - yarp::dev::InteractionModeEnum mode = (yarp::dev::InteractionModeEnum) cmd.get(2).asVocab(); + int axis = cmd.get(3).asInt32(); + yarp::dev::InteractionModeEnum mode = (yarp::dev::InteractionModeEnum) cmd.get(2).asVocab32(); *ok = iInteract->setInteractionMode(axis, mode); *rec=true; //or false } @@ -1627,26 +1627,26 @@ void handleInteractionModeMsg(IInteractionMode *iInteract, const yarp::os::Bottl case VOCAB_GET: { - int which = cmd.get(2).asVocab(); + int which = cmd.get(2).asVocab32(); switch(which) { case VOCAB_INTERACTION_MODE: { - int axis = cmd.get(3).asInt(); + int axis = cmd.get(3).asInt32(); yarp::dev::InteractionModeEnum mode; *ok = iInteract->getInteractionMode(axis, &mode); // create response if(*ok) { - response.addVocab(VOCAB_IS); - response.addInt(axis); - response.addVocab(VOCAB_INTERACTION_MODE); - response.addVocab(mode); + response.addVocab32(VOCAB_IS); + response.addInt32(axis); + response.addVocab32(VOCAB_INTERACTION_MODE); + response.addVocab32(mode); *rec=true; } else { - response.addVocab(VOCAB_FAILED); + response.addVocab32(VOCAB_FAILED); *rec = false; } } @@ -1654,7 +1654,7 @@ void handleInteractionModeMsg(IInteractionMode *iInteract, const yarp::os::Bottl case VOCAB_INTERACTION_MODES: { - int axis = cmd.get(3).asInt(); + int axis = cmd.get(3).asInt32(); yarp::dev::InteractionModeEnum *modes; modes = new yarp::dev::InteractionModeEnum[jnts]; @@ -1662,15 +1662,15 @@ void handleInteractionModeMsg(IInteractionMode *iInteract, const yarp::os::Bottl // create response if(*ok) { - response.addVocab(VOCAB_IS); - response.addVocab(VOCAB_INTERACTION_MODES); + response.addVocab32(VOCAB_IS); + response.addVocab32(VOCAB_INTERACTION_MODES); for(int i=0; isliderScaleSmooth->setValue(currentSmoothFactor * 10); onSmoothValueChanged(currentSmoothFactor * 10); reply = portThread.sendRpcCommand(true, get_threshold); - if(reply.isNull() || reply.size()==0 || !reply.get(0).isInt()){ + if(reply.isNull() || reply.size()==0 || !reply.get(0).isInt32()){ printLog("Error while getting the safety threshold"); return false; }else{ - currentThreshold = reply.get(0).asInt(); + currentThreshold = reply.get(0).asInt32(); ui->spinThreashold->setValue(currentThreshold); } reply = portThread.sendRpcCommand(true, get_gain); - if(reply.isNull() || reply.size()==0 || (!reply.get(0).isDouble() && !reply.get(0).isInt())){ + if(reply.isNull() || reply.size()==0 || (!reply.get(0).isFloat64() && !reply.get(0).isInt32())){ printLog("Error while getting the compensation gain"); return false; }else{ - currentCompGain = reply.get(0).asDouble(); + currentCompGain = reply.get(0).asFloat64(); ui->spinCompGain->setValue(currentCompGain); } reply = portThread.sendRpcCommand(true,get_cont_gain); - if(reply.isNull() || reply.size()==0 || (!reply.get(0).isDouble() && !reply.get(0).isInt())){ + if(reply.isNull() || reply.size()==0 || (!reply.get(0).isFloat64() && !reply.get(0).isInt32())){ printLog("Error while getting the contact compensation gain"); return false; }else{ - currentContCompGain = reply.get(0).asDouble(); + currentContCompGain = reply.get(0).asFloat64(); ui->spinCompContactGain->setValue(currentContCompGain); } reply = portThread.sendRpcCommand(true,get_max_neigh_dist); - if(reply.isNull() || reply.size()==0 || (!reply.get(0).isDouble() && !reply.get(0).isInt())){ + if(reply.isNull() || reply.size()==0 || (!reply.get(0).isFloat64() && !reply.get(0).isInt32())){ printLog("Error while getting the max neighbor distance"); return false; }else{ - currentMaxNeighDist = reply.get(0).asDouble(); + currentMaxNeighDist = reply.get(0).asFloat64(); ui->spinNeighbor->setValue(currentMaxNeighDist * 100); } @@ -195,7 +195,7 @@ bool MainWindow::initGuiStatus(){ //int numTaxels = 0; for(unsigned int i=0;iget(i*2).toString().c_str(); - portDim[i] = portList->get(i*2+1).asInt(); + portDim[i] = portList->get(i*2+1).asInt32(); //numTaxels += portDim[i]; ss<< "\n - "<< portNames[i]<< " ("<< portDim[i]<< " taxels)"; } @@ -249,13 +249,13 @@ void MainWindow::onSpinThresholdChanged(int value) // set the threshold Bottle b, setReply; - b.addInt(set_threshold); - b.addInt(safetyThr); + b.addInt32(set_threshold); + b.addInt32(safetyThr); portThread.guiRpcPort->write(b, setReply); // read the threshold Bottle getReply = portThread.sendRpcCommand(true, get_threshold); - currentThreshold = getReply.get(0).asInt(); + currentThreshold = getReply.get(0).asInt32(); if(safetyThr==currentThreshold){ QString msg = QString("Safety threshold changed: %1").arg(safetyThr); @@ -279,13 +279,13 @@ void MainWindow::onSpinCompGainChanged(double value) // set the gain Bottle b, setReply; - b.addInt(set_gain); - b.addDouble(compGain); + b.addInt32(set_gain); + b.addFloat64(compGain); portThread.guiRpcPort->write(b, setReply); // read the gain Bottle getReply = portThread.sendRpcCommand(true, get_gain); - currentCompGain = getReply.get(0).asDouble(); + currentCompGain = getReply.get(0).asFloat64(); if(compGain==currentCompGain){ QString msg = QString("Compensation gain changed: %1").arg(compGain); @@ -309,13 +309,13 @@ void MainWindow::onSpinCompContactGainChanged(double value) // set the gain Bottle b, setReply; - b.addInt(set_cont_gain); - b.addDouble(contCompGain); + b.addInt32(set_cont_gain); + b.addFloat64(contCompGain); portThread.guiRpcPort->write(b, setReply); // read the gain Bottle getReply = portThread.sendRpcCommand(true, get_cont_gain); - currentContCompGain = getReply.get(0).asDouble(); + currentContCompGain = getReply.get(0).asFloat64(); if(contCompGain==currentContCompGain){ QString msg = QString("Contact compensation gain changed: %1").arg(contCompGain); @@ -341,13 +341,13 @@ void MainWindow::onSpinNeighborChanged(double value) // set the value Bottle b, setReply; - b.addInt(set_max_neigh_dist); - b.addDouble(maxNeighDist); + b.addInt32(set_max_neigh_dist); + b.addFloat64(maxNeighDist); portThread.guiRpcPort->write(b, setReply); // read the value Bottle getReply = portThread.sendRpcCommand(true, get_max_neigh_dist); - currentMaxNeighDist = getReply.get(0).asDouble(); + currentMaxNeighDist = getReply.get(0).asFloat64(); if(maxNeighDist==currentMaxNeighDist){ QString msg = QString("Max neighbor distance changed: %1 m").arg(maxNeighDist); @@ -393,13 +393,13 @@ void MainWindow::changeSmooth(int val) // set the smooth factor Bottle b, setReply; - b.addInt(set_smooth_factor); - b.addDouble(smoothFactor); + b.addInt32(set_smooth_factor); + b.addFloat64(smoothFactor); portThread.guiRpcPort->write(b, setReply); // read the smooth factor Bottle getReply = portThread.sendRpcCommand(true, get_smooth_factor); - currentSmoothFactor = getReply.get(0).asDouble(); + currentSmoothFactor = getReply.get(0).asFloat64(); currentSmoothFactor = round(currentSmoothFactor, 1); //double(int((currentSmoothFactor*10)+0.5))/10.0; if(smoothFactor==currentSmoothFactor){ @@ -429,7 +429,7 @@ void MainWindow::onThreashold() } msg<< "TR"<< i/12<< ":\t"; } - msg << int(touchThr.get(index).asDouble())<< ";\t"; + msg << int(touchThr.get(index).asFloat64())<< ";\t"; index++; } QMessageBox::information(this,"Information",QString("%1").arg(msg.str().c_str())); @@ -451,7 +451,7 @@ void MainWindow::onSmooth(bool btnState) // if the button is off it means it is going to be turned on if (btnState){ Bottle b, setReply; - b.addInt(set_smooth_filter); + b.addInt32(set_smooth_filter); b.addString("on"); portThread.guiRpcPort->write(b, setReply); Bottle reply = portThread.sendRpcCommand(true, get_smooth_filter); @@ -468,7 +468,7 @@ void MainWindow::onSmooth(bool btnState) } } else { Bottle b, setReply; - b.addInt(set_smooth_filter); b.addString("off"); + b.addInt32(set_smooth_filter); b.addString("off"); portThread.guiRpcPort->write(b, setReply); Bottle reply = portThread.sendRpcCommand(true, get_smooth_filter); if(string(reply.toString().c_str()).compare("off") == 0){ @@ -489,7 +489,7 @@ void MainWindow::onBinarization(bool btnState) { if (btnState){ Bottle b, setReply; - b.addInt(set_binarization); + b.addInt32(set_binarization); b.addString("on"); portThread.guiRpcPort->write(b, setReply); Bottle reply = portThread.sendRpcCommand(true, get_binarization); @@ -505,7 +505,7 @@ void MainWindow::onBinarization(bool btnState) } } else { Bottle b, setReply; - b.addInt(set_binarization); + b.addInt32(set_binarization); b.addString("off"); portThread.guiRpcPort->write(b, setReply); Bottle reply = portThread.sendRpcCommand(true, get_binarization); diff --git a/src/tools/skinManagerGui/portthread.cpp b/src/tools/skinManagerGui/portthread.cpp index 722beb3035..40cbb8b1f6 100644 --- a/src/tools/skinManagerGui/portthread.cpp +++ b/src/tools/skinManagerGui/portthread.cpp @@ -59,7 +59,7 @@ Bottle PortThread::sendRpcCommand(bool responseExpected, SkinManagerCommand cmd) // create the bottle Bottle b; - b.addInt(cmd); + b.addInt32(cmd); //g_print("Going to send rpc msg: %s\n", b.toString().c_str()); if(responseExpected){ guiRpcPort->write(b, resp); diff --git a/src/tools/stereoCalib/src/stereoCalibThread.cpp b/src/tools/stereoCalib/src/stereoCalibThread.cpp index 468a505f5c..6ad37cdab5 100644 --- a/src/tools/stereoCalib/src/stereoCalibThread.cpp +++ b/src/tools/stereoCalib/src/stereoCalibThread.cpp @@ -21,16 +21,16 @@ stereoCalibThread::stereoCalibThread(ResourceFinder &rf, Port* commPort, const c this->outNameLeft +=rf.check("outLeft",Value("/cam/left:o"),"Output image port (string)").asString().c_str(); Bottle stereoCalibOpts=rf.findGroup("STEREO_CALIBRATION_CONFIGURATION"); - this->boardWidth= stereoCalibOpts.check("boardWidth", Value(8)).asInt(); - this->boardHeight= stereoCalibOpts.check("boardHeight", Value(6)).asInt(); - this->numOfPairs= stereoCalibOpts.check("numberOfPairs", Value(30)).asInt(); - this->squareSize= (float)stereoCalibOpts.check("boardSize", Value(0.09241)).asDouble(); + this->boardWidth= stereoCalibOpts.check("boardWidth", Value(8)).asInt32(); + this->boardHeight= stereoCalibOpts.check("boardHeight", Value(6)).asInt32(); + this->numOfPairs= stereoCalibOpts.check("numberOfPairs", Value(30)).asInt32(); + this->squareSize= (float)stereoCalibOpts.check("boardSize", Value(0.09241)).asFloat64(); this->boardType= stereoCalibOpts.check("boardType", Value("CHESSBOARD")).asString(); this->commandPort=commPort; this->imageDir=imageDir; this->startCalibration=0; this->currentPathDir=rf.getHomeContextPath().c_str(); - int tmp=stereoCalibOpts.check("MonoCalib", Value(0)).asInt(); + int tmp=stereoCalibOpts.check("MonoCalib", Value(0)).asInt32(); this->stereo= tmp?false:true; this->camCalibFile=rf.getHomeContextPath().c_str(); this->standalone = rf.check("standalone"); diff --git a/src/tools/trajectoryPlayer/main.cpp b/src/tools/trajectoryPlayer/main.cpp index 0e8234eda1..23cebead46 100644 --- a/src/tools/trajectoryPlayer/main.cpp +++ b/src/tools/trajectoryPlayer/main.cpp @@ -123,8 +123,8 @@ class BroadcastingThread: public PeriodicThread Bottle& bot2 = this->port_data_out.prepare(); bot2.clear(); - bot2.addInt(actions->action_vector[j].counter); - bot2.addDouble(actions->action_vector[j].time); + bot2.addInt32(actions->action_vector[j].counter); + bot2.addFloat64(actions->action_vector[j].time); int size = this->actions->action_vector[j].get_n_joints(); double *ll = actions->action_vector[j].q_joints; @@ -132,30 +132,30 @@ class BroadcastingThread: public PeriodicThread bot2.addString("commands:"); for (int ix=0;ixport_data_out.write(); } }; @@ -221,8 +221,8 @@ class WorkingThread: public PeriodicThread //prepare the output command Bottle& bot = port_command_out.prepare(); bot.clear(); - bot.addInt(actions.action_vector[action_id].counter); - bot.addDouble(actions.action_vector[action_id].time); + bot.addInt32(actions.action_vector[action_id].counter); + bot.addFloat64(actions.action_vector[action_id].time); bot.addString(actions.action_vector[action_id].tag.c_str()); //@@@ you can add stuff here... @@ -253,18 +253,18 @@ class WorkingThread: public PeriodicThread double *ll = actions.action_vector[action_id].q_joints; Bottle& bot2 = this->port_command_joints.prepare(); bot2.clear(); - bot2.addInt(actions.action_vector[action_id].counter); - bot2.addDouble(actions.action_vector[action_id].time); + bot2.addInt32(actions.action_vector[action_id].counter); + bot2.addFloat64(actions.action_vector[action_id].time); int size = this->actions.action_vector[action_id].get_n_joints(); bot2.addString("commands:"); for (int ix=0;ixport_command_joints.write(); } @@ -488,7 +488,7 @@ class scriptModule: public RFModule if (rf.check("period")==true) { - int period = rf.find("period").asInt(); + int period = rf.find("period").asInt32(); yInfo() << "Thread period set to " << period << "ms"; w_thread.setPeriod((double)period/1000.0); } @@ -502,7 +502,7 @@ class scriptModule: public RFModule int req_joints = 0; //default value if (rf.check("joints")) { - req_joints = rf.find("joints").asInt();} + req_joints = rf.find("joints").asInt32();} else { yError() << "Missing parameter 'joints' (number of joints to control)"; @@ -528,7 +528,7 @@ class scriptModule: public RFModule if (b->size() != req_joints) { yError() << "invalid size of jointsMap parameter"; return false; } for (int i = 0; i < b->size(); i++) { - robot.joints_map[i] = b->get(i).asInt(); + robot.joints_map[i] = b->get(i).asInt32(); } } else @@ -575,8 +575,8 @@ class scriptModule: public RFModule cout << "load" << endl; cout << "forever" << endl; cout << "list" << endl; - reply.addVocab(Vocab::encode("many")); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("many"); + reply.addVocab32("ack"); reply.addString("Available commands:"); reply.addString("start"); reply.addString("stop"); @@ -598,7 +598,7 @@ class scriptModule: public RFModule this->b_thread.attachActions(&w_thread.actions); if (this->b_thread.isRunning()==false) b_thread.start(); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else if (cmdstring == "forever") { @@ -607,31 +607,31 @@ class scriptModule: public RFModule else this->w_thread.actions.current_status = ACTION_RUNNING; w_thread.actions.forever = true; - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else if (cmdstring == "stop") { this->w_thread.actions.current_status = ACTION_STOP; if (this->b_thread.isRunning()==true) b_thread.askToStop(); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else if (cmdstring == "clear") { this->w_thread.actions.clear(); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else if (cmdstring == "add") { if(!w_thread.actions.parseCommandLine(command.get(1).asString().c_str(), -1, robot.n_joints)) { yError() << "Unable to parse command"; - reply.addVocab(Vocab::encode("ERROR Unable to parse file")); + reply.addVocab32("error"); } else { yInfo() << "Command added"; - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } } else if (cmdstring == "load") @@ -640,12 +640,12 @@ class scriptModule: public RFModule if (!w_thread.actions.openFile(filename, robot.n_joints)) { yError() << "Unable to parse file"; - reply.addVocab(Vocab::encode("ERROR Unable to parse file")); + reply.addVocab32("error"); } else { yInfo() << "File opened"; - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } } else if (cmdstring == "reset") @@ -655,23 +655,23 @@ class scriptModule: public RFModule if (this->b_thread.isRunning()==true) b_thread.askToStop(); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else if (cmdstring == "list") { this->w_thread.actions.print(); - reply.addVocab(Vocab::encode("ack")); + reply.addVocab32("ack"); } else { - reply.addVocab(Vocab::encode("nack")); + reply.addVocab32("nack"); ret = false; } } } else { - reply.addVocab(Vocab::encode("nack")); + reply.addVocab32("nack"); ret = false; } diff --git a/src/tools/trajectoryPlayer/utils.h b/src/tools/trajectoryPlayer/utils.h index b2a893aaae..a8eae18235 100644 --- a/src/tools/trajectoryPlayer/utils.h +++ b/src/tools/trajectoryPlayer/utils.h @@ -43,13 +43,13 @@ using namespace yarp::sig; using namespace yarp::dev; using namespace yarp::math; -#define VCTP_TIME yarp::os::createVocab('t','i','m','e') -#define VCTP_OFFSET yarp::os::createVocab('o','f','f') -#define VCTP_CMD_NOW yarp::os::createVocab('c','t','p','n') -#define VCTP_CMD_QUEUE yarp::os::createVocab('c','t','p','q') -#define VCTP_CMD_FILE yarp::os::createVocab('c','t','p','f') -#define VCTP_POSITION yarp::os::createVocab('p','o','s') -#define VCTP_WAIT yarp::os::createVocab('w','a','i','t') +#define VCTP_TIME yarp::os::createVocab32('t','i','m','e') +#define VCTP_OFFSET yarp::os::createVocab32('o','f','f') +#define VCTP_CMD_NOW yarp::os::createVocab32('c','t','p','n') +#define VCTP_CMD_QUEUE yarp::os::createVocab32('c','t','p','q') +#define VCTP_CMD_FILE yarp::os::createVocab32('c','t','p','f') +#define VCTP_POSITION yarp::os::createVocab32('p','o','s') +#define VCTP_WAIT yarp::os::createVocab32('w','a','i','t') #define ACTION_IDLE 0 #define ACTION_START 1 diff --git a/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.cpp b/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.cpp index 7f8d6a0cfe..12abaca8a4 100644 --- a/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.cpp +++ b/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.cpp @@ -32,7 +32,7 @@ bool WholeBodyPlayerModule::updateModule() { response.clear(); // pause ok &= m_rpcPort.write(reqPause, response); - if (!ok || response.get(0).asVocab() != VOCAB_OK) { + if (!ok || response.get(0).asVocab32() != VOCAB_OK) { yError()<<"wholeBodyPlayer: the port"<getName()<<"is closed because the pause request failed.. closing"; return false; } @@ -47,7 +47,7 @@ bool WholeBodyPlayerModule::updateModule() { // start response.clear(); ok &= m_rpcPort.write(reqPlay, response); - if (!ok || response.get(0).asVocab() != VOCAB_OK) { + if (!ok || response.get(0).asVocab32() != VOCAB_OK) { yError()<<"wholeBodyPlayer: the port"<getName()<<"is closed because the start request failed.. closing"; return false; } diff --git a/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.h b/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.h index f2b9834306..1be26a8a03 100644 --- a/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.h +++ b/src/tools/wholeBodyPlayer/WholeBodyPlayerModule.h @@ -111,7 +111,7 @@ class ReplayPort : public yarp::os::BufferedPort bool ok = m_enc->getEncoders(m_currState.data()); m_mutex.lock(); for (size_t i=0; i max[i]) { yWarning()<<"ReplayPort: trying to move joint"< ok &= delta < tolerance; // TODO improve the check calculating the distance between the 2 vector !!! if (!ok && !m_simulator && (!m_isArm || i < 5)) { // 5 is for ignoring the hands in the security check yWarning()<<"ReplayPort: joint"<