1 #ifndef PLANNER_SETTINGS_H 2 #define PLANNER_SETTINGS_H 5 #include <KrisLibrary/structs/array2d.h> 6 #include <KrisLibrary/geometry/CollisionMesh.h> 7 #include <KrisLibrary/utils/PropertyMap.h> 55 bool CheckCollision(
RobotWorld& world,
int id1,
int id2=-1,Real tol=0);
57 bool CheckCollision(
RobotWorld& world,Geometry::AnyCollisionGeometry3D* mesh,
int id=-1,Real tol=0);
63 pair<int,int> CheckCollision(
RobotWorld& world,
const vector<int>& ids,Real tol=0);
68 pair<int,int> CheckCollision(
RobotWorld& world,
const vector<int>& ids1,
const vector<int>& ids2,Real tol=0);
73 Real DistanceLowerBound(
RobotWorld& world,
int id1,
int id2=-1,Real eps=0,Real bound=Inf);
76 Real DistanceLowerBound(
RobotWorld& world,Geometry::AnyCollisionGeometry3D* mesh,
int id,Real eps=0,Real bound=Inf);
82 Real DistanceLowerBound(
RobotWorld& world,
const vector<int>& ids,Real eps=0,Real bound=Inf,
int* closest1=NULL,
int* closest2=NULL);
87 Real DistanceLowerBound(
RobotWorld& world,
const vector<int>& ids1,
const vector<int>& ids2,Real eps=0,Real bound=Inf,
int* closest1=NULL,
int* closest2=NULL);
90 void EnumerateCollisionPairs(
RobotWorld& world,vector<pair<int,int> >& pairs)
const;
94 void EnumerateCollisionQueries(
RobotWorld& world,
int id1,
int id2,
95 vector<pair<int,int> >& pairs,
96 vector<Geometry::AnyCollisionQuery>& queries);
98 void EnumerateCollisionQueries(
RobotWorld& world,Geometry::AnyCollisionGeometry3D* mesh,
int id,
99 vector<int>& checkedIDs,
100 vector<Geometry::AnyCollisionQuery>& queries);
102 Array2D<bool> collisionEnabled;
103 vector<RobotPlannerSettings> robotSettings;
104 vector<ObjectPlannerSettings> objectSettings;
105 vector<TerrainPlannerSettings> terrainSettings;
PropertyMap properties
other properties
Definition: PlannerSettings.h:31
Definition: PlannerSettings.h:28
Definition: PlannerSettings.h:19
Real collisionEpsilon
threshold for edge feasibility checks
Definition: PlannerSettings.h:22
Real collisionEpsilon
threshold for edge feasibility checks
Definition: PlannerSettings.h:11
bool touchable
true if its allowed to be touched
Definition: PlannerSettings.h:30
A structure containing settings that should be used for collision detection, contact solving...
Definition: PlannerSettings.h:41
Definition: PlannerSettings.h:9
bool touchable
true if its allowed to be touched
Definition: PlannerSettings.h:21
The main world class containing multiple robots, objects, and static geometries (terrains). Lights and other viewport information may also be stored here.
Definition: World.h:20
Vector distanceWeights
for non-euclidean distance metric
Definition: PlannerSettings.h:12
Real contactEpsilon
convergence threshold for contact solving
Definition: PlannerSettings.h:14
AABB3D worldBounds
for translation
Definition: PlannerSettings.h:24
PropertyMap properties
other properties
Definition: PlannerSettings.h:25
AABB3D worldBounds
base position sampling range for free-floating robots
Definition: PlannerSettings.h:13
Real rotationWeight
for distance metric
Definition: PlannerSettings.h:23
PropertyMap properties
other properties
Definition: PlannerSettings.h:16
int contactIKMaxIters
max iters for contact solving
Definition: PlannerSettings.h:15