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

Update due to changes with profiles and overrides #134

Merged
merged 2 commits into from
Dec 9, 2024
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
7 changes: 4 additions & 3 deletions .github/workflows/clang_format.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,18 @@ on:

jobs:
clang_format:
runs-on: ubuntu-20.04
runs-on: ubuntu-22.04
steps:
- uses: actions/checkout@v4

- name: Run clang format
run: |
sudo apt update
sudo apt install -y git clang-format
sudo apt install -y git clang-format-12
if [ $? -ge 1 ]; then return 1; fi
./.run-clang-format
if [ $? -ge 1 ]; then return 1; fi
git diff
output=$(git diff)
echo $output
if [ -n "$output" ]; then exit 1; else exit 0; fi

2 changes: 1 addition & 1 deletion .run-clang-format
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
#!/bin/bash
find . -type d \( -name bullet3_ros -o -name fcl_ros -o -name libccd_ros -o -name gtest_ros -o -name tesseract_ext \) -prune -o -type f -regex '.*\.\(cpp\|hpp\|cc\|cxx\|h\|hxx\)' -exec clang-format-10 -style=file -i {} \;
find . -type d \( -name bullet3_ros -o -name fcl_ros -o -name libccd_ros -o -name gtest_ros -o -name tesseract_ext \) -prune -o -type f -regex '.*\.\(cpp\|hpp\|cc\|cxx\|h\|hxx\)' -exec clang-format-12 -style=file -i {} \;
1 change: 0 additions & 1 deletion tesseract_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
2 changes: 0 additions & 2 deletions tesseract_msgs/msg/PlannerProfileRemapping.msg

This file was deleted.

3 changes: 0 additions & 3 deletions tesseract_msgs/msg/PlanningRequest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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
90 changes: 36 additions & 54 deletions tesseract_planning_server/src/tesseract_planning_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,13 +251,6 @@ void TesseractPlanningServer::onMotionPlanningCallback(
data->setData("planning_input", std::move(planning_input));
data->setData("environment", std::shared_ptr<const tesseract_environment::Environment>(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;
Expand Down Expand Up @@ -301,69 +294,58 @@ void TesseractPlanningServer::onMotionPlanningCallback(
void TesseractPlanningServer::loadDefaultPlannerProfiles()
{
// Add TrajOpt Default Profiles
profiles_->addProfile<tesseract_planning::TrajOptPlanProfile>(
TRAJOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptDefaultPlanProfile>());
profiles_->addProfile<tesseract_planning::TrajOptCompositeProfile>(
TRAJOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptDefaultCompositeProfile>());
profiles_->addProfile<tesseract_planning::TrajOptSolverProfile>(
TRAJOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptDefaultSolverProfile>());
profiles_->addProfile(TRAJOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptDefaultPlanProfile>());
profiles_->addProfile(TRAJOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptDefaultCompositeProfile>());
profiles_->addProfile(TRAJOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptDefaultSolverProfile>());

// Add TrajOpt IFOPT Default Profiles
#ifdef TESSERACT_TASK_COMPOSER_HAS_TRAJOPT_IFOPT
profiles_->addProfile<tesseract_planning::TrajOptIfoptPlanProfile>(
TRAJOPT_IFOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptIfoptDefaultPlanProfile>());
profiles_->addProfile<tesseract_planning::TrajOptIfoptCompositeProfile>(
TRAJOPT_IFOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptIfoptDefaultCompositeProfile>());
profiles_->addProfile<tesseract_planning::TrajOptIfoptSolverProfile>(
TRAJOPT_IFOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptIfoptDefaultSolverProfile>());
profiles_->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptIfoptDefaultPlanProfile>());
profiles_->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptIfoptDefaultCompositeProfile>());
profiles_->addProfile(TRAJOPT_IFOPT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::TrajOptIfoptDefaultSolverProfile>());
#endif

// Add Descartes Default Profiles
profiles_->addProfile<tesseract_planning::DescartesPlanProfile<double>>(
DESCARTES_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::DescartesDefaultPlanProfile<double>>());
profiles_->addProfile(DESCARTES_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::DescartesDefaultPlanProfile<double>>());

// Add OMPL Default Profiles
profiles_->addProfile<tesseract_planning::OMPLPlanProfile>(
OMPL_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::OMPLDefaultPlanProfile>());
profiles_->addProfile(OMPL_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::OMPLDefaultPlanProfile>());

// Add Simple Default Profiles
profiles_->addProfile<tesseract_planning::SimplePlannerPlanProfile>(
SIMPLE_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::SimplePlannerLVSNoIKPlanProfile>());
profiles_->addProfile(SIMPLE_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::SimplePlannerLVSNoIKPlanProfile>());

// MinLengthTask calls the SimpleMotionPlanner to generate a seed path with waypoints interpolated in joint space
profiles_->addProfile<tesseract_planning::MinLengthProfile>(MLT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::MinLengthProfile>());
profiles_->addProfile(MLT_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::MinLengthProfile>());

// Post hoc collision checking
profiles_->addProfile<tesseract_planning::ContactCheckProfile>(
DCC_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::ContactCheckProfile>());
profiles_->addProfile(DCC_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::ContactCheckProfile>());

// Time parameterization
profiles_->addProfile<tesseract_planning::IterativeSplineParameterizationProfile>(
ISP_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::IterativeSplineParameterizationProfile>());
profiles_->addProfile(ISP_DEFAULT_NAMESPACE,
tesseract_planning::DEFAULT_PROFILE_KEY,
std::make_shared<tesseract_planning::IterativeSplineParameterizationProfile>());
}

Eigen::Isometry3d TesseractPlanningServer::tfFindTCPOffset(const tesseract_common::ManipulatorInfo& manip_info)
Expand Down
5 changes: 3 additions & 2 deletions tesseract_rosutils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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})
Expand Down Expand Up @@ -68,4 +69,4 @@ ament_package()
if(TESSERACT_ENABLE_TESTING)
enable_testing()
add_subdirectory(test)
endif()
endif()
6 changes: 0 additions & 6 deletions tesseract_rosutils/include/tesseract_rosutils/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <tesseract_msgs/msg/string_double_pair.hpp>
#include <tesseract_msgs/msg/transform_map.hpp>
#include <tesseract_msgs/msg/visual_geometry.hpp>
#include <tesseract_msgs/msg/planner_profile_remapping.hpp>
#include <tesseract_msgs/msg/task_composer_key.hpp>
#include <tesseract_msgs/msg/task_composer_node_info.hpp>
#include <geometry_msgs/msg/pose.hpp>
Expand Down Expand Up @@ -189,11 +188,6 @@ bool fromMsg(std::shared_ptr<tesseract_scene_graph::JointSafety>& 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<tesseract_msgs::msg::ContactMarginPair>& contact_margin_pairs_msg);
std::vector<tesseract_msgs::msg::ContactMarginPair>
Expand Down
1 change: 1 addition & 0 deletions tesseract_rosutils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<depend>tf2_eigen</depend>
<depend>trajectory_msgs</depend>
<depend>visualization_msgs</depend>
<depend>octomap_msgs</depend>

<depend>tesseract_task_composer</depend>

Expand Down
35 changes: 0 additions & 35 deletions tesseract_rosutils/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, std::string> 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<tesseract_msgs::msg::ContactMarginPair>& contact_margin_pairs_msg)
{
Expand Down
Loading