#include <collision_proximity_space.h>
Definition at line 58 of file collision_proximity_space.h.
Definition at line 63 of file collision_proximity_space.h.
Definition at line 68 of file collision_proximity_space.h.
CollisionProximitySpace::CollisionProximitySpace | ( | const std::string & | robot_description_name, |
bool | register_with_environment_server = true , |
||
bool | use_signed_environment_field = false , |
||
bool | use_signed_self_field = false |
||
) |
Definition at line 64 of file collision_proximity_space.cpp.
Definition at line 124 of file collision_proximity_space.cpp.
void CollisionProximitySpace::deleteAllAttachedObjectDecompositions | ( | ) | [private] |
Definition at line 148 of file collision_proximity_space.cpp.
void CollisionProximitySpace::deleteAllStaticObjectDecompositions | ( | ) | [private] |
Definition at line 138 of file collision_proximity_space.cpp.
planning_environment::CollisionModelsInterface* collision_proximity::CollisionProximitySpace::getCollisionModelsInterface | ( | ) | const [inline] |
Definition at line 169 of file collision_proximity_space.h.
std::vector<std::string> collision_proximity::CollisionProximitySpace::getCurrentAttachedBodyNames | ( | ) | const [inline] |
Definition at line 184 of file collision_proximity_space.h.
const std::string& collision_proximity::CollisionProximitySpace::getCurrentGroupName | ( | ) | const [inline] |
Definition at line 175 of file collision_proximity_space.h.
std::vector<std::string> collision_proximity::CollisionProximitySpace::getCurrentLinkNames | ( | ) | const [inline] |
Definition at line 179 of file collision_proximity_space.h.
bool CollisionProximitySpace::getEnvironmentCollisions | ( | std::vector< bool > & | collisions, |
bool | stop_at_first = false |
||
) | const |
Definition at line 1094 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getEnvironmentProximityGradients | ( | std::vector< GradientInfo > & | gradients, |
bool | subtract_radii = false |
||
) | const |
Definition at line 1123 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getGroupLinkAndAttachedBodyNames | ( | const std::string & | group_name, |
const planning_models::KinematicState & | state, | ||
std::vector< std::string > & | link_names, | ||
std::vector< unsigned int > & | link_indices, | ||
std::vector< std::string > & | attached_body_names, | ||
std::vector< unsigned int > & | attached_body_link_indices | ||
) | const [private] |
Definition at line 660 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getIntraGroupCollisions | ( | std::vector< bool > & | collisions, |
bool | stop_at_first = false |
||
) | const |
Definition at line 928 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getIntraGroupProximityGradients | ( | std::vector< GradientInfo > & | gradients, |
bool | subtract_radii = false |
||
) | const |
Definition at line 968 of file collision_proximity_space.cpp.
tf::Transform CollisionProximitySpace::getInverseWorldTransform | ( | const planning_models::KinematicState & | state | ) | const |
Definition at line 439 of file collision_proximity_space.cpp.
void CollisionProximitySpace::getProximityGradientMarkers | ( | const std::vector< std::string > & | link_names, |
const std::vector< std::string > & | attached_body_names, | ||
const std::vector< GradientInfo > & | gradients, | ||
const std::string & | ns, | ||
visualization_msgs::MarkerArray & | arr | ||
) | const |
Definition at line 1147 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getSelfCollisions | ( | std::vector< bool > & | collisions, |
bool | stop_at_first = false |
||
) | const |
Definition at line 1033 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getSelfProximityGradients | ( | std::vector< GradientInfo > & | gradients, |
bool | subtract_radii = false |
||
) | const |
Definition at line 1062 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getStateCollisions | ( | bool & | in_collision, |
std::vector< CollisionType > & | collisions | ||
) | const |
Definition at line 802 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::getStateGradients | ( | std::vector< GradientInfo > & | gradients, |
bool | subtract_radii = false |
||
) | const |
Definition at line 826 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::isEnvironmentCollision | ( | void | ) | const |
Definition at line 1088 of file collision_proximity_space.cpp.
Definition at line 922 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::isSelfCollision | ( | void | ) | const |
Definition at line 1027 of file collision_proximity_space.cpp.
Definition at line 795 of file collision_proximity_space.cpp.
CollisionProximitySpace::TrajectorySafety CollisionProximitySpace::isTrajectorySafe | ( | const trajectory_msgs::JointTrajectory & | trajectory, |
const arm_navigation_msgs::Constraints & | goal_constraints, | ||
const arm_navigation_msgs::Constraints & | path_constraints, | ||
const std::string & | groupName | ||
) |
Definition at line 1207 of file collision_proximity_space.cpp.
void CollisionProximitySpace::loadDefaultCollisionOperations | ( | ) | [private] |
Definition at line 161 of file collision_proximity_space.cpp.
void CollisionProximitySpace::loadRobotBodyDecompositions | ( | ) | [private] |
Definition at line 249 of file collision_proximity_space.cpp.
void CollisionProximitySpace::prepareEnvironmentDistanceField | ( | const planning_models::KinematicState & | state | ) | [private] |
Definition at line 505 of file collision_proximity_space.cpp.
void CollisionProximitySpace::prepareSelfDistanceField | ( | const std::vector< std::string > & | link_names, |
const planning_models::KinematicState & | state | ||
) | [private] |
Definition at line 526 of file collision_proximity_space.cpp.
Definition at line 374 of file collision_proximity_space.cpp.
void CollisionProximitySpace::setBodyPosesGivenKinematicState | ( | const planning_models::KinematicState & | state | ) | [private] |
Definition at line 409 of file collision_proximity_space.cpp.
void collision_proximity::CollisionProximitySpace::setBodyPosesToCurrent | ( | ) | [private] |
void collision_proximity::CollisionProximitySpace::setCollisionTolerance | ( | double | tol | ) | [inline] |
Definition at line 189 of file collision_proximity_space.h.
void CollisionProximitySpace::setCurrentGroupState | ( | const planning_models::KinematicState & | state | ) |
Definition at line 384 of file collision_proximity_space.cpp.
void CollisionProximitySpace::setDistanceFieldForGroupQueries | ( | const std::string & | group_name, |
const planning_models::KinematicState & | state | ||
) | [private] |
Definition at line 487 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::setPlanningScene | ( | const arm_navigation_msgs::PlanningScene & | planning_scene | ) |
Definition at line 270 of file collision_proximity_space.cpp.
void CollisionProximitySpace::setPlanningSceneCallback | ( | const arm_navigation_msgs::PlanningScene & | scene | ) |
Definition at line 274 of file collision_proximity_space.cpp.
void CollisionProximitySpace::setupForGroupQueries | ( | const std::string & | group_name, |
const arm_navigation_msgs::RobotState & | rob_state, | ||
std::vector< std::string > & | link_names, | ||
std::vector< std::string > & | attached_body_names | ||
) |
Definition at line 287 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::setupGradientStructures | ( | const std::vector< std::string > & | link_names, |
const std::vector< std::string > & | attached_body_names, | ||
std::vector< GradientInfo > & | gradients | ||
) | const [private] |
Definition at line 749 of file collision_proximity_space.cpp.
void CollisionProximitySpace::syncObjectsWithCollisionSpace | ( | const planning_models::KinematicState & | state | ) | [private] |
Definition at line 449 of file collision_proximity_space.cpp.
bool CollisionProximitySpace::updateSphereLocations | ( | const std::vector< std::string > & | link_names, |
const std::vector< std::string > & | attached_body_names, | ||
std::vector< GradientInfo > & | gradients | ||
) | [private] |
Definition at line 714 of file collision_proximity_space.cpp.
void CollisionProximitySpace::visualizeBoundingCylinders | ( | const std::vector< std::string > & | object_names | ) | const |
Definition at line 1698 of file collision_proximity_space.cpp.
void CollisionProximitySpace::visualizeCollisions | ( | const std::vector< std::string > & | link_names, |
const std::vector< std::string > & | attached_body_names, | ||
const std::vector< CollisionType > | collisions | ||
) | const |
Definition at line 1515 of file collision_proximity_space.cpp.
void CollisionProximitySpace::visualizeDistanceField | ( | distance_field::DistanceField< distance_field::PropDistanceFieldVoxel > * | distance_field | ) | const |
Definition at line 1398 of file collision_proximity_space.cpp.
void CollisionProximitySpace::visualizeDistanceFieldPlane | ( | distance_field::DistanceField< distance_field::PropDistanceFieldVoxel > * | distance_field | ) | const |
Definition at line 1407 of file collision_proximity_space.cpp.
void CollisionProximitySpace::visualizeObjectSpheres | ( | const std::vector< std::string > & | object_names | ) | const |
Definition at line 1648 of file collision_proximity_space.cpp.
void CollisionProximitySpace::visualizeObjectVoxels | ( | const std::vector< std::string > & | object_names | ) | const |
Definition at line 1612 of file collision_proximity_space.cpp.
std::map<std::string, std::map<std::string, bool> > collision_proximity::CollisionProximitySpace::attached_object_collision_links_ [private] |
Definition at line 265 of file collision_proximity_space.h.
std::map<std::string, BodyDecompositionVector*> collision_proximity::CollisionProximitySpace::attached_object_map_ [private] |
Definition at line 261 of file collision_proximity_space.h.
std::map<std::string, BodyDecomposition*> collision_proximity::CollisionProximitySpace::body_decomposition_map_ [private] |
Definition at line 259 of file collision_proximity_space.h.
planning_environment::CollisionModelsInterface* collision_proximity::CollisionProximitySpace::collision_models_interface_ [private] |
Definition at line 249 of file collision_proximity_space.h.
std::vector<std::vector<double> > collision_proximity::CollisionProximitySpace::colors_ [mutable, private] |
Definition at line 244 of file collision_proximity_space.h.
std::vector<BodyDecompositionVector*> collision_proximity::CollisionProximitySpace::current_attached_body_decompositions_ [private] |
Definition at line 275 of file collision_proximity_space.h.
std::vector<unsigned int> collision_proximity::CollisionProximitySpace::current_attached_body_indices_ [private] |
Definition at line 273 of file collision_proximity_space.h.
std::vector<std::string> collision_proximity::CollisionProximitySpace::current_attached_body_names_ [private] |
Definition at line 271 of file collision_proximity_space.h.
std::vector<GradientInfo> collision_proximity::CollisionProximitySpace::current_gradients_ [private] |
Definition at line 280 of file collision_proximity_space.h.
std::string collision_proximity::CollisionProximitySpace::current_group_name_ [private] |
Definition at line 269 of file collision_proximity_space.h.
std::vector<std::vector<bool> > collision_proximity::CollisionProximitySpace::current_intra_group_collision_links_ [private] |
Definition at line 276 of file collision_proximity_space.h.
std::vector<BodyDecomposition*> collision_proximity::CollisionProximitySpace::current_link_body_decompositions_ [private] |
Definition at line 274 of file collision_proximity_space.h.
std::vector<unsigned int> collision_proximity::CollisionProximitySpace::current_link_indices_ [private] |
Definition at line 272 of file collision_proximity_space.h.
std::vector<std::string> collision_proximity::CollisionProximitySpace::current_link_names_ [private] |
Definition at line 270 of file collision_proximity_space.h.
Definition at line 277 of file collision_proximity_space.h.
std::map<std::string, std::map<std::string, bool> > collision_proximity::CollisionProximitySpace::enabled_self_collision_links_ [private] |
Definition at line 263 of file collision_proximity_space.h.
distance_field::DistanceField<distance_field::PropDistanceFieldVoxel>* collision_proximity::CollisionProximitySpace::environment_distance_field_ [private] |
Definition at line 246 of file collision_proximity_space.h.
boost::recursive_mutex collision_proximity::CollisionProximitySpace::group_queries_lock_ [mutable, private] |
Definition at line 257 of file collision_proximity_space.h.
std::map<std::string, std::map<std::string, bool> > collision_proximity::CollisionProximitySpace::intra_group_collision_links_ [private] |
Definition at line 264 of file collision_proximity_space.h.
Definition at line 287 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::max_self_distance_ [private] |
Definition at line 288 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::origin_x_ [private] |
Definition at line 284 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::origin_y_ [private] |
Definition at line 284 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::origin_z_ [private] |
Definition at line 284 of file collision_proximity_space.h.
Definition at line 251 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::resolution_ [private] |
Definition at line 285 of file collision_proximity_space.h.
Definition at line 251 of file collision_proximity_space.h.
distance_field::DistanceField<distance_field::PropDistanceFieldVoxel>* collision_proximity::CollisionProximitySpace::self_distance_field_ [private] |
Definition at line 247 of file collision_proximity_space.h.
std::map<std::string, bool> collision_proximity::CollisionProximitySpace::self_excludes_ [private] |
Definition at line 266 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::size_x_ [private] |
Definition at line 283 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::size_y_ [private] |
Definition at line 283 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::size_z_ [private] |
Definition at line 283 of file collision_proximity_space.h.
std::map<std::string, BodyDecompositionVector*> collision_proximity::CollisionProximitySpace::static_object_map_ [private] |
Definition at line 260 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::tolerance_ [private] |
Definition at line 285 of file collision_proximity_space.h.
double collision_proximity::CollisionProximitySpace::undefined_distance_ [private] |
Definition at line 289 of file collision_proximity_space.h.
ros::Publisher collision_proximity::CollisionProximitySpace::vis_distance_field_marker_publisher_ [private] |
Definition at line 253 of file collision_proximity_space.h.
Definition at line 255 of file collision_proximity_space.h.
Definition at line 254 of file collision_proximity_space.h.