diff --git a/tesseract_examples/src/puzzle_piece_auxillary_axes_example.cpp b/tesseract_examples/src/puzzle_piece_auxillary_axes_example.cpp index ccb49fd73e8..c97f84ad8af 100644 --- a/tesseract_examples/src/puzzle_piece_auxillary_axes_example.cpp +++ b/tesseract_examples/src/puzzle_piece_auxillary_axes_example.cpp @@ -31,6 +31,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include +#include #include #include #include @@ -287,9 +288,14 @@ bool PuzzlePieceAuxillaryAxesExample::run() problem->input = program; // Solve task + tesseract_common::Timer stopwatch; + stopwatch.start(); TaskComposerFuture::UPtr future = executor->run(*task, std::move(problem)); future->wait(); + stopwatch.stop(); + CONSOLE_BRIDGE_logInform("Planning took %f seconds.", stopwatch.elapsedSeconds()); + // Plot Process Trajectory if (plotter_ != nullptr && plotter_->isConnected()) { diff --git a/tesseract_examples/src/puzzle_piece_example.cpp b/tesseract_examples/src/puzzle_piece_example.cpp index b1020c0ef83..8ce1f9ce76a 100644 --- a/tesseract_examples/src/puzzle_piece_example.cpp +++ b/tesseract_examples/src/puzzle_piece_example.cpp @@ -30,8 +30,8 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH TESSERACT_COMMON_IGNORE_WARNINGS_POP #include -#include #include +#include #include #include #include diff --git a/tesseract_examples/test/puzzle_piece_auxillary_axes_example_unit.cpp b/tesseract_examples/test/puzzle_piece_auxillary_axes_example_unit.cpp index e99a450a5e3..5ae2048da01 100644 --- a/tesseract_examples/test/puzzle_piece_auxillary_axes_example_unit.cpp +++ b/tesseract_examples/test/puzzle_piece_auxillary_axes_example_unit.cpp @@ -25,7 +25,7 @@ TEST(TesseractExamples, PuzzlePieceAuxillaryAxesCppTrajOptExampleUnit) // NOLIN EXPECT_TRUE(example.run()); } -TEST(TesseractExamples, DISABLED_PuzzlePieceAuxillaryAxesCppTrajOptIfoptExampleUnit) // NOLINT +TEST(TesseractExamples, PuzzlePieceAuxillaryAxesCppTrajOptIfoptExampleUnit) // NOLINT { auto locator = std::make_shared(); tesseract_common::fs::path urdf_path = diff --git a/tesseract_motion_planners/trajopt_ifopt/src/profile/trajopt_ifopt_default_plan_profile.cpp b/tesseract_motion_planners/trajopt_ifopt/src/profile/trajopt_ifopt_default_plan_profile.cpp index 62963f892fd..f0450734465 100644 --- a/tesseract_motion_planners/trajopt_ifopt/src/profile/trajopt_ifopt_default_plan_profile.cpp +++ b/tesseract_motion_planners/trajopt_ifopt/src/profile/trajopt_ifopt_default_plan_profile.cpp @@ -38,7 +38,7 @@ void TrajOptIfoptDefaultPlanProfile::apply(TrajOptIfoptProblem& problem, const CartesianWaypointPoly& cartesian_waypoint, const InstructionPoly& parent_instruction, const tesseract_common::ManipulatorInfo& manip_info, - const std::vector& active_links, + const std::vector& /*active_links*/, int index) const { assert(parent_instruction.isMoveInstruction()); @@ -61,20 +61,30 @@ void TrajOptIfoptDefaultPlanProfile::apply(TrajOptIfoptProblem& problem, throw std::runtime_error("TrajOptIfoptDefaultPlanProfile: cartesian_coeff size must be 6."); trajopt_ifopt::JointPosition::ConstPtr var = problem.vars[static_cast(index)]; - - /* Check if this cartesian waypoint is dynamic - * (i.e. defined relative to a frame that will move with the kinematic chain) - */ - bool is_active_tcp_frame = (std::find(active_links.begin(), active_links.end(), mi.tcp_frame) != active_links.end()); - bool is_static_working_frame = - (std::find(active_links.begin(), active_links.end(), mi.working_frame) == active_links.end()); - - if ((is_static_working_frame && is_active_tcp_frame) || (!is_active_tcp_frame && !is_static_working_frame)) + switch (term_type) { - switch (term_type) - { - case TrajOptIfoptTermType::CONSTRAINT: - addCartesianPositionConstraint(*problem.nlp, + case TrajOptIfoptTermType::CONSTRAINT: + addCartesianPositionConstraint(*problem.nlp, + var, + problem.manip, + mi.tcp_frame, + mi.working_frame, + tcp_offset, + cartesian_waypoint.getTransform(), + cartesian_coeff); + break; + case TrajOptIfoptTermType::SQUARED_COST: + addCartesianPositionSquaredCost(*problem.nlp, + var, + problem.manip, + mi.tcp_frame, + mi.working_frame, + tcp_offset, + cartesian_waypoint.getTransform(), + cartesian_coeff); + break; + case TrajOptIfoptTermType::ABSOLUTE_COST: + addCartesianPositionAbsoluteCost(*problem.nlp, var, problem.manip, mi.tcp_frame, @@ -82,36 +92,7 @@ void TrajOptIfoptDefaultPlanProfile::apply(TrajOptIfoptProblem& problem, tcp_offset, cartesian_waypoint.getTransform(), cartesian_coeff); - break; - case TrajOptIfoptTermType::SQUARED_COST: - addCartesianPositionSquaredCost(*problem.nlp, - var, - problem.manip, - mi.tcp_frame, - mi.working_frame, - tcp_offset, - cartesian_waypoint.getTransform(), - cartesian_coeff); - break; - case TrajOptIfoptTermType::ABSOLUTE_COST: - addCartesianPositionAbsoluteCost(*problem.nlp, - var, - problem.manip, - mi.tcp_frame, - mi.working_frame, - tcp_offset, - cartesian_waypoint.getTransform(), - cartesian_coeff); - break; - } - } - else if (!is_static_working_frame && is_active_tcp_frame) - { - throw std::runtime_error("TrajOpt IFOPT currently does not support dynamic cartesian waypoints!"); - } - else - { - throw std::runtime_error("TrajOpt, both tcp_frame and working_frame are both static!"); + break; } }