Skip to content

Commit

Permalink
Restructure tesseract_task_composer like other plugin based packages
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Jun 12, 2023
1 parent 93fe0c7 commit dd5f9ae
Show file tree
Hide file tree
Showing 110 changed files with 785 additions and 634 deletions.
1 change: 1 addition & 0 deletions tesseract_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ target_link_libraries(
trajopt::trajopt_sqp
trajopt::trajopt_ifopt
tesseract::tesseract_task_composer
tesseract::tesseract_task_composer_planning
console_bridge::console_bridge
${PCL_LIBRARIES})
target_compile_options(${PROJECT_NAME} PUBLIC ${TESSERACT_COMPILE_OPTIONS})
Expand Down
11 changes: 5 additions & 6 deletions tesseract_examples/src/basic_cartesian_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_motion_planners/trajopt_ifopt/profile/trajopt_ifopt_default_plan_profile.h>
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_plan_profile.h>

#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>

#include <tesseract_geometry/impl/octree.h>

Expand Down Expand Up @@ -249,15 +248,15 @@ bool BasicCartesianExample::run()
input_data.setData(input_key, program);

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

if (plotter_ != nullptr && plotter_->isConnected())
plotter_->waitForInput("Hit Enter to solve for trajectory.");

// Solve task
tesseract_common::Timer stopwatch;
stopwatch.start();
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
14 changes: 7 additions & 7 deletions tesseract_examples/src/car_seat_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_command_language/move_instruction.h>
#include <tesseract_command_language/profile_dictionary.h>
#include <tesseract_command_language/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>
#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>

#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_solver_profile.h>
Expand Down Expand Up @@ -306,10 +306,10 @@ bool CarSeatExample::run()
input_data.setData(input_key, program);

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

// Solve task
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down Expand Up @@ -395,10 +395,10 @@ bool CarSeatExample::run()
input_data.setData(input_key, program);

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

// Solve task
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
11 changes: 5 additions & 6 deletions tesseract_examples/src/freespace_hybrid_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_motion_planners/ompl/profile/ompl_default_plan_profile.h>
#include <tesseract_motion_planners/core/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
#include <tesseract_visualization/markers/toolpath_marker.h>

#include <tesseract_geometry/impl/sphere.h>
Expand Down Expand Up @@ -185,10 +184,10 @@ bool FreespaceHybridExample::run()
input_data.setData(input_key, program);

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

// Solve task
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
11 changes: 5 additions & 6 deletions tesseract_examples/src/freespace_ompl_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_motion_planners/ompl/profile/ompl_default_plan_profile.h>
#include <tesseract_motion_planners/core/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
#include <tesseract_visualization/markers/toolpath_marker.h>

#include <tesseract_geometry/impl/sphere.h>
Expand Down Expand Up @@ -185,10 +184,10 @@ bool FreespaceOMPLExample::run()
input_data.setData(input_key, program);

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

// Solve task
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
11 changes: 5 additions & 6 deletions tesseract_examples/src/glass_upright_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_command_language/joint_waypoint.h>
#include <tesseract_command_language/move_instruction.h>
#include <tesseract_command_language/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
#include <tesseract_visualization/markers/toolpath_marker.h>

#include <tesseract_motion_planners/core/utils.h>
Expand Down Expand Up @@ -242,15 +241,15 @@ bool GlassUprightExample::run()
input_data.setData(input_key, program);

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

if (plotter_ != nullptr && plotter_->isConnected())
plotter_->waitForInput("Hit Enter to solve for trajectory.");

// Solve process plan
tesseract_common::Timer stopwatch;
stopwatch.start();
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
17 changes: 8 additions & 9 deletions tesseract_examples/src/pick_and_place_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,10 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_command_language/joint_waypoint.h>
#include <tesseract_command_language/move_instruction.h>
#include <tesseract_command_language/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/profiles/contact_check_profile.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/planning/profiles/contact_check_profile.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
#include <tesseract_visualization/markers/toolpath_marker.h>

#include <tesseract_geometry/impl/box.h>
Expand Down Expand Up @@ -232,10 +231,10 @@ bool PickAndPlaceExample::run()
pick_input_data.setData(pick_input_key, pick_program);

// Create Task Composer Problem
auto pick_problem = std::make_unique<PlanningTaskComposerProblem>(env_, pick_input_data);
auto pick_problem = std::make_unique<PlanningTaskComposerProblem>(env_, pick_input_data, profiles);

// Solve task
TaskComposerInput pick_input(std::move(pick_problem), profiles);
TaskComposerInput pick_input(std::move(pick_problem));
TaskComposerFuture::UPtr pick_future = executor->run(*pick_task, pick_input);
pick_future->wait();

Expand Down Expand Up @@ -353,10 +352,10 @@ bool PickAndPlaceExample::run()
place_input_data.setData(place_input_key, place_program);

// Create Task Composer Problem
auto place_problem = std::make_unique<PlanningTaskComposerProblem>(env_, place_input_data);
auto place_problem = std::make_unique<PlanningTaskComposerProblem>(env_, place_input_data, profiles);

// Solve task
TaskComposerInput place_input(std::move(place_problem), profiles);
TaskComposerInput place_input(std::move(place_problem));
TaskComposerFuture::UPtr place_future = executor->run(*place_task, place_input);
place_future->wait();

Expand Down
11 changes: 5 additions & 6 deletions tesseract_examples/src/puzzle_piece_auxillary_axes_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_solver_profile.h>
#include <tesseract_motion_planners/core/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
#include <tesseract_visualization/markers/toolpath_marker.h>
#include <trajopt_sco/osqp_interface.hpp>

Expand Down Expand Up @@ -238,10 +237,10 @@ bool PuzzlePieceAuxillaryAxesExample::run()
plotter_->waitForInput();

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

// Solve task
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
11 changes: 5 additions & 6 deletions tesseract_examples/src/puzzle_piece_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_composite_profile.h>
#include <tesseract_motion_planners/trajopt/profile/trajopt_default_solver_profile.h>
#include <tesseract_motion_planners/core/utils.h>
#include <tesseract_task_composer/planning_task_composer_problem.h>
#include <tesseract_task_composer/task_composer_input.h>

#include <tesseract_task_composer/task_composer_plugin_factory.h>
#include <tesseract_task_composer/planning/planning_task_composer_problem.h>
#include <tesseract_task_composer/core/task_composer_input.h>
#include <tesseract_task_composer/core/task_composer_plugin_factory.h>
#include <tesseract_visualization/markers/toolpath_marker.h>

using namespace trajopt;
Expand Down Expand Up @@ -228,10 +227,10 @@ bool PuzzlePieceExample::run()
plotter_->waitForInput();

// Create Task Composer Problem
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data);
auto problem = std::make_unique<PlanningTaskComposerProblem>(env_, input_data, profiles);

// Solve task
TaskComposerInput input(std::move(problem), profiles);
TaskComposerInput input(std::move(problem));
TaskComposerFuture::UPtr future = executor->run(*task, input);
future->wait();

Expand Down
Loading

0 comments on commit dd5f9ae

Please sign in to comment.