Commit b317b755 authored by Guilhem Saurel's avatar Guilhem Saurel
Browse files

Format

parent 05e12ede
Pipeline #6465 failed with stage
in 1 minute and 3 seconds
...@@ -18,37 +18,35 @@ ...@@ -18,37 +18,35 @@
// <http://www.gnu.org/licenses/>. // <http://www.gnu.org/licenses/>.
#ifndef HPP_RBPRM_CORBA_SERVER_HH #ifndef HPP_RBPRM_CORBA_SERVER_HH
# define HPP_RBPRM_CORBA_SERVER_HH #define HPP_RBPRM_CORBA_SERVER_HH
# include <hpp/corba/template/server.hh> #include <hpp/corba/template/server.hh>
# include <hpp/corbaserver/problem-solver-map.hh> #include <hpp/corbaserver/problem-solver-map.hh>
# include <hpp/corbaserver/rbprm/config.hh> #include <hpp/corbaserver/rbprm/config.hh>
# include <hpp/corbaserver/server-plugin.hh> #include <hpp/corbaserver/server-plugin.hh>
namespace hpp { namespace hpp {
namespace rbprm { namespace rbprm {
namespace impl { namespace impl {
class RbprmBuilder; class RbprmBuilder;
} }
class HPP_RBPRM_CORBA_DLLAPI Server : public corbaServer::ServerPlugin class HPP_RBPRM_CORBA_DLLAPI Server : public corbaServer::ServerPlugin {
{ public:
public: Server(corbaServer::Server* parent);
Server (corbaServer::Server* parent);
~Server();
~Server ();
/// Start corba server
/// Start corba server /// Call hpp::corba::Server <impl::Problem>::startCorbaServer
/// Call hpp::corba::Server <impl::Problem>::startCorbaServer void startCorbaServer(const std::string& contextId, const std::string& contextKind);
void startCorbaServer(const std::string& contextId,
const std::string& contextKind); std::string name() const;
std::string name () const; public:
corba::Server<impl::RbprmBuilder>* rbprmBuilder_;
public: }; // class Server
corba::Server <impl::RbprmBuilder>* rbprmBuilder_; } // namespace rbprm
}; // class Server } // namespace hpp
} // namespace rbprm
} // namespace hpp #endif // HPP_RBPRM_CORBA_SERVER_HH
#endif // HPP_RBPRM_CORBA_SERVER_HH
...@@ -16,12 +16,11 @@ ...@@ -16,12 +16,11 @@
// <http://www.gnu.org/licenses/>. // <http://www.gnu.org/licenses/>.
#ifndef HPP_MANIPULATION_CORBA_FWD_HH #ifndef HPP_MANIPULATION_CORBA_FWD_HH
# define HPP_MANIPULATION_CORBA_FWD_HH #define HPP_MANIPULATION_CORBA_FWD_HH
namespace hpp { namespace hpp {
namespace manipulation { namespace manipulation {
namespace corba { namespace corba {}
} } // namespace manipulation
} } // namespace hpp
} #endif // HPP_MANIPULATION_CORBA_FWD_HH
#endif // HPP_MANIPULATION_CORBA_FWD_HH
...@@ -19,15 +19,13 @@ ...@@ -19,15 +19,13 @@
#include <hpp/core/problem-solver.hh> #include <hpp/core/problem-solver.hh>
typedef hpp::corbaServer::Server CorbaServer; typedef hpp::corbaServer::Server CorbaServer;
int main (int argc, char* argv []) int main(int argc, char* argv[]) {
{ hpp::core::ProblemSolverPtr_t problemSolver(hpp::core::ProblemSolver::create());
hpp::core::ProblemSolverPtr_t problemSolver (hpp::core::ProblemSolver::create());
CorbaServer corbaServer (problemSolver, argc, CorbaServer corbaServer(problemSolver, argc, const_cast<const char**>(argv), true);
const_cast<const char**> (argv), true);
corbaServer.startCorbaServer (); corbaServer.startCorbaServer();
corbaServer.loadPlugin (corbaServer.mainContextId (), "rbprm-corba.so"); corbaServer.loadPlugin(corbaServer.mainContextId(), "rbprm-corba.so");
corbaServer.loadPlugin (corbaServer.mainContextId (), "affordance-corba.so"); corbaServer.loadPlugin(corbaServer.mainContextId(), "affordance-corba.so");
corbaServer.processRequest(true); corbaServer.processRequest(true);
} }
This source diff could not be displayed because it is too large. You can view the blob instead.
...@@ -16,410 +16,391 @@ ...@@ -16,410 +16,391 @@
// <http://www.gnu.org/licenses/>. // <http://www.gnu.org/licenses/>.
#ifndef HPP_RBPRM_CORBA_BUILDER_IMPL_HH #ifndef HPP_RBPRM_CORBA_BUILDER_IMPL_HH
# define HPP_RBPRM_CORBA_BUILDER_IMPL_HH #define HPP_RBPRM_CORBA_BUILDER_IMPL_HH
# include <hpp/core/problem-solver.hh> #include <hpp/core/problem-solver.hh>
# include <hpp/core/path.hh> #include <hpp/core/path.hh>
# include "hpp/corbaserver/rbprm/rbprmbuilder-idl.hh" #include "hpp/corbaserver/rbprm/rbprmbuilder-idl.hh"
# include <hpp/rbprm/rbprm-device.hh> #include <hpp/rbprm/rbprm-device.hh>
# include <hpp/rbprm/rbprm-fullbody.hh> #include <hpp/rbprm/rbprm-fullbody.hh>
# include <hpp/rbprm/rbprm-shooter.hh> #include <hpp/rbprm/rbprm-shooter.hh>
# include <hpp/rbprm/rbprm-validation.hh> #include <hpp/rbprm/rbprm-validation.hh>
# include <hpp/rbprm/sampling/analysis.hh> #include <hpp/rbprm/sampling/analysis.hh>
# include <hpp/core/collision-path-validation-report.hh> #include <hpp/core/collision-path-validation-report.hh>
# include <hpp/core/problem-solver.hh> #include <hpp/core/problem-solver.hh>
# include <hpp/core/straight-path.hh> #include <hpp/core/straight-path.hh>
# include <hpp/core/problem.hh> #include <hpp/core/problem.hh>
#include <hpp/corbaserver/affordance/server.hh> #include <hpp/corbaserver/affordance/server.hh>
# include <hpp/corbaserver/problem-solver-map.hh> #include <hpp/corbaserver/problem-solver-map.hh>
# include <hpp/rbprm/rbprm-path-validation.hh> #include <hpp/rbprm/rbprm-path-validation.hh>
# include <hpp/fcl/BVH/BVH_model.h> #include <hpp/fcl/BVH/BVH_model.h>
# include <hpp/core/config-validations.hh> #include <hpp/core/config-validations.hh>
#include <hpp/rbprm/dynamic/dynamic-path-validation.hh> #include <hpp/rbprm/dynamic/dynamic-path-validation.hh>
# include "hpp/corbaserver/fwd.hh" #include "hpp/corbaserver/fwd.hh"
# include "hpp/corbaserver/rbprm/server.hh" #include "hpp/corbaserver/rbprm/server.hh"
namespace hpp { namespace hpp {
namespace rbprm { namespace rbprm {
namespace impl { namespace impl {
using CORBA::Short; using CORBA::Short;
typedef hpp::core::Container <hpp::core::AffordanceObjects_t> affMap_t; typedef hpp::core::Container<hpp::core::AffordanceObjects_t> affMap_t;
struct BindShooter struct BindShooter {
{ BindShooter(const std::size_t shootLimit = 10000, const std::size_t displacementLimit = 100)
BindShooter(const std::size_t shootLimit = 10000, : shootLimit_(shootLimit), displacementLimit_(displacementLimit) {}
const std::size_t displacementLimit = 100)
: shootLimit_(shootLimit) hpp::rbprm::RbPrmShooterPtr_t create(
, displacementLimit_(displacementLimit) {} /*const hpp::pinocchio::DevicePtr_t& robot,*/ const hpp::core::Problem& problem) {
affMap_ = problemSolver_->affordanceObjects;
hpp::rbprm::RbPrmShooterPtr_t create (/*const hpp::pinocchio::DevicePtr_t& robot,*/ const hpp::core::Problem& problem) hpp::pinocchio::RbPrmDevicePtr_t robotcast =
{ boost::static_pointer_cast<hpp::pinocchio::RbPrmDevice>(problem.robot());
affMap_ = problemSolver_->affordanceObjects; if (affMap_.map.empty()) {
hpp::pinocchio::RbPrmDevicePtr_t robotcast = boost::static_pointer_cast<hpp::pinocchio::RbPrmDevice>(problem.robot()); throw hpp::Error("No affordances found. Unable to create shooter object.");
if (affMap_.map.empty ()) { }
throw hpp::Error ("No affordances found. Unable to create shooter object."); rbprm::RbPrmShooterPtr_t shooter =
} hpp::rbprm::RbPrmShooter::create(robotcast, problemSolver_->problem()->collisionObstacles(), affMap_,
rbprm::RbPrmShooterPtr_t shooter = hpp::rbprm::RbPrmShooter::create romFilter_, affFilter_, shootLimit_, displacementLimit_);
(robotcast, problemSolver_->problem ()->collisionObstacles(), affMap_, if (!so3Bounds_.empty()) shooter->BoundSO3(so3Bounds_);
romFilter_,affFilter_,shootLimit_,displacementLimit_); shooter->sampleExtraDOF(problem.getParameter("ConfigurationShooter/sampleExtraDOF").boolValue());
if(!so3Bounds_.empty()) shooter->ratioWeighted(problem.getParameter("RbprmShooter/ratioWeighted").floatValue());
shooter->BoundSO3(so3Bounds_); return shooter;
shooter->sampleExtraDOF(problem.getParameter("ConfigurationShooter/sampleExtraDOF").boolValue()); }
shooter->ratioWeighted(problem.getParameter("RbprmShooter/ratioWeighted").floatValue ());
return shooter; hpp::core::PathValidationPtr_t createPathValidation(const hpp::pinocchio::DevicePtr_t& robot,
} const hpp::pinocchio::value_type& val) {
hpp::pinocchio::RbPrmDevicePtr_t robotcast = boost::static_pointer_cast<hpp::pinocchio::RbPrmDevice>(robot);
hpp::core::PathValidationPtr_t createPathValidation (const hpp::pinocchio::DevicePtr_t& robot, const hpp::pinocchio::value_type& val) affMap_ = problemSolver_->affordanceObjects;
{ if (affMap_.map.empty()) {
hpp::pinocchio::RbPrmDevicePtr_t robotcast = boost::static_pointer_cast<hpp::pinocchio::RbPrmDevice>(robot); throw hpp::Error("No affordances found. Unable to create Path Validaton object.");
affMap_ = problemSolver_->affordanceObjects; }
if (affMap_.map.empty ()) { hpp::rbprm::RbPrmValidationPtr_t validation(
throw hpp::Error ("No affordances found. Unable to create Path Validaton object."); hpp::rbprm::RbPrmValidation::create(robotcast, romFilter_, affFilter_, affMap_));
} hpp::rbprm::RbPrmPathValidationPtr_t collisionChecking = hpp::rbprm::RbPrmPathValidation::create(robot, val);
hpp::rbprm::RbPrmValidationPtr_t validation collisionChecking->add(validation);
(hpp::rbprm::RbPrmValidation::create(robotcast, romFilter_, affFilter_, affMap_)); problemSolver_->problem()->configValidation(core::ConfigValidations::create());
hpp::rbprm::RbPrmPathValidationPtr_t collisionChecking = hpp::rbprm::RbPrmPathValidation::create(robot,val); problemSolver_->problem()->configValidations()->add(validation);
collisionChecking->add (validation); return collisionChecking;
problemSolver_->problem()->configValidation(core::ConfigValidations::create ()); }
problemSolver_->problem()->configValidations()->add(validation);
return collisionChecking; hpp::core::PathValidationPtr_t createDynamicPathValidation(const hpp::pinocchio::DevicePtr_t& robot,
} const hpp::pinocchio::value_type& val) {
hpp::pinocchio::RbPrmDevicePtr_t robotcast = boost::static_pointer_cast<hpp::pinocchio::RbPrmDevice>(robot);
hpp::core::PathValidationPtr_t createDynamicPathValidation (const hpp::pinocchio::DevicePtr_t& robot, const hpp::pinocchio::value_type& val) affMap_ = problemSolver_->affordanceObjects;
{ if (affMap_.map.empty()) {
hpp::pinocchio::RbPrmDevicePtr_t robotcast = boost::static_pointer_cast<hpp::pinocchio::RbPrmDevice>(robot); throw hpp::Error("No affordances found. Unable to create Path Validaton object.");
affMap_ = problemSolver_->affordanceObjects; }
if (affMap_.map.empty ()) { hpp::rbprm::RbPrmValidationPtr_t validation(
throw hpp::Error ("No affordances found. Unable to create Path Validaton object."); hpp::rbprm::RbPrmValidation::create(robotcast, romFilter_, affFilter_, affMap_));
} hpp::rbprm::DynamicPathValidationPtr_t collisionChecking = hpp::rbprm::DynamicPathValidation::create(robot, val);
hpp::rbprm::RbPrmValidationPtr_t validation collisionChecking->add(validation);
(hpp::rbprm::RbPrmValidation::create(robotcast, romFilter_, affFilter_, affMap_)); problemSolver_->problem()->configValidation(core::ConfigValidations::create());
hpp::rbprm::DynamicPathValidationPtr_t collisionChecking = hpp::rbprm::DynamicPathValidation::create(robot,val); problemSolver_->problem()->configValidations()->add(validation);
collisionChecking->add (validation); // build the dynamicValidation :
problemSolver_->problem()->configValidation(core::ConfigValidations::create ()); double sizeFootX, sizeFootY, mass, mu;
problemSolver_->problem()->configValidations()->add(validation); bool rectangularContact;
// build the dynamicValidation : sizeFootX = problemSolver_->problem()->getParameter(std::string("DynamicPlanner/sizeFootX")).floatValue() / 2.;
double sizeFootX,sizeFootY,mass,mu; sizeFootY = problemSolver_->problem()->getParameter(std::string("DynamicPlanner/sizeFootY")).floatValue() / 2.;
bool rectangularContact; if (sizeFootX > 0. && sizeFootY > 0.)
sizeFootX = problemSolver_->problem()->getParameter (std::string("DynamicPlanner/sizeFootX")).floatValue()/2.; rectangularContact = 1;
sizeFootY = problemSolver_->problem()->getParameter (std::string("DynamicPlanner/sizeFootY")).floatValue()/2.; else
if(sizeFootX > 0. && sizeFootY > 0.) rectangularContact = 0;
rectangularContact = 1; mass = robot->mass();
else mu = problemSolver_->problem()->getParameter(std::string("DynamicPlanner/friction")).floatValue();
rectangularContact = 0; hppDout(notice, "mu define in python : " << mu);
mass = robot->mass(); DynamicValidationPtr_t dynamicVal =
mu = problemSolver_->problem()->getParameter (std::string("DynamicPlanner/friction")).floatValue(); DynamicValidation::create(rectangularContact, sizeFootX, sizeFootY, mass, mu, robot);
hppDout(notice,"mu define in python : "<<mu); collisionChecking->addDynamicValidator(dynamicVal);
DynamicValidationPtr_t dynamicVal = DynamicValidation::create(rectangularContact,sizeFootX,sizeFootY,mass,mu,robot);
collisionChecking->addDynamicValidator(dynamicVal); return collisionChecking;
}
return collisionChecking;
} hpp::core::ProblemSolverPtr_t problemSolver_;
std::vector<std::string> romFilter_;
hpp::core::ProblemSolverPtr_t problemSolver_; std::map<std::string, std::vector<std::string> > affFilter_;
std::vector<std::string> romFilter_; std::size_t shootLimit_;
std::map<std::string, std::vector<std::string> > affFilter_; std::size_t displacementLimit_;
std::size_t shootLimit_; std::vector<double> so3Bounds_;
std::size_t displacementLimit_; affMap_t affMap_;
std::vector<double> so3Bounds_; };
affMap_t affMap_;
}; class FullBodyMap {
public:
class FullBodyMap { typedef std::map<std::string, rbprm::RbPrmFullBodyPtr_t> fMap_t;
public:
typedef std::map<std::string, rbprm::RbPrmFullBodyPtr_t> fMap_t; std::string selected_;
fMap_t map_;
std::string selected_;
fMap_t map_; FullBodyMap(const std::string& name = "None") : selected_(name) {
// map_[selected_] = init;
FullBodyMap (const std::string& name = "None") : }
selected_ (name)
{ rbprm::RbPrmFullBodyPtr_t operator->() { return selected(); }
//map_[selected_] = init; operator rbprm::RbPrmFullBodyPtr_t() { return selected(); }
} rbprm::RbPrmFullBodyPtr_t selected() { return map_[selected_]; }
bool has(const std::string& name) const {
rbprm::RbPrmFullBodyPtr_t operator-> () { // ProblemMap_t::const_iterator it = map_.find (name);
return selected(); // return it != map_.end ();
} return map_.end() != map_.find(name);
operator rbprm::RbPrmFullBodyPtr_t () { }
return selected(); template <typename ReturnType>
} ReturnType keys() const {
rbprm::RbPrmFullBodyPtr_t selected () { ReturnType l;
return map_[selected_]; for (fMap_t::const_iterator it = map_.begin(); it != map_.end(); ++it) l.push_back(it->first);
} return l;
bool has (const std::string& name) const }
{ };
// ProblemMap_t::const_iterator it = map_.find (name);
// return it != map_.end (); class RbprmBuilder : public virtual POA_hpp::corbaserver::rbprm::RbprmBuilder {
return map_.end() != map_.find (name); public:
} RbprmBuilder();
template <typename ReturnType> ReturnType keys () const
{ void setServer(Server* server) { server_ = server; }
ReturnType l;
for (fMap_t::const_iterator it = map_.begin (); virtual void loadRobotRomModel(const char* robotName, const char* rootJointType, const char* packageName,
it != map_.end (); ++it) const char* modelName, const char* urdfSuffix,
l.push_back (it->first); const char* srdfSuffix) throw(hpp::Error);
return l;
} virtual void loadRobotCompleteModel(const char* robotName, const char* rootJointType, const char* packageName,
}; const char* modelName, const char* urdfSuffix,
const char* srdfSuffix) throw(hpp::Error);
class RbprmBuilder : public virtual POA_hpp::corbaserver::rbprm::RbprmBuilder
{ virtual void loadFullBodyRobot(const char* robotName, const char* rootJointType, const char* packageName,
public: const char* modelName, const char* urdfSuffix, const char* srdfSuffix,
RbprmBuilder (); const char* selectedProblem) throw(hpp::Error);
void setServer (Server* server) virtual void loadFullBodyRobotFromExistingRobot() throw(hpp::Error);
{
server_ = server; void setStaticStability(const bool staticStability) throw(hpp::Error);
}
void setReferenceConfig(const hpp::floatSeq& referenceConfig) throw(hpp::Error);
virtual void loadRobotRomModel (const char* robotName, void setPostureWeights(const hpp::floatSeq& postureWeights) throw(hpp::Error);
const char* rootJointType, void setReferenceEndEffector(const char* romName, const hpp::floatSeq& ref) throw(hpp::Error);
const char* packageName, void usePosturalTaskContactCreation(const bool usePosturalTaskContactCreation) throw(hpp::Error);
const char* modelName,
const char* urdfSuffix, virtual void setFilter(const hpp::Names_t& roms) throw(hpp::Error);
const char* srdfSuffix) throw (hpp::Error); virtual void setAffordanceFilter(const char* romName, const hpp::Names_t& affordances) throw(hpp::Error);
virtual void boundSO3(const hpp::floatSeq& limitszyx) throw(hpp::Error);
virtual void loadRobotCompleteModel (const char* robotName,
const char* rootJointType, virtual hpp::floatSeq* getSampleConfig(const char* limb, unsigned int sampleId) throw(hpp::Error);
const char* packageName, virtual hpp::floatSeq* getSamplePosition(const char* limb, unsigned int sampleId) throw(hpp::Error);
const char* modelName, virtual hpp::floatSeqSeq* getEffectorPosition(const char* limb,
const char* urdfSuffix, const hpp::floatSeq& configuration) throw(hpp::Error);
const char* srdfSuffix) throw (hpp::Error); virtual CORBA::UShort getNumSamples(const char* limb) throw(hpp::Error);
virtual hpp::floatSeq* getOctreeNodeIds(const char* limb) throw(hpp::Error);
virtual double getSampleValue(const char* limb, const char* valueName, unsigned int sampleId) throw(hpp::Error);
virtual void loadFullBodyRobot (const char* robotName, virtual double getEffectorDistance(unsigned short state1, unsigned short state2) throw(hpp::Error);
const char* rootJointType,
const char* packageName, rbprm::State generateContacts_internal(const hpp::floatSeq& configuration, const hpp::floatSeq& direction,
const char* modelName, const hpp::floatSeq& acceleration,
const char* urdfSuffix, const double robustnessThreshold) throw(hpp::Error);
const char* srdfSuffix, virtual hpp::floatSeq* generateContacts(const hpp::floatSeq& configuration, const hpp::floatSeq& direction,
const char* selectedProblem) throw (hpp::Error); const hpp::floatSeq& acceleration,
const double robustnessThreshold) throw(hpp::Error);
virtual void loadFullBodyRobotFromExistingRobot () throw (hpp::Error); virtual CORBA::Short generateStateInContact(const hpp::floatSeq& configuration, const hpp::floatSeq& direction,
const hpp::floatSeq& acceleration,
void setStaticStability(const bool staticStability) throw (hpp::Error); const double robustnessThreshold) throw(hpp::Error);
void setReferenceConfig(const hpp::floatSeq &referenceConfig) throw (hpp::Error); virtual hpp::floatSeq* generateGroundContact(const hpp::Names_t& contactLimbs) throw(hpp::Error);
void setPostureWeights(const hpp::floatSeq &postureWeights) throw (hpp::Error);
void setReferenceEndEffector(const char* romName, const hpp::floatSeq &ref) throw(hpp::Error); virtual hpp::floatSeq* getContactSamplesIds(const char* limb, const hpp::floatSeq& configuration,
void usePosturalTaskContactCreation(const bool usePosturalTaskContactCreation) throw (hpp::Error); const hpp::floatSeq& direction) throw(hpp::Error);
virtual void setFilter(const hpp::Names_t& roms) throw (hpp::Error); virtual hpp::floatSeqSeq* getContactSamplesProjected(const char* limb, const hpp::floatSeq& configuration,
virtual void setAffordanceFilter(const char* romName, const hpp::Names_t& affordances) throw (hpp::Error); const hpp::floatSeq& direction,
virtual void boundSO3(const hpp::floatSeq& limitszyx) throw (hpp::Error); unsigned short numSamples) throw(hpp::Error);
virtual short generateContactState(::CORBA::UShort currentState, const char* name,
virtual hpp::floatSeq* getSampleConfig(const char* limb, unsigned int sampleId) throw (hpp::Error); const ::hpp::floatSeq& direction) throw(hpp::Error);
virtual hpp::floatSeq* getSamplePosition(const char* limb, unsigned int sampleId) throw (hpp::Error);
virtual hpp::floatSeqSeq* getEffectorPosition(const char* limb, const hpp::floatSeq& configuration) throw (hpp::Error); virtual hpp::floatSeq* getSamplesIdsInOctreeNode(const char* limb, double octreeNodeId) throw(hpp::Error);
virtual CORBA::UShort getNumSamples(const char* limb) throw (hpp::Error);
virtual hpp::floatSeq* getOctreeNodeIds(const char* limb) throw (hpp::Error); virtual void addLimb(const char* id, const char* limb, const char* effector, const hpp::floatSeq& offset,
virtual double getSampleValue(const char* limb, const char* valueName, unsigned int sampleId) throw (hpp::Error); const hpp::floatSeq& normal, double x, double y, unsigned int samples,
virtual double getEffectorDistance(unsigned short state1, unsigned short state2) throw (hpp::Error); const char* heuristicName, double resolution, const char* contactType,
double disableEffectorCollision, double grasp, const hpp::floatSeq& limbOffset,
rbprm::State generateContacts_internal(const hpp::floatSeq& configuration, const char* kinematicConstraintsPath, double kinematicConstraintsMin) throw(hpp::Error);
const hpp::floatSeq& direction,const hpp::floatSeq& acceleration, const double robustnessThreshold ) throw (hpp::Error); virtual void addNonContactingLimb(const char* id, const char* limb, const char* effector,
virtual hpp::floatSeq* generateContacts(const hpp::floatSeq& configuration, unsigned int samples) throw(hpp::Error);
const hpp::floatSeq& direction, const hpp::floatSeq& acceleration, const double robustnessThreshold) throw (hpp::Error);
virtual CORBA::Short generateStateInContact(const hpp::floatSeq& configuration, virtual void addLimbDatabase(const char* databasePath, const char* id, const char* heuristicName, double loadValues,
const hpp::floatSeq& direction, const hpp::floatSeq& acceleration, const double robustnessThreshold) throw (hpp::Error); double disableEffectorCollision, double grasp) throw(hpp::Error);
virtual hpp::floatSeq* generateGroundContact(const hpp::Names_t& contactLimbs) throw (hpp::Error); 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 hpp::floatSeq* getContactSamplesIds(const char* limb, virtual void setStartStateId(unsigned short stateId) throw(hpp::Error);
const hpp::floatSeq& configuration, virtual void setEndStateId(unsigned short stateId) throw(hpp::Error);
const hpp::floatSeq& direction) throw (hpp::Error); virtual hpp::floatSeq* computeContactForConfig(const hpp::floatSeq& configuration,
const char* limbNam) throw(hpp::Error);
virtual hpp::floatSeqSeq* getContactSamplesProjected(const char* limb, virtual hpp::floatSeqSeq* computeContactPoints(unsigned short cId) throw(hpp::Error);
const hpp::floatSeq& configuration, virtual hpp::floatSeqSeq* computeContactPointsAtState(unsigned short cId,
const hpp::floatSeq& direction, unsigned short isIntermediate) throw(hpp::Error);
unsigned short numSamples) throw (hpp::Error); virtual hpp::floatSeqSeq* computeContactPointsForLimb(unsigned short cId, const char* limbName) throw(hpp::Error);
virtual hpp::floatSeqSeq* computeContactPointsAtStateForLimb(unsigned short cId, unsigned short isIntermediate,
virtual short generateContactState(::CORBA::UShort currentState, const char* name, const ::hpp::floatSeq& direction) throw (hpp::Error); const char* limbName) throw(hpp::Error);
virtual hpp::floatSeqSeq* computeCenterOfContactAtStateForLimb(unsigned short cId, unsigned short isIntermediate,
const char* limbName) throw(hpp::Error);
virtual hpp::floatSeq* getSamplesIdsInOctreeNode(const char* limb, virtual hpp::floatSeqSeq* interpolate(double timestep, double path, double robustnessTreshold,
double octreeNodeId) throw (hpp::Error); unsigned short filterStates, bool testReachability, bool quasiStatic,
bool erasePreviousStates) throw(hpp::Error);
virtual void addLimb(const char* id, const char* limb, const char* effector, const hpp::floatSeq& offset, const hpp::floatSeq& normal, double x, double y, virtual hpp::floatSeqSeq* interpolateConfigs(const hpp::floatSeqSeq& configs, double robustnessTreshold,
unsigned int samples, const char *heuristicName, double resolution, const char *contactType, unsigned short filterStates, bool testReachability, bool quasiStatic,
double disableEffectorCollision, double grasp,const hpp::floatSeq& limbOffset,const char* kinematicConstraintsPath, double kinematicConstraintsMin) throw (hpp::Error); bool erasePreviousStates) throw(hpp::Error);
virtual void addNonContactingLimb(const char* id, const char* limb, const char* effector, unsigned int samples) throw (hpp::Error); virtual hpp::floatSeqSeq* getContactCone(unsigned short stateId, double friction) throw(hpp::Error);
virtual hpp::floatSeqSeq* getContactIntermediateCone(unsigned short stateId, double friction) throw(hpp::Error);
virtual void addLimbDatabase(const char* databasePath, const char* id, const char* heuristicName, double loadValues, virtual CORBA::Short generateComTraj(const hpp::floatSeqSeq& positions, const hpp::floatSeqSeq& velocities,
double disableEffectorCollision, double grasp) throw (hpp::Error); const hpp::floatSeqSeq& accelerations, const double dt) throw(hpp::Error);
virtual void setStartState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error); virtual CORBA::Short straightPath(const hpp::floatSeqSeq& positions) throw(hpp::Error);
virtual void setEndState(const hpp::floatSeq& configuration, const hpp::Names_t& contactLimbs) throw (hpp::Error); virtual CORBA::Short generateCurveTraj(const hpp::floatSeqSeq& positions) throw(hpp::Error);
virtual void setStartStateId(unsigned short stateId) throw (hpp::Error); virtual CORBA::Short generateCurveTrajParts(const hpp::floatSeqSeq& positions,
virtual void setEndStateId(unsigned short stateId) throw (hpp::Error); const hpp::floatSeq& partitions) throw(hpp::Error);
virtual hpp::floatSeq* computeContactForConfig(const hpp::floatSeq& configuration, const char* limbNam) throw (hpp::Error); virtual CORBA::Short generateRootPath(const hpp::floatSeqSeq& rootPositions, const hpp::floatSeq& q1,
virtual hpp::floatSeqSeq* computeContactPoints(unsigned short cId) throw (hpp::Error); const hpp::floatSeq& q2) throw(hpp::Error);
virtual hpp::floatSeqSeq* computeContactPointsAtState(unsigned short cId, unsigned short isIntermediate) throw (hpp::Error); virtual CORBA::Short limbRRT(unsigned short state1, unsigned short state2,
virtual hpp::floatSeqSeq* computeContactPointsForLimb(unsigned short cId, const char* limbName) throw (hpp::Error); unsigned short numOptimizations) throw(hpp::Error);
virtual hpp::floatSeqSeq* computeContactPointsAtStateForLimb(unsigned short cId, unsigned short isIntermediate, const char* limbName) throw (hpp::Error); virtual CORBA::Short limbRRTFromRootPath(unsigned short state1, unsigned short state2, unsigned short path,
virtual hpp::floatSeqSeq* computeCenterOfContactAtStateForLimb(unsigned short cId, unsigned short isIntermediate, const char *limbName) throw (hpp::Error); unsigned short numOptimizations) throw(hpp::Error);
virtual hpp::floatSeqSeq* interpolate(double timestep, double path, double robustnessTreshold, unsigned short filterStates, bool testReachability, bool quasiStatic, bool erasePreviousStates) throw (hpp::Error); virtual CORBA::Short configToPath(const hpp::floatSeqSeq& configs) throw(hpp::Error);
virtual hpp::floatSeqSeq* interpolateConfigs(const hpp::floatSeqSeq& configs, double robustnessTreshold, unsigned short filterStates, bool testReachability, bool quasiStatic, bool erasePreviousStates) throw (hpp::Error); virtual CORBA::Short comRRT(unsigned short state1, unsigned short state2, unsigned short path,
virtual