Skip to content

Commit

Permalink
fixup! Adapt to API changes in srdfdom
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Nov 8, 2021
1 parent e57d7d5 commit 60b8d19
Show file tree
Hide file tree
Showing 5 changed files with 5 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ class CollisionDetectorPandaTest : public testing::Test
acm_->setDefaultEntry(name, collision_detection::AllowedCollision::NEVER);
// allow collisions for pairs that have been disabled
for (auto const& collision : robot_model_->getSRDF()->getCollisionPairs())
acm_->setEntry(collision.link1_, collision.link2_, collision.disabled);
acm_->setEntry(collision.link1_, collision.link2_, collision.disabled_);

cenv_ = value_->allocateEnv(robot_model_);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class BulletCollisionDetectionTester : public testing::Test
acm_->setDefaultEntry(name, collision_detection::AllowedCollision::NEVER);
// allow collisions for pairs that have been disabled
for (auto const& collision : robot_model_->getSRDF()->getCollisionPairs())
acm_->setEntry(collision.link1_, collision.link2_, collision.disabled);
acm_->setEntry(collision.link1_, collision.link2_, collision.disabled_);

cenv_ = std::make_shared<collision_detection::CollisionEnvBullet>(robot_model_);

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ void PlanningScene::initialize()
acm_->setDefaultEntry(name, collision_detection::AllowedCollision::ALWAYS);
// allow collisions for pairs that have been disabled
for (auto const& collision : getRobotModel()->getSRDF()->getCollisionPairs())
acm_->setEntry(collision.link1_, collision.link2_, collision.disabled);
acm_->setEntry(collision.link1_, collision.link2_, collision.disabled_);

setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
}
Expand Down
2 changes: 1 addition & 1 deletion moveit_setup_assistant/src/tools/moveit_config_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ void MoveItConfigData::loadAllowedCollisionMatrix()
// Update the allowed collision matrix, in case there has been a change
for (const auto& collision : srdf_->collision_pairs_)
{
allowed_collision_matrix_.setEntry(collision.link1_, collision.link2_, collision.disabled);
allowed_collision_matrix_.setEntry(collision.link1_, collision.link2_, collision.disabled_);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -691,6 +691,7 @@ void DefaultCollisionsWidget::linkPairsToSRDF()
dc.link1_ = pair_it->first.first;
dc.link2_ = pair_it->first.second;
dc.reason_ = moveit_setup_assistant::disabledReasonToString(pair_it->second.reason);
dc.disabled_ = pair_it->second.disable_check;
config_data_->srdf_->collision_pairs_.push_back(dc);
}
}
Expand Down

0 comments on commit 60b8d19

Please sign in to comment.