From e8ef40a941c75dda6243ed846ea1ed291550953a Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Tue, 24 Oct 2023 16:09:03 +0200 Subject: [PATCH] change default planner --- .../eci_demo/src/MoveitBasicPlannersExample.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/kuka_driver_examples/eci_demo/src/MoveitBasicPlannersExample.cpp b/kuka_driver_examples/eci_demo/src/MoveitBasicPlannersExample.cpp index a1896cb3..0b339ae4 100755 --- a/kuka_driver_examples/eci_demo/src/MoveitBasicPlannersExample.cpp +++ b/kuka_driver_examples/eci_demo/src/MoveitBasicPlannersExample.cpp @@ -99,7 +99,7 @@ int main(int argc, char * argv[]) example_node->addBreakPoint(); // Plan with collision avoidance - planned_trajectory = example_node->planToPoint(standing_pose, "ompl", "chomp"); + planned_trajectory = example_node->planToPoint(standing_pose, "ompl", "RRTConnectkConfigDefault"); if (planned_trajectory != nullptr) { example_node->drawTrajectory(*planned_trajectory); example_node->addBreakPoint(); @@ -114,7 +114,7 @@ int main(int argc, char * argv[]) q.w = 1; example_node->setOrientationConstraint(q); // Plan with collision avoidance - planned_trajectory = example_node->planToPoint(cart_goal, "ompl", "chomp"); + planned_trajectory = example_node->planToPoint(cart_goal, "ompl", "RRTConnectkConfigDefault"); if (planned_trajectory != nullptr) { example_node->drawTrajectory(*planned_trajectory); example_node->addBreakPoint();