From 6768610598b75fd361d0b5da0e1a6a16f0764792 Mon Sep 17 00:00:00 2001 From: Aron Svastits Date: Wed, 25 Oct 2023 13:57:50 +0200 Subject: [PATCH] remove coll objects --- .../src/MoveitCollisionAvoidanceExample.cpp | 13 ------------- .../src/MoveitConstrainedPlanningExample.cpp | 13 ------------- 2 files changed, 26 deletions(-) diff --git a/kuka_driver_examples/eci_demo/src/MoveitCollisionAvoidanceExample.cpp b/kuka_driver_examples/eci_demo/src/MoveitCollisionAvoidanceExample.cpp index d26e37a1..1ed1c6ff 100755 --- a/kuka_driver_examples/eci_demo/src/MoveitCollisionAvoidanceExample.cpp +++ b/kuka_driver_examples/eci_demo/src/MoveitCollisionAvoidanceExample.cpp @@ -33,22 +33,9 @@ int main(int argc, char * argv[]) .detach(); example_node->initialize(); - example_node->addBreakPoint(); // Add robot platform example_node->addRobotPlatform(); - - // Add collision object - kuka_driver_interfaces::msg::CollisionBox box_msg; - box_msg.position.x = 0.25; - box_msg.position.y = -0.075; - box_msg.position.z = 0.675; - - box_msg.size.x = 0.1; - box_msg.size.y = 0.4; - box_msg.size.z = 0.1; - - example_node->addCollisionBox(std::make_shared(box_msg)); example_node->addBreakPoint(); auto standing_pose = Eigen::Isometry3d( diff --git a/kuka_driver_examples/eci_demo/src/MoveitConstrainedPlanningExample.cpp b/kuka_driver_examples/eci_demo/src/MoveitConstrainedPlanningExample.cpp index 81408a46..d89e292c 100755 --- a/kuka_driver_examples/eci_demo/src/MoveitConstrainedPlanningExample.cpp +++ b/kuka_driver_examples/eci_demo/src/MoveitConstrainedPlanningExample.cpp @@ -33,22 +33,9 @@ int main(int argc, char * argv[]) .detach(); example_node->initialize(); - example_node->addBreakPoint(); // Add robot platform example_node->addRobotPlatform(); - - // Add collision object - kuka_driver_interfaces::msg::CollisionBox box_msg; - box_msg.position.x = 0.25; - box_msg.position.y = -0.075; - box_msg.position.z = 0.675; - - box_msg.size.x = 0.1; - box_msg.size.y = 0.4; - box_msg.size.z = 0.1; - - example_node->addCollisionBox(std::make_shared(box_msg)); example_node->addBreakPoint(); auto cart_goal = Eigen::Isometry3d(