Skip to content

Commit

Permalink
Add ruckig trajectory smoothing
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Jul 28, 2022
1 parent 59159ea commit 425b93c
Show file tree
Hide file tree
Showing 19 changed files with 1,192 additions and 15 deletions.
1 change: 1 addition & 0 deletions tesseract_process_managers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ add_library(
src/task_generators/iterative_spline_parameterization_task_generator.cpp
src/task_generators/motion_planner_task_generator.cpp
src/task_generators/profile_switch_task_generator.cpp
src/task_generators/ruckig_trajectory_smoothing_task_generator.cpp
src/task_generators/seed_min_length_task_generator.cpp
src/task_generators/time_optimal_parameterization_task_generator.cpp
src/task_generators/upsample_trajectory_task_generator.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,18 +31,26 @@
namespace tesseract_planning
{
/** @brief Create TrajOpt Process Pipeline */
TaskflowGenerator::UPtr createTrajOptGenerator(bool check_input = true, bool post_collision_check = true);
TaskflowGenerator::UPtr createTrajOptGenerator(bool check_input = true,
bool post_collision_check = true,
bool post_smoothing = false);

#ifdef TESSERACT_PROCESS_MANAGERS_HAS_TRAJOPT_IFOPT
/** @brief Create TrajOpt IFOPT Process Pipeline */
TaskflowGenerator::UPtr createTrajOptIfoptGenerator(bool check_input = true, bool post_collision_check = true);
TaskflowGenerator::UPtr createTrajOptIfoptGenerator(bool check_input = true,
bool post_collision_check = true,
bool post_smoothing = false);
#endif

/** @brief Create OMPL Process Pipeline */
TaskflowGenerator::UPtr createOMPLGenerator(bool check_input = true, bool post_collision_check = true);
TaskflowGenerator::UPtr createOMPLGenerator(bool check_input = true,
bool post_collision_check = true,
bool post_smoothing = false);

/** @brief Create Descartes Process Pipeline */
TaskflowGenerator::UPtr createDescartesGenerator(bool check_input = true, bool post_collision_check = true);
TaskflowGenerator::UPtr createDescartesGenerator(bool check_input = true,
bool post_collision_check = true,
bool post_smoothing = false);

/**
* @brief Create Descartes Only Process Pipeline
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ static const std::string PROFILE_SWITCH_DEFAULT_NAMESPACE = "
static const std::string SEED_MIN_LENGTH_DEFAULT_NAMESPACE = "SEED_MIN_LENGTH_CHECK";
static const std::string TIME_OPTIMAL_PARAMETERIZATION_DEFAULT_NAMESPACE = "TIME_OPTIMAL_PARAMETERIZATION";
static const std::string UPSAMPLE_TRAJECTORY_DEFAULT_NAMESPACE = "UPSAMPLE_TRAJECTORY";
static const std::string RUCKIG_TRAJECTORY_SMOOTHING_DEFAULT_NAMESPACE = "RUCKIG_TRAJECTORY_SMOOTHING";

// clang-format on
} // namespace tesseract_planning::profile_ns
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
/**
* @file ruckig_trajectory_smoothing_task_generator.h
* @brief Leveraging Ruckig to smooth trajectory
*
* @author Levi Armstrong
* @date July 27, 2022
* @version TODO
* @bug No known bugs
*
* @par License
* Software License Agreement (Apache License)
* @par
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
* http://www.apache.org/licenses/LICENSE-2.0
* @par
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef TESSERACT_PROCESS_MANAGERS_RUCKIG_TRAJECTORY_SMOOTHING_TASK_GENERATOR_H
#define TESSERACT_PROCESS_MANAGERS_RUCKIG_TRAJECTORY_SMOOTHING_TASK_GENERATOR_H

#include <tesseract_common/macros.h>
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <boost/serialization/access.hpp>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_process_managers/core/task_generator.h>
#include <tesseract_time_parameterization/ruckig_trajectory_smoothing.h>
#include <tesseract_process_managers/core/default_task_namespaces.h>

namespace tesseract_planning
{
class RuckigTrajectorySmoothingTaskGenerator : public TaskGenerator
{
public:
using UPtr = std::unique_ptr<RuckigTrajectorySmoothingTaskGenerator>;

RuckigTrajectorySmoothingTaskGenerator(std::string name = profile_ns::RUCKIG_TRAJECTORY_SMOOTHING_DEFAULT_NAMESPACE);

~RuckigTrajectorySmoothingTaskGenerator() override = default;
RuckigTrajectorySmoothingTaskGenerator(const RuckigTrajectorySmoothingTaskGenerator&) = delete;
RuckigTrajectorySmoothingTaskGenerator& operator=(const RuckigTrajectorySmoothingTaskGenerator&) = delete;
RuckigTrajectorySmoothingTaskGenerator(RuckigTrajectorySmoothingTaskGenerator&&) = delete;
RuckigTrajectorySmoothingTaskGenerator& operator=(RuckigTrajectorySmoothingTaskGenerator&&) = delete;

int conditionalProcess(TaskInput input, std::size_t unique_id) const override final;

void process(TaskInput input, std::size_t unique_id) const override final;
};

class RuckigTrajectorySmoothingTaskInfo : public TaskInfo
{
public:
using Ptr = std::shared_ptr<RuckigTrajectorySmoothingTaskInfo>;
using ConstPtr = std::shared_ptr<const RuckigTrajectorySmoothingTaskInfo>;

RuckigTrajectorySmoothingTaskInfo() = default;
RuckigTrajectorySmoothingTaskInfo(std::size_t unique_id,
std::string name = profile_ns::RUCKIG_TRAJECTORY_SMOOTHING_DEFAULT_NAMESPACE);

TaskInfo::UPtr clone() const override;

bool operator==(const RuckigTrajectorySmoothingTaskInfo& rhs) const;
bool operator!=(const RuckigTrajectorySmoothingTaskInfo& rhs) const;

private:
friend class boost::serialization::access;
template <class Archive>
void serialize(Archive& ar, const unsigned int version); // NOLINT
};
} // namespace tesseract_planning

#include <boost/serialization/export.hpp>
#include <boost/serialization/tracking.hpp>
BOOST_CLASS_EXPORT_KEY2(tesseract_planning::RuckigTrajectorySmoothingTaskInfo, "RuckigTrajectorySmoothingTaskInfo")

#endif // TESSERACT_PROCESS_MANAGERS_RUCKIG_TRAJECTORY_SMOOTHING_TASK_GENERATOR_H
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
/**
* @file ruckig_trajectory_smoothing_profile.h
* @brief Leveraging Ruckig to smooth trajectory
*
* @author Levi Armstrong
* @date July 27, 2022
* @version TODO
* @bug No known bugs
*
* @par License
* Software License Agreement (Apache License)
* @par
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
* http://www.apache.org/licenses/LICENSE-2.0
* @par
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef TESSERACT_PROCESS_MANAGERS_RUCKIG_TRAJECTORY_SMOOTHING_PROFILE_H
#define TESSERACT_PROCESS_MANAGERS_RUCKIG_TRAJECTORY_SMOOTHING_PROFILE_H

#include <tesseract_common/macros.h>
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <memory>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

namespace tesseract_planning
{
struct RuckigTrajectorySmoothingCompositeProfile
{
using Ptr = std::shared_ptr<RuckigTrajectorySmoothingCompositeProfile>;
using ConstPtr = std::shared_ptr<const RuckigTrajectorySmoothingCompositeProfile>;

RuckigTrajectorySmoothingCompositeProfile() = default;
RuckigTrajectorySmoothingCompositeProfile(double duration_extension_fraction,
double max_duration_extension_factor,
double max_velocity_scaling_factor,
double max_acceleration_scaling_factor)
: duration_extension_fraction(duration_extension_fraction)
, max_duration_extension_factor(max_duration_extension_factor)
, max_velocity_scaling_factor(max_velocity_scaling_factor)
, max_acceleration_scaling_factor(max_acceleration_scaling_factor)
{
}

/** @brief duration_extension_fraction The amount to scale the trajectory each time */
double duration_extension_fraction{ 1.1 };

/** @brief The max allow extension factor */
double max_duration_extension_factor{ 10.0 };

/** @brief max_velocity_scaling_factor The max velocity scaling factor passed to the solver */
double max_velocity_scaling_factor{ 1.0 };

/** @brief max_velocity_scaling_factor The max acceleration scaling factor passed to the solver */
double max_acceleration_scaling_factor{ 1.0 };

/** @brief max_jerk_scaling_factor The max jerk scaling factor passed to the solver */
double max_jerk_scaling_factor{ 1.0 };
};

struct RuckigTrajectorySmoothingMoveProfile
{
using Ptr = std::shared_ptr<RuckigTrajectorySmoothingMoveProfile>;
using ConstPtr = std::shared_ptr<const RuckigTrajectorySmoothingMoveProfile>;

RuckigTrajectorySmoothingMoveProfile() = default;
RuckigTrajectorySmoothingMoveProfile(double max_velocity_scaling_factor, double max_acceleration_scaling_factor)
: max_velocity_scaling_factor(max_velocity_scaling_factor)
, max_acceleration_scaling_factor(max_acceleration_scaling_factor)
{
}

/** @brief max_velocity_scaling_factor The max velocity scaling factor passed to the solver */
double max_velocity_scaling_factor{ 1.0 };

/** @brief max_velocity_scaling_factor The max acceleration scaling factor passed to the solver */
double max_acceleration_scaling_factor{ 1.0 };

/** @brief max_jerk_scaling_factor The max jerk scaling factor passed to the solver */
double max_jerk_scaling_factor{ 1.0 };
};
} // namespace tesseract_planning

#endif // TESSERACT_PROCESS_MANAGERS_RUCKIG_TRAJECTORY_SMOOTHING_PROFILE_H
69 changes: 61 additions & 8 deletions tesseract_process_managers/src/core/default_process_planners.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <tesseract_process_managers/task_generators/seed_min_length_task_generator.h>
#include <tesseract_process_managers/task_generators/discrete_contact_check_task_generator.h>
#include <tesseract_process_managers/task_generators/iterative_spline_parameterization_task_generator.h>
#include <tesseract_process_managers/task_generators/ruckig_trajectory_smoothing_task_generator.h>
#include <tesseract_process_managers/task_generators/check_input_task_generator.h>

#include <tesseract_motion_planners/simple/simple_motion_planner.h>
Expand All @@ -51,7 +52,7 @@

namespace tesseract_planning
{
TaskflowGenerator::UPtr createTrajOptGenerator(bool check_input, bool post_collision_check)
TaskflowGenerator::UPtr createTrajOptGenerator(bool check_input, bool post_collision_check, bool post_smoothing)
{
auto tf = std::make_unique<GraphTaskflow>("TrajOptTaskflow");

Expand Down Expand Up @@ -83,6 +84,11 @@ TaskflowGenerator::UPtr createTrajOptGenerator(bool check_input, bool post_colli
// Setup time parameterization
int time_parameterization_task = tf->addNode(std::make_unique<IterativeSplineParameterizationTaskGenerator>(), true);

// Setup trajectory smoothing
int smoothing_task{ std::numeric_limits<int>::min() };
if (post_smoothing)
smoothing_task = tf->addNode(std::make_unique<RuckigTrajectorySmoothingTaskGenerator>(), true);

if (check_input)
tf->addEdges(check_input_task, { GraphTaskflow::ERROR_NODE, has_seed_task });

Expand All @@ -100,13 +106,21 @@ TaskflowGenerator::UPtr createTrajOptGenerator(bool check_input, bool post_colli
tf->addEdges(motion_planner_task, { GraphTaskflow::ERROR_NODE, time_parameterization_task });
}

tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
if (post_smoothing)
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, smoothing_task });
tf->addEdges(smoothing_task, { GraphTaskflow::DONE_NODE });
}
else
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
}

return tf;
}

#ifdef TESSERACT_PROCESS_MANAGERS_HAS_TRAJOPT_IFOPT
TaskflowGenerator::UPtr createTrajOptIfoptGenerator(bool check_input, bool post_collision_check)
TaskflowGenerator::UPtr createTrajOptIfoptGenerator(bool check_input, bool post_collision_check, bool post_smoothing)
{
auto tf = std::make_unique<GraphTaskflow>("TrajOptIfoptTaskflow");

Expand Down Expand Up @@ -138,6 +152,11 @@ TaskflowGenerator::UPtr createTrajOptIfoptGenerator(bool check_input, bool post_
// Setup time parameterization
int time_parameterization_task = tf->addNode(std::make_unique<IterativeSplineParameterizationTaskGenerator>(), true);

// Setup trajectory smoothing
int smoothing_task{ std::numeric_limits<int>::min() };
if (post_smoothing)
smoothing_task = tf->addNode(std::make_unique<RuckigTrajectorySmoothingTaskGenerator>(), true);

if (check_input)
tf->addEdges(check_input_task, { GraphTaskflow::ERROR_NODE, has_seed_task });

Expand All @@ -155,13 +174,21 @@ TaskflowGenerator::UPtr createTrajOptIfoptGenerator(bool check_input, bool post_
tf->addEdges(motion_planner_task, { GraphTaskflow::ERROR_NODE, time_parameterization_task });
}

tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
if (post_smoothing)
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, smoothing_task });
tf->addEdges(smoothing_task, { GraphTaskflow::DONE_NODE });
}
else
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
}

return tf;
}
#endif

TaskflowGenerator::UPtr createOMPLGenerator(bool check_input, bool post_collision_check)
TaskflowGenerator::UPtr createOMPLGenerator(bool check_input, bool post_collision_check, bool post_smoothing)
{
auto tf = std::make_unique<GraphTaskflow>("OMPLTaskflow");

Expand Down Expand Up @@ -193,6 +220,11 @@ TaskflowGenerator::UPtr createOMPLGenerator(bool check_input, bool post_collisio
// Setup time parameterization
int time_parameterization_task = tf->addNode(std::make_unique<IterativeSplineParameterizationTaskGenerator>(), true);

// Setup trajectory smoothing
int smoothing_task{ std::numeric_limits<int>::min() };
if (post_smoothing)
smoothing_task = tf->addNode(std::make_unique<RuckigTrajectorySmoothingTaskGenerator>(), true);

if (check_input)
tf->addEdges(check_input_task, { GraphTaskflow::ERROR_NODE, has_seed_task });

Expand All @@ -210,12 +242,20 @@ TaskflowGenerator::UPtr createOMPLGenerator(bool check_input, bool post_collisio
tf->addEdges(motion_planner_task, { GraphTaskflow::ERROR_NODE, time_parameterization_task });
}

tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
if (post_smoothing)
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, smoothing_task });
tf->addEdges(smoothing_task, { GraphTaskflow::DONE_NODE });
}
else
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
}

return tf;
}

TaskflowGenerator::UPtr createDescartesGenerator(bool check_input, bool post_collision_check)
TaskflowGenerator::UPtr createDescartesGenerator(bool check_input, bool post_collision_check, bool post_smoothing)
{
auto tf = std::make_unique<GraphTaskflow>("DescartesTaskflow");

Expand Down Expand Up @@ -247,6 +287,11 @@ TaskflowGenerator::UPtr createDescartesGenerator(bool check_input, bool post_col
// Setup time parameterization
int time_parameterization_task = tf->addNode(std::make_unique<IterativeSplineParameterizationTaskGenerator>(), true);

// Setup trajectory smoothing
int smoothing_task{ std::numeric_limits<int>::min() };
if (post_smoothing)
smoothing_task = tf->addNode(std::make_unique<RuckigTrajectorySmoothingTaskGenerator>(), true);

if (check_input)
tf->addEdges(check_input_task, { GraphTaskflow::ERROR_NODE, has_seed_task });

Expand All @@ -264,7 +309,15 @@ TaskflowGenerator::UPtr createDescartesGenerator(bool check_input, bool post_col
tf->addEdges(motion_planner_task, { GraphTaskflow::ERROR_NODE, time_parameterization_task });
}

tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
if (post_smoothing)
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, smoothing_task });
tf->addEdges(smoothing_task, { GraphTaskflow::DONE_NODE });
}
else
{
tf->addEdges(time_parameterization_task, { GraphTaskflow::ERROR_NODE, GraphTaskflow::DONE_NODE });
}

return tf;
}
Expand Down
Loading

0 comments on commit 425b93c

Please sign in to comment.