diff --git a/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl b/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl index 804504d7dc6f837650663985d6551977a7342dea..01b6ae8ed217393010f3876cfa323f1be4f0725e 100755 --- a/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl +++ b/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl @@ -279,12 +279,6 @@ module hpp /// \param contactLimbs ids of the limb in contact for the state void setStartState(in floatSeq dofArray, in Names_t contactLimbs) raises (Error); - /// Add a state to fullBody, defined by it's configuration and contacts - /// \param dofArray configuration of the robot - /// \param contactLimbs ids of the limb in contact for the state - short addState(in floatSeq dofArray, in Names_t contactLimbs) raises (Error); - - /// Compute effector contact points and normals for a given configuration /// in local coordinates /// \param dofArray configuration of the robot diff --git a/src/hpp/corbaserver/rbprm/rbprmfullbody.py b/src/hpp/corbaserver/rbprm/rbprmfullbody.py index b05bd52dc75f6f80e57c963dd3179f8d097f1da3..72f54a63eefd0f68740f4ece9fb3f390de088cd2 100755 --- a/src/hpp/corbaserver/rbprm/rbprmfullbody.py +++ b/src/hpp/corbaserver/rbprm/rbprmfullbody.py @@ -291,13 +291,6 @@ class FullBody (object): def setStartState(self, configuration, contacts): return self.client.rbprm.rbprm.setStartState(configuration, contacts) - ## Add a state to fullBody, defined by it's configurations and contacts - # - # \param configuration the desired state configuration - # \param contacts the array of limbs in contact - def addState(self, configuration, contacts): - return self.client.rbprm.rbprm.addState(configuration, contacts) - ## Create a state given a configuration and contacts # # \param configuration the desired start configuration diff --git a/src/rbprmbuilder.impl.cc b/src/rbprmbuilder.impl.cc index 32cd19ef50c3193a6c067badca7ab60c5d1965da..80410c02a31fba3ab05e53f5c4e812db8a9318e2 100755 --- a/src/rbprmbuilder.impl.cc +++ b/src/rbprmbuilder.impl.cc @@ -1260,23 +1260,6 @@ namespace hpp { } } - CORBA::Short RbprmBuilder::addState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error) - { - try - { - State state; - std::vector<std::string> names = stringConversion(contactLimbs); - SetPositionAndNormal(state,fullBody(), configuration, names); - lastStatesComputed_.push_back(state); - lastStatesComputedTime_.push_back(std::make_pair(0.,state)); - } - catch(std::runtime_error& e) - { - throw Error(e.what()); - } - return lastStatesComputed_.size()-1; - } - double RbprmBuilder::getTimeAtState(unsigned short stateId)throw (hpp::Error){ try diff --git a/src/rbprmbuilder.impl.hh b/src/rbprmbuilder.impl.hh index d699a9a7a9a2bc5bf7e940238215a8df8afc42b8..836b073ff088fa3172424bfc949a4367de2f1f1f 100755 --- a/src/rbprmbuilder.impl.hh +++ b/src/rbprmbuilder.impl.hh @@ -248,7 +248,6 @@ namespace hpp { virtual void setStartState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error); virtual void setEndState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error); - virtual CORBA::Short addState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error); virtual hpp::floatSeq* computeContactForConfig(const hpp::floatSeq& configuration, const char* limbNam) throw (hpp::Error); virtual hpp::floatSeqSeq* computeContactPoints(unsigned short cId) throw (hpp::Error); virtual hpp::floatSeqSeq* computeContactPointsAtState(unsigned short cId, unsigned short isIntermediate) throw (hpp::Error);