From 718ebda80e4a98d0f2e38b1560440ecb8b88828b Mon Sep 17 00:00:00 2001
From: Pierre Fernbach <pierre.fernbach@laas.fr>
Date: Wed, 8 Feb 2017 18:28:07 +0100
Subject: [PATCH] add optionnal parameter to generateContacts :
 robustnessThreshold

---
 idl/hpp/corbaserver/rbprm/rbprmbuilder.idl | 2 +-
 src/hpp/corbaserver/rbprm/rbprmfullbody.py | 6 +++---
 src/rbprmbuilder.impl.cc                   | 4 ++--
 src/rbprmbuilder.impl.hh                   | 2 +-
 4 files changed, 7 insertions(+), 7 deletions(-)

diff --git a/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl b/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl
index a14fb35..cadf322 100755
--- a/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl
+++ b/idl/hpp/corbaserver/rbprm/rbprmbuilder.idl
@@ -185,7 +185,7 @@ module hpp
     /// \param dofArray initial configuration of the robot
     /// \param direction desired direction of motion for the robot
     /// \return transformed configuration for which all possible contacts have been created
-    floatSeq generateContacts(in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration) raises (Error);
+    floatSeq generateContacts(in floatSeq dofArray, in floatSeq direction, in floatSeq acceleration, in double robustnessThreshold) raises (Error);
 
     /// Generate an autocollision free configuration with limbs in contact with the ground
     /// \param contactLimbs name of the limbs to project in contact
diff --git a/src/hpp/corbaserver/rbprm/rbprmfullbody.py b/src/hpp/corbaserver/rbprm/rbprmfullbody.py
index 64ba916..f250dc2 100755
--- a/src/hpp/corbaserver/rbprm/rbprmfullbody.py
+++ b/src/hpp/corbaserver/rbprm/rbprmfullbody.py
@@ -198,11 +198,11 @@ class FullBody (object):
 	## Generates a balanced contact configuration, considering the
     #  given current configuration of the robot, and a direction of motion.
     #  Typically used to generate a start and / or goal configuration automatically for a planning problem.
-	#
+    #
     # \param configuration the initial robot configuration
     # \param direction a 3d vector specifying the desired direction of motion
-    def generateContacts(self, configuration, direction,acceleration = [0,0,0]):
-      return self.client.rbprm.rbprm.generateContacts(configuration, direction, acceleration)
+    def generateContacts(self, configuration, direction,acceleration = [0,0,0], robustnessThreshold = 0):
+      return self.client.rbprm.rbprm.generateContacts(configuration, direction, acceleration, robustnessThreshold)
 		
 	## Generate an autocollision free configuration with limbs in contact with the ground
     # \param contactLimbs name of the limbs to project in contact
diff --git a/src/rbprmbuilder.impl.cc b/src/rbprmbuilder.impl.cc
index 5a3ba5b..4c5cb21 100755
--- a/src/rbprmbuilder.impl.cc
+++ b/src/rbprmbuilder.impl.cc
@@ -655,7 +655,7 @@ namespace hpp {
     }
 
     hpp::floatSeq* RbprmBuilder::generateContacts(const hpp::floatSeq& configuration,
-      const hpp::floatSeq& direction,const hpp::floatSeq& acceleration) throw (hpp::Error)
+      const hpp::floatSeq& direction,const hpp::floatSeq& acceleration, const double robustnessThreshold ) throw (hpp::Error)
     {
         if(!fullBodyLoaded_)
             throw Error ("No full body robot was loaded");
@@ -675,7 +675,7 @@ namespace hpp {
             model::Configuration_t config = dofArrayToConfig (fullBody_->device_, configuration);
 
             rbprm::State state = rbprm::ComputeContacts(fullBody_,config,
-              affMap, bindShooter_.affFilter_, dir,0,acc);
+              affMap, bindShooter_.affFilter_, dir,robustnessThreshold,acc);
             hpp::floatSeq* dofArray = new hpp::floatSeq();
             dofArray->length(_CORBA_ULong(state.configuration_.rows()));
             for(std::size_t i=0; i< _CORBA_ULong(config.rows()); i++)
diff --git a/src/rbprmbuilder.impl.hh b/src/rbprmbuilder.impl.hh
index 308933f..1bae486 100755
--- a/src/rbprmbuilder.impl.hh
+++ b/src/rbprmbuilder.impl.hh
@@ -131,7 +131,7 @@ namespace hpp {
         virtual double getEffectorDistance(unsigned short  state1, unsigned short  state2) throw (hpp::Error);
 
         virtual hpp::floatSeq* generateContacts(const hpp::floatSeq& configuration,
-                                                const hpp::floatSeq& direction, const hpp::floatSeq& acceleration) throw (hpp::Error);
+                                                const hpp::floatSeq& direction, const hpp::floatSeq& acceleration, const double robustnessThreshold) throw (hpp::Error);
 
         virtual hpp::floatSeq* generateGroundContact(const hpp::Names_t& contactLimbs) throw (hpp::Error);
 
-- 
GitLab