Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feat/support conversions #958

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,15 @@ class AllowedCollisionMatrix
lookup_table_.insert(acm.getAllAllowedCollisions().begin(), acm.getAllAllowedCollisions().end());
}

/**
* @brief Reserve space for the internal data storage
* @param size The size to reserve
*/
void reserveAllowedCollisionMatrix(std::size_t size)
{
lookup_table_.reserve(size);
}

friend std::ostream& operator<<(std::ostream& os, const AllowedCollisionMatrix& acm)
{
for (const auto& pair : acm.getAllAllowedCollisions())
Expand Down
6 changes: 6 additions & 0 deletions tesseract_scene_graph/include/tesseract_scene_graph/graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -347,6 +347,12 @@ class SceneGraph
*/
JointLimits::ConstPtr getJointLimits(const std::string& name);

/**
* @brief Set the allowed collision matrix
* @param acm The allowed collision matrix to assign
*/
void setAllowedCollisionMatrix(tesseract_common::AllowedCollisionMatrix::Ptr acm);

/**
* @brief Disable collision between two collision objects
* @param link_name1 Collision object name
Expand Down
5 changes: 5 additions & 0 deletions tesseract_scene_graph/src/graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -624,6 +624,11 @@ JointLimits::ConstPtr SceneGraph::getJointLimits(const std::string& name)
return found->second.first->limits;
}

void SceneGraph::setAllowedCollisionMatrix(tesseract_common::AllowedCollisionMatrix::Ptr acm)
{
acm_ = std::move(acm);
}

void SceneGraph::addAllowedCollision(const std::string& link_name1,
const std::string& link_name2,
const std::string& reason)
Expand Down
Loading