Skip to content

Commit 57833b8

Browse files
committed
Address review
1 parent 382f6dd commit 57833b8

File tree

5 files changed

+17
-18
lines changed

5 files changed

+17
-18
lines changed

moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -151,10 +151,10 @@ struct CollisionRequest
151151
std::string group_name = "";
152152

153153
/** \brief If true, use padded collision environment */
154-
bool use_padded_collision_environment = true;
154+
bool pad_environment_collisions = true;
155155

156156
/** \brief If true, do self collision check with padded robot links */
157-
bool use_padded_self_collision = false;
157+
bool pad_self_collisions = false;
158158

159159
/** \brief If true, compute proximity distance */
160160
bool distance = false;

moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -368,7 +368,7 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro
368368
const collision_detection::AllowedCollisionMatrix& acm) const;
369369

370370
/** \brief Check whether a specified state (\e robot_state) is in collision, with respect to a given
371-
allowed collision matrix (\e acm). */
371+
allowed collision matrix (\e acm). If validate_transforms is set true, the given robot state is checked for dirty transforms. */
372372
void checkCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res,
373373
const moveit::core::RobotState& robot_state,
374374
const collision_detection::AllowedCollisionMatrix& acm, bool validate_transforms = true) const;

moveit_core/planning_scene/src/planning_scene.cpp

Lines changed: 12 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -440,8 +440,8 @@ void PlanningScene::checkCollision(const collision_detection::CollisionRequest&
440440
"transforms before checking collision.");
441441
}
442442
// check collision with the world using the padded version
443-
req.use_padded_collision_environment ? getCollisionEnv()->checkRobotCollision(req, res, robot_state, acm) :
444-
getCollisionEnvUnpadded()->checkRobotCollision(req, res, robot_state, acm);
443+
req.pad_environment_collisions ? getCollisionEnv()->checkRobotCollision(req, res, robot_state, acm) :
444+
getCollisionEnvUnpadded()->checkRobotCollision(req, res, robot_state, acm);
445445

446446
// Return early if a collision was found or the maximum number of allowed contacts is exceeded
447447
if (res.collision || (req.contacts && res.contacts.size() >= req.max_contacts))
@@ -450,23 +450,23 @@ void PlanningScene::checkCollision(const collision_detection::CollisionRequest&
450450
}
451451

452452
// do self-collision checking with the unpadded version of the robot
453-
req.use_padded_self_collision ? getCollisionEnv()->checkSelfCollision(req, res, robot_state, acm) :
454-
getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
453+
req.pad_self_collisions ? getCollisionEnv()->checkSelfCollision(req, res, robot_state, acm) :
454+
getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
455455
}
456456

457457
void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionRequest& req,
458458
collision_detection::CollisionResult& res)
459459
{
460460
collision_detection::CollisionRequest new_req = req;
461-
new_req.use_padded_collision_environment = false;
461+
new_req.pad_environment_collisions = false;
462462
checkCollision(req, res, getCurrentStateNonConst(), getAllowedCollisionMatrix());
463463
}
464464

465465
void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionRequest& req,
466466
collision_detection::CollisionResult& res) const
467467
{
468468
collision_detection::CollisionRequest new_req = req;
469-
new_req.use_padded_collision_environment = false;
469+
new_req.pad_environment_collisions = false;
470470
checkCollision(new_req, res, getCurrentState(), getAllowedCollisionMatrix());
471471
}
472472

@@ -475,7 +475,7 @@ void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionR
475475
const moveit::core::RobotState& robot_state) const
476476
{
477477
collision_detection::CollisionRequest new_req = req;
478-
new_req.use_padded_collision_environment = false;
478+
new_req.pad_environment_collisions = false;
479479
checkCollision(new_req, res, robot_state, getAllowedCollisionMatrix());
480480
}
481481

@@ -484,7 +484,7 @@ void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionR
484484
moveit::core::RobotState& robot_state) const
485485
{
486486
collision_detection::CollisionRequest new_req = req;
487-
new_req.use_padded_collision_environment = false;
487+
new_req.pad_environment_collisions = false;
488488
checkCollision(new_req, res, static_cast<const moveit::core::RobotState&>(robot_state), getAllowedCollisionMatrix());
489489
}
490490

@@ -495,7 +495,7 @@ void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionR
495495
{
496496
robot_state.updateCollisionBodyTransforms();
497497
collision_detection::CollisionRequest new_req = req;
498-
new_req.use_padded_collision_environment = false;
498+
new_req.pad_environment_collisions = false;
499499
checkCollision(new_req, res, static_cast<const moveit::core::RobotState&>(robot_state), acm);
500500
}
501501

@@ -505,7 +505,7 @@ void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionR
505505
const collision_detection::AllowedCollisionMatrix& acm) const
506506
{
507507
collision_detection::CollisionRequest new_req = req;
508-
new_req.use_padded_collision_environment = false;
508+
new_req.pad_environment_collisions = false;
509509
checkCollision(req, res, robot_state, acm);
510510
}
511511

@@ -515,7 +515,6 @@ void PlanningScene::checkSelfCollision(const collision_detection::CollisionReque
515515
checkSelfCollision(req, res, getCurrentStateNonConst());
516516
}
517517

518-
/** \brief Check whether the current state is in self collision */
519518
void PlanningScene::checkSelfCollision(const collision_detection::CollisionRequest& req,
520519
collision_detection::CollisionResult& res) const
521520
{
@@ -556,8 +555,8 @@ void PlanningScene::checkSelfCollision(const collision_detection::CollisionReque
556555
const moveit::core::RobotState& robot_state,
557556
const collision_detection::AllowedCollisionMatrix& acm) const
558557
{
559-
req.use_padded_self_collision ? getCollisionEnv()->checkSelfCollision(req, res, robot_state, acm) :
560-
getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
558+
req.pad_self_collisions ? getCollisionEnv()->checkSelfCollision(req, res, robot_state, acm) :
559+
getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
561560
}
562561

563562
void PlanningScene::getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts)

moveit_ros/benchmarks/src/BenchmarkExecutor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1010,7 +1010,7 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics,
10101010

10111011
// compute correctness and clearance
10121012
collision_detection::CollisionRequest req;
1013-
req.use_padded_collision_environment = false;
1013+
req.pad_environment_collisions = false;
10141014
for (std::size_t k = 0; k < p.getWayPointCount(); ++k)
10151015
{
10161016
collision_detection::CollisionResult res;

moveit_ros/planning/plan_execution/src/plan_execution.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -282,7 +282,7 @@ bool plan_execution::PlanExecution::isRemainingPathValid(const ExecutableMotionP
282282
std::size_t wpc = t.getWayPointCount();
283283
collision_detection::CollisionRequest req;
284284
req.group_name = t.getGroupName();
285-
req.use_padded_collision_environment = false;
285+
req.pad_environment_collisions = false;
286286
for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
287287
{
288288
collision_detection::CollisionResult res;

0 commit comments

Comments
 (0)