From 70dc113a66f361da625f8aa78de0bb40effb793b Mon Sep 17 00:00:00 2001 From: Levi Armstrong Date: Sat, 4 Jan 2025 23:12:55 -0600 Subject: [PATCH] Update due to changes in tesseract and tesseract_planning repos --- tesseract_monitoring/src/contact_monitor.cpp | 13 +++++++------ .../src/tesseract_planning_server_node.cpp | 4 +++- 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/tesseract_monitoring/src/contact_monitor.cpp b/tesseract_monitoring/src/contact_monitor.cpp index 171e73a3..931c3c03 100644 --- a/tesseract_monitoring/src/contact_monitor.cpp +++ b/tesseract_monitoring/src/contact_monitor.cpp @@ -44,6 +44,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include +#include #include #include #include @@ -140,7 +141,7 @@ struct ContactMonitor::Implementation // Create a new manager std::vector active; tesseract_collision::CollisionMarginData contact_margin_data; - tesseract_collision::IsContactAllowedFn fn; + tesseract_common::ContactAllowedValidator::ConstPtr fn; { auto lock_read = monitor->environment().lockRead(); @@ -148,13 +149,13 @@ struct ContactMonitor::Implementation env_revision = monitor->environment().getRevision(); active = manager->getActiveCollisionObjects(); contact_margin_data = manager->getCollisionMarginData(); - fn = manager->getIsContactAllowedFn(); + fn = manager->getContactAllowedValidator(); manager = monitor->environment().getDiscreteContactManager(); } manager->setActiveCollisionObjects(active); manager->setCollisionMarginData(contact_margin_data); - manager->setIsContactAllowedFn(fn); + manager->setContactAllowedValidator(fn); for (const auto& disabled_link_name : disabled_link_names) manager->disableCollisionObject(disabled_link_name); } @@ -237,19 +238,19 @@ struct ContactMonitor::Implementation // Create a new manager std::vector active; tesseract_collision::CollisionMarginData contact_margin_data; - tesseract_collision::IsContactAllowedFn fn; + tesseract_common::ContactAllowedValidator::ConstPtr fn; { auto lock_read = monitor->environment().lockRead(); active = manager->getActiveCollisionObjects(); contact_margin_data = manager->getCollisionMarginData(); - fn = manager->getIsContactAllowedFn(); + fn = manager->getContactAllowedValidator(); manager = monitor->environment().getDiscreteContactManager(); } manager->setActiveCollisionObjects(active); manager->setCollisionMarginData(contact_margin_data); - manager->setIsContactAllowedFn(fn); + manager->setContactAllowedValidator(fn); for (const auto& disabled_link_name : disabled_link_names) manager->disableCollisionObject(disabled_link_name); diff --git a/tesseract_planning_server/src/tesseract_planning_server_node.cpp b/tesseract_planning_server/src/tesseract_planning_server_node.cpp index 32254a27..18fe6e07 100644 --- a/tesseract_planning_server/src/tesseract_planning_server_node.cpp +++ b/tesseract_planning_server/src/tesseract_planning_server_node.cpp @@ -29,6 +29,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include TESSERACT_COMMON_IGNORE_WARNINGS_POP +#include #include #include #include @@ -83,8 +84,9 @@ int main(int argc, char** argv) if (!task_composer_config.empty()) { + tesseract_common::GeneralResourceLocator locator; tesseract_common::fs::path config(task_composer_config); - planning_server->getTaskComposerServer().loadConfig(config); + planning_server->getTaskComposerServer().loadConfig(config, locator); } ros::Timer update_cache = nh.createTimer(ros::Duration(cache_refresh_rate), updateCacheCallback);