#include <hpp/rbprm/rbprm-validation.hh>
|
virtual bool | validate (const core::Configuration_t &config) |
|
virtual bool | validate (const core::Configuration_t &config, core::ValidationReportPtr_t &validationReport) |
|
virtual bool | validate (const core::Configuration_t &config, const std::vector< std::string > &filter) |
|
virtual bool | validate (const core::Configuration_t &config, core::ValidationReportPtr_t &validationReport, const std::vector< std::string > &filter) |
|
virtual void | addObstacle (const core::CollisionObjectConstPtr_t &object) |
|
virtual void | removeObstacleFromJoint (const core::JointPtr_t &joint, const core::CollisionObjectPtr_t &obstacle) |
|
virtual void | randomnizeCollisionPairs () |
| randomnizeCollisionPairs More...
|
|
void | computeAllContacts (bool computeAllContacts) |
| set if the collision validation should compute all the possible contacts or stop after the first pairs in collision This method set the parameter for all the romValidations_ objects (but not the trunk) More...
|
|
|
static RbPrmValidationPtr_t | create (const pinocchio::RbPrmDevicePtr_t &robot, const std::vector< std::string > &filter=std::vector< std::string >(), const std::map< std::string, std::vector< std::string > > &affFilters=std::map< std::string, std::vector< std::string > >(), const affMap_t &affordances=affMap_t(), const core::ObjectStdVector_t &geometries=core::ObjectStdVector_t()) |
|
Validate a configuration with respect to the reachability condition; a Configuration is valid if the trunk robot is collision free while the Range Of Motion of the is colliding.
◆ RbPrmValidation()
hpp::rbprm::RbPrmValidation::RbPrmValidation |
( |
const pinocchio::RbPrmDevicePtr_t & |
robot, |
|
|
const std::vector< std::string > & |
filter, |
|
|
const std::map< std::string, std::vector< std::string > > & |
affFilters, |
|
|
const affMap_t & |
affordances, |
|
|
const core::ObjectStdVector_t & |
geometries |
|
) |
| |
|
protected |
◆ addObstacle()
virtual void hpp::rbprm::RbPrmValidation::addObstacle |
( |
const core::CollisionObjectConstPtr_t & |
object | ) |
|
|
virtual |
Add an obstacle to validation
- Parameters
-
object | obstacle added Store obstacle and build a collision pair with each body of the robot. this function has to be called for trunk validation and rom validation separately unless they use same obstacles (not usually the case) |
◆ computeAllContacts()
void hpp::rbprm::RbPrmValidation::computeAllContacts |
( |
bool |
computeAllContacts | ) |
|
set if the collision validation should compute all the possible contacts or stop after the first pairs in collision This method set the parameter for all the romValidations_ objects (but not the trunk)
◆ create()
static RbPrmValidationPtr_t hpp::rbprm::RbPrmValidation::create |
( |
const pinocchio::RbPrmDevicePtr_t & |
robot, |
|
|
const std::vector< std::string > & |
filter = std::vector< std::string >() , |
|
|
const std::map< std::string, std::vector< std::string > > & |
affFilters = std::map< std::string, std::vector< std::string > >() , |
|
|
const affMap_t & |
affordances = affMap_t() , |
|
|
const core::ObjectStdVector_t & |
geometries = core::ObjectStdVector_t() |
|
) |
| |
|
static |
◆ randomnizeCollisionPairs()
virtual void hpp::rbprm::RbPrmValidation::randomnizeCollisionPairs |
( |
| ) |
|
|
virtual |
randomnizeCollisionPairs
Rearrange the collisions pairs of all configValidation in a random manner
◆ removeObstacleFromJoint()
virtual void hpp::rbprm::RbPrmValidation::removeObstacleFromJoint |
( |
const core::JointPtr_t & |
joint, |
|
|
const core::CollisionObjectPtr_t & |
obstacle |
|
) |
| |
|
virtual |
Remove a collision pair between a joint and an obstacle
- Parameters
-
the | joint that holds the inner objects, |
the | obstacle to remove. This is applied for both trunk and rom shapes. This can be done for a single shape through trunkValidation_ and romValidation_ attributes. |
◆ validate() [1/4]
virtual bool hpp::rbprm::RbPrmValidation::validate |
( |
const core::Configuration_t & |
config | ) |
|
|
virtual |
Compute whether the configuration is valid
- Parameters
-
config | the config to check for validity, |
throwIfInValid | if true throw an exception if config is invalid. |
- Returns
- whether the whole config is valid.
◆ validate() [2/4]
virtual bool hpp::rbprm::RbPrmValidation::validate |
( |
const core::Configuration_t & |
config, |
|
|
core::ValidationReportPtr_t & |
validationReport |
|
) |
| |
|
virtual |
Compute whether the configuration is valid
- Parameters
-
config | the config to check for validity, |
- Return values
-
validationReport | report on validation (used only for rom shape). This parameter will dynamically cast into CollisionValidationReport type, |
- Returns
- whether the whole config is valid.
◆ validate() [3/4]
virtual bool hpp::rbprm::RbPrmValidation::validate |
( |
const core::Configuration_t & |
config, |
|
|
const std::vector< std::string > & |
filter |
|
) |
| |
|
virtual |
Compute whether the configuration is valid
- Parameters
-
config | the config to check for validity, |
- Return values
-
validationReport | report on validation (used only for rom shape). This parameter will dynamically cast into CollisionValidationReport type, |
- Returns
- whether the whole config is valid.
◆ validate() [4/4]
virtual bool hpp::rbprm::RbPrmValidation::validate |
( |
const core::Configuration_t & |
config, |
|
|
core::ValidationReportPtr_t & |
validationReport, |
|
|
const std::vector< std::string > & |
filter |
|
) |
| |
|
virtual |
Compute whether the configuration is valid
- Parameters
-
config | the config to check for validity, |
- Return values
-
validationReport | report on validation (used only for rom shape). This parameter will dynamically cast into CollisionValidationReport type, |
- Parameters
-
filter | specify constraints on all roms required to be in contact, will return false if all specified roms are not colliding |
- Returns
- whether the whole config is valid.
◆ boundValidation_
const core::JointBoundValidationPtr_t hpp::rbprm::RbPrmValidation::boundValidation_ |
◆ defaultFilter_
std::vector<std::string> hpp::rbprm::RbPrmValidation::defaultFilter_ |
◆ romValidations_
CollisionValidation for the range of motion of the limbs.
◆ trunkValidation_
const core::CollisionValidationPtr_t hpp::rbprm::RbPrmValidation::trunkValidation_ |
CollisionValidation for the trunk.
The documentation for this class was generated from the following file: