diff --git a/tesseract_msgs/CMakeLists.txt b/tesseract_msgs/CMakeLists.txt index 03d1f270..9e44e91c 100644 --- a/tesseract_msgs/CMakeLists.txt +++ b/tesseract_msgs/CMakeLists.txt @@ -65,7 +65,6 @@ set(message_files "msg/Mesh.msg" "msg/ObjectColor.msg" "msg/OctreeSubType.msg" - "msg/PlannerProfileRemapping.msg" "msg/PlanningRequest.msg" "msg/PlanningResponse.msg" "msg/PluginInfo.msg" diff --git a/tesseract_msgs/msg/PlanningRequest.msg b/tesseract_msgs/msg/PlanningRequest.msg index c1dcb2f3..29ac652d 100644 --- a/tesseract_msgs/msg/PlanningRequest.msg +++ b/tesseract_msgs/msg/PlanningRequest.msg @@ -7,6 +7,3 @@ string input # This should be an xml string of tesseract_common::AnyPoly bool dotgraph # Enable if DOT Graph should be generated and returned bool debug # Enable debug content bool save_io # Enable saving of input and output for task infos - -tesseract_msgs/PlannerProfileRemapping move_profile_remapping -tesseract_msgs/PlannerProfileRemapping composite_profile_remapping diff --git a/tesseract_planning_server/src/tesseract_planning_server.cpp b/tesseract_planning_server/src/tesseract_planning_server.cpp index 8ffee13a..2b73f3cb 100644 --- a/tesseract_planning_server/src/tesseract_planning_server.cpp +++ b/tesseract_planning_server/src/tesseract_planning_server.cpp @@ -251,13 +251,6 @@ void TesseractPlanningServer::onMotionPlanningCallback( data->setData("planning_input", std::move(planning_input)); data->setData("environment", std::shared_ptr(std::move(env))); data->setData("profiles", profiles_); - auto move_profile_remapping = tesseract_rosutils::fromMsg(goal->request.move_profile_remapping); - if (!move_profile_remapping.empty()) - data->setData("move_profile_remapping", move_profile_remapping); - - auto composite_profile_remapping = tesseract_rosutils::fromMsg(goal->request.composite_profile_remapping); - if (!composite_profile_remapping.empty()) - data->setData("composite_profile_remapping", composite_profile_remapping); // Solve tesseract_common::Stopwatch stopwatch; @@ -301,69 +294,58 @@ void TesseractPlanningServer::onMotionPlanningCallback( void TesseractPlanningServer::loadDefaultPlannerProfiles() { // Add TrajOpt Default Profiles - profiles_->addProfile( - TRAJOPT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); - profiles_->addProfile( - TRAJOPT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); - profiles_->addProfile( - TRAJOPT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(TRAJOPT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); + profiles_->addProfile(TRAJOPT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); + profiles_->addProfile(TRAJOPT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); // Add TrajOpt IFOPT Default Profiles #ifdef TESSERACT_TASK_COMPOSER_HAS_TRAJOPT_IFOPT - profiles_->addProfile( - TRAJOPT_IFOPT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); - profiles_->addProfile( - TRAJOPT_IFOPT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); - profiles_->addProfile( - TRAJOPT_IFOPT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); + profiles_->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); + profiles_->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); #endif // Add Descartes Default Profiles - profiles_->addProfile>( - DESCARTES_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared>()); + profiles_->addProfile(DESCARTES_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared>()); // Add OMPL Default Profiles - profiles_->addProfile( - OMPL_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(OMPL_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); // Add Simple Default Profiles - profiles_->addProfile( - SIMPLE_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(SIMPLE_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); // MinLengthTask calls the SimpleMotionPlanner to generate a seed path with waypoints interpolated in joint space - profiles_->addProfile(MLT_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(MLT_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); // Post hoc collision checking - profiles_->addProfile( - DCC_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(DCC_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); // Time parameterization - profiles_->addProfile( - ISP_DEFAULT_NAMESPACE, - tesseract_planning::DEFAULT_PROFILE_KEY, - std::make_shared()); + profiles_->addProfile(ISP_DEFAULT_NAMESPACE, + tesseract_planning::DEFAULT_PROFILE_KEY, + std::make_shared()); } Eigen::Isometry3d TesseractPlanningServer::tfFindTCPOffset(const tesseract_common::ManipulatorInfo& manip_info) diff --git a/tesseract_rosutils/CMakeLists.txt b/tesseract_rosutils/CMakeLists.txt index 3ded15b9..5a763f11 100644 --- a/tesseract_rosutils/CMakeLists.txt +++ b/tesseract_rosutils/CMakeLists.txt @@ -9,6 +9,7 @@ project(${pkg_extracted_name} VERSION ${pkg_extracted_version} LANGUAGES C CXX) find_package(ament_index_cpp REQUIRED) find_package(rclcpp REQUIRED) find_package(tf2_eigen REQUIRED) +find_package(octomap_msgs REQUIRED) find_package(trajectory_msgs REQUIRED) find_package(visualization_msgs REQUIRED) # tesseract @@ -20,7 +21,6 @@ find_package(tesseract_msgs REQUIRED) # Load variable for clang tidy args, compiler options and cxx version tesseract_variables() - add_library(${PROJECT_NAME} SHARED src/plotting.cpp src/conversions.cpp src/utils.cpp) target_link_libraries(${PROJECT_NAME} PUBLIC @@ -34,6 +34,7 @@ target_link_libraries(${PROJECT_NAME} PRIVATE ament_index_cpp::ament_index_cpp ${tf2_eigen_TARGETS} + ${octomap_msgs_TARGETS} ) target_compile_options(${PROJECT_NAME} PRIVATE ${TESSERACT_COMPILE_OPTIONS}) target_clang_tidy(${PROJECT_NAME} ARGUMENTS ${TESSERACT_CLANG_TIDY_ARGS} ENABLE ${TESSERACT_ENABLE_CLANG_TIDY}) @@ -68,4 +69,4 @@ ament_package() if(TESSERACT_ENABLE_TESTING) enable_testing() add_subdirectory(test) -endif() \ No newline at end of file +endif() diff --git a/tesseract_rosutils/include/tesseract_rosutils/utils.h b/tesseract_rosutils/include/tesseract_rosutils/utils.h index 146530f4..9274b668 100644 --- a/tesseract_rosutils/include/tesseract_rosutils/utils.h +++ b/tesseract_rosutils/include/tesseract_rosutils/utils.h @@ -58,7 +58,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include #include #include -#include #include #include #include @@ -189,11 +188,6 @@ bool fromMsg(std::shared_ptr& joint_safety, bool toMsg(tesseract_msgs::msg::Joint& joint_msg, const tesseract_scene_graph::Joint& joint); -tesseract_planning::PlannerProfileRemapping -fromMsg(const tesseract_msgs::msg::PlannerProfileRemapping& profile_remapping_msg); -tesseract_msgs::msg::PlannerProfileRemapping -toMsg(const tesseract_planning::PlannerProfileRemapping& profile_remapping); - tesseract_common::PairsCollisionMarginData fromMsg(const std::vector& contact_margin_pairs_msg); std::vector diff --git a/tesseract_rosutils/package.xml b/tesseract_rosutils/package.xml index 85ef5467..a702489b 100644 --- a/tesseract_rosutils/package.xml +++ b/tesseract_rosutils/package.xml @@ -15,6 +15,7 @@ tf2_eigen trajectory_msgs visualization_msgs + octomap_msgs tesseract_task_composer diff --git a/tesseract_rosutils/src/utils.cpp b/tesseract_rosutils/src/utils.cpp index ac14a60e..1e8cef88 100644 --- a/tesseract_rosutils/src/utils.cpp +++ b/tesseract_rosutils/src/utils.cpp @@ -1040,41 +1040,6 @@ tesseract_scene_graph::Joint fromMsg(const tesseract_msgs::msg::Joint& joint_msg return joint; } -tesseract_planning::PlannerProfileRemapping -fromMsg(const tesseract_msgs::msg::PlannerProfileRemapping& profile_remapping_msg) -{ - tesseract_planning::PlannerProfileRemapping profile_remapping; - for (std::size_t i = 0; i < profile_remapping_msg.planner.size(); ++i) - { - std::unordered_map mapping; - for (const auto& pair : profile_remapping_msg.mapping[i].pairs) - mapping.emplace(pair.first, pair.second); - - profile_remapping[profile_remapping_msg.planner[i]] = mapping; - } - - return profile_remapping; -} - -tesseract_msgs::msg::PlannerProfileRemapping toMsg(const tesseract_planning::PlannerProfileRemapping& profile_remapping) -{ - tesseract_msgs::msg::PlannerProfileRemapping profile_remapping_msg; - for (const auto& planner_remapping : profile_remapping) - { - profile_remapping_msg.planner.push_back(planner_remapping.first); - tesseract_msgs::msg::ProfileMap mapping; - for (const auto& planner_pair : planner_remapping.second) - { - tesseract_msgs::msg::StringPair p; - p.first = planner_pair.first; - p.second = planner_pair.second; - mapping.pairs.push_back(p); - } - profile_remapping_msg.mapping.push_back(mapping); - } - return profile_remapping_msg; -} - tesseract_common::PairsCollisionMarginData fromMsg(const std::vector& contact_margin_pairs_msg) {