Commit 0e9d3108 authored by Pierre Fernbach's avatar Pierre Fernbach
Browse files

[python api] addNewContact : add optional parameter 'lockOtherJoints'

parent 2807b9ac
...@@ -747,8 +747,10 @@ module hpp ...@@ -747,8 +747,10 @@ module hpp
/// \param p 3d position of the point /// \param p 3d position of the point
/// \param n 3d normal of the contact location center /// \param n 3d normal of the contact location center
/// \param max_num_sample number of times it will try to randomly sample a configuration before failing /// \param max_num_sample number of times it will try to randomly sample a configuration before failing
/// \param lockOtherJoints : if True, the values of all the joints exepct the ones of 'limbName' are constrained to be constant.
/// This only affect the first projection, if max_num_sample > 0 and the first projection was unsuccessfull, the parameter is ignored
/// \return (success,NState) whether the creation was successful, as well as the new state /// \return (success,NState) whether the creation was successful, as well as the new state
short addNewContact(in unsigned short stateId, in string limbName, in floatSeq position, in floatSeq normal, in unsigned short max_num_sample) raises (Error); short addNewContact(in unsigned short stateId, in string limbName, in floatSeq position, in floatSeq normal, in unsigned short max_num_sample, in boolean lockOtherJoints) raises (Error);
/// removes a contact from the state /// removes a contact from the state
/// if the limb is not already in contact, does nothing /// if the limb is not already in contact, does nothing
......
...@@ -3230,7 +3230,7 @@ namespace hpp { ...@@ -3230,7 +3230,7 @@ namespace hpp {
CORBA::Short RbprmBuilder::addNewContact(unsigned short stateId, const char* limbName, CORBA::Short RbprmBuilder::addNewContact(unsigned short stateId, const char* limbName,
const hpp::floatSeq& position, const hpp::floatSeq& normal, unsigned short max_num_sample) throw (hpp::Error) const hpp::floatSeq& position, const hpp::floatSeq& normal, unsigned short max_num_sample, bool lockOtherJoints) throw (hpp::Error)
{ {
try try
{ {
...@@ -3244,7 +3244,7 @@ namespace hpp { ...@@ -3244,7 +3244,7 @@ namespace hpp {
config = dofArrayToConfig (std::size_t(3), normal); config = dofArrayToConfig (std::size_t(3), normal);
fcl::Vec3f n; for(int i =0; i<3; ++i) n[i] = config[i]; fcl::Vec3f n; for(int i =0; i<3; ++i) n[i] = config[i];
projection::ProjectionReport rep = projection::projectStateToObstacle(fullBody(),limb, fullBody()->GetLimbs().at(limb), ns, n,p); projection::ProjectionReport rep = projection::projectStateToObstacle(fullBody(),limb, fullBody()->GetLimbs().at(limb), ns, n,p,lockOtherJoints);
hppDout(notice,"Projection State to obstacle success : "<<rep.success_); hppDout(notice,"Projection State to obstacle success : "<<rep.success_);
hppDout(notice,"report status : "<<rep.status_); hppDout(notice,"report status : "<<rep.status_);
ValidationReportPtr_t rport (ValidationReportPtr_t(new CollisionValidationReport)); ValidationReportPtr_t rport (ValidationReportPtr_t(new CollisionValidationReport));
......
...@@ -349,7 +349,7 @@ namespace hpp { ...@@ -349,7 +349,7 @@ namespace hpp {
virtual Names_t* getContactsVariations(unsigned short stateIdFrom,unsigned short stateIdTo )throw (hpp::Error); virtual Names_t* getContactsVariations(unsigned short stateIdFrom,unsigned short stateIdTo )throw (hpp::Error);
virtual Names_t* getAllLimbsNames()throw (hpp::Error); virtual Names_t* getAllLimbsNames()throw (hpp::Error);
virtual CORBA::Short addNewContact(unsigned short stateId, const char* limbName, virtual CORBA::Short addNewContact(unsigned short stateId, const char* limbName,
const hpp::floatSeq& position, const hpp::floatSeq& normal, unsigned short max_num_sample) throw (hpp::Error); const hpp::floatSeq& position, const hpp::floatSeq& normal, unsigned short max_num_sample, bool lockOtherJoints) throw (hpp::Error);
virtual CORBA::Short removeContact(unsigned short stateId, const char* limbName) throw (hpp::Error); virtual CORBA::Short removeContact(unsigned short stateId, const char* limbName) throw (hpp::Error);
virtual hpp::floatSeq* computeTargetTransform(const char* limbName, const hpp::floatSeq& configuration, const hpp::floatSeq& p, const hpp::floatSeq& n) throw (hpp::Error); virtual hpp::floatSeq* computeTargetTransform(const char* limbName, const hpp::floatSeq& configuration, const hpp::floatSeq& p, const hpp::floatSeq& n) throw (hpp::Error);
virtual Names_t* getEffectorsTrajectoriesNames(unsigned short pathId)throw (hpp::Error); virtual Names_t* getEffectorsTrajectoriesNames(unsigned short pathId)throw (hpp::Error);
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment