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

Add optional namespace field to task nodes #433

Merged
Original file line number Diff line number Diff line change
Expand Up @@ -37,18 +37,18 @@ class MotionPlanner
using ConstPtr = std::shared_ptr<const MotionPlanner>;
/** @brief Construct a basic planner */
MotionPlanner() = default;
MotionPlanner(std::string name);
MotionPlanner(std::string ns);
virtual ~MotionPlanner() = default;
MotionPlanner(const MotionPlanner&) = delete;
MotionPlanner& operator=(const MotionPlanner&) = delete;
MotionPlanner(MotionPlanner&&) = delete;
MotionPlanner& operator=(MotionPlanner&&) = delete;

/**
* @brief Get the name of this planner
* @brief Get the namespace of this planner
* @details This is also used as the namespace for the profiles in the profile dictionary
*/
const std::string& getName() const;
const std::string& getNamespace() const;

/**
* @brief Solve the planner request problem
Expand Down Expand Up @@ -79,7 +79,7 @@ class MotionPlanner
bool format_result_as_input);

protected:
std::string name_;
std::string ns_;
};
} // namespace tesseract_planning
Levi-Armstrong marked this conversation as resolved.
Show resolved Hide resolved
#endif // TESSERACT_PLANNING_PLANNER_H
8 changes: 4 additions & 4 deletions tesseract_motion_planners/core/src/planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@

namespace tesseract_planning
{
MotionPlanner::MotionPlanner(std::string name) : name_(std::move(name))
MotionPlanner::MotionPlanner(std::string ns) : ns_(std::move(ns))
{
if (name_.empty())
throw std::runtime_error("MotionPlanner name is empty!");
if (ns_.empty())
throw std::runtime_error("MotionPlanner namespace is empty!");
}

const std::string& MotionPlanner::getName() const { return name_; }
const std::string& MotionPlanner::getNamespace() const { return ns_; }

bool MotionPlanner::checkRequest(const PlannerRequest& request)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ class DescartesMotionPlanner : public MotionPlanner
{
public:
/** @brief Construct a basic planner */
DescartesMotionPlanner(std::string name);
DescartesMotionPlanner(std::string ns);
~DescartesMotionPlanner() override = default;
DescartesMotionPlanner(const DescartesMotionPlanner&) = delete;
DescartesMotionPlanner& operator=(const DescartesMotionPlanner&) = delete;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ constexpr auto ERROR_FAILED_TO_FIND_VALID_SOLUTION{ "Failed to find valid soluti
namespace tesseract_planning
{
template <typename FloatType>
DescartesMotionPlanner<FloatType>::DescartesMotionPlanner(std::string name) : MotionPlanner(std::move(name)) // NOLINT
DescartesMotionPlanner<FloatType>::DescartesMotionPlanner(std::string ns) : MotionPlanner(std::move(ns)) // NOLINT
{
}

Expand Down Expand Up @@ -213,7 +213,7 @@ void DescartesMotionPlanner<FloatType>::clear()
template <typename FloatType>
MotionPlanner::Ptr DescartesMotionPlanner<FloatType>::clone() const
{
return std::make_shared<DescartesMotionPlanner<FloatType>>(name_);
return std::make_shared<DescartesMotionPlanner<FloatType>>(ns_);
}

template <typename FloatType>
Expand Down Expand Up @@ -284,10 +284,10 @@ DescartesMotionPlanner<FloatType>::createProblem(const PlannerRequest& request)

// Get Plan Profile
std::string profile = plan_instruction.getProfile();
profile = getProfileString(name_, profile, request.plan_profile_remapping);
profile = getProfileString(ns_, profile, request.plan_profile_remapping);
auto cur_plan_profile = getProfile<DescartesPlanProfile<FloatType>>(
name_, profile, *request.profiles, std::make_shared<DescartesDefaultPlanProfile<FloatType>>());
// cur_plan_profile = applyProfileOverrides(name_, profile, cur_plan_profile,
ns_, profile, *request.profiles, std::make_shared<DescartesDefaultPlanProfile<FloatType>>());
// cur_plan_profile = applyProfileOverrides(ns_, profile, cur_plan_profile,
// plan_instruction.profile_overrides);
if (!cur_plan_profile)
throw std::runtime_error("DescartesMotionPlanner: Invalid profile");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class OMPLMotionPlanner : public MotionPlanner
{
public:
/** @brief Construct a planner */
OMPLMotionPlanner(std::string name);
OMPLMotionPlanner(std::string ns);

/**
* @brief Sets up the OMPL problem then solves. It is intended to simplify setting up
Expand Down
10 changes: 5 additions & 5 deletions tesseract_motion_planners/ompl/src/ompl_motion_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ bool checkGoalState(const ompl::base::ProblemDefinitionPtr& prob_def,
}

/** @brief Construct a basic planner */
OMPLMotionPlanner::OMPLMotionPlanner(std::string name) : MotionPlanner(std::move(name)) {}
OMPLMotionPlanner::OMPLMotionPlanner(std::string ns) : MotionPlanner(std::move(ns)) {}

bool OMPLMotionPlanner::terminate()
{
Expand Down Expand Up @@ -307,7 +307,7 @@ PlannerResponse OMPLMotionPlanner::solve(const PlannerRequest& request) const

void OMPLMotionPlanner::clear() { parallel_plan_ = nullptr; }

MotionPlanner::Ptr OMPLMotionPlanner::clone() const { return std::make_shared<OMPLMotionPlanner>(name_); }
MotionPlanner::Ptr OMPLMotionPlanner::clone() const { return std::make_shared<OMPLMotionPlanner>(ns_); }

OMPLProblemConfig OMPLMotionPlanner::createSubProblem(const PlannerRequest& request,
const tesseract_common::ManipulatorInfo& composite_mi,
Expand All @@ -322,10 +322,10 @@ OMPLProblemConfig OMPLMotionPlanner::createSubProblem(const PlannerRequest& requ

// Get Plan Profile
std::string profile = end_instruction.getProfile();
profile = getProfileString(name_, profile, request.plan_profile_remapping);
profile = getProfileString(ns_, profile, request.plan_profile_remapping);
auto cur_plan_profile =
getProfile<OMPLPlanProfile>(name_, profile, *request.profiles, std::make_shared<OMPLDefaultPlanProfile>());
cur_plan_profile = applyProfileOverrides(name_, profile, cur_plan_profile, end_instruction.getProfileOverrides());
getProfile<OMPLPlanProfile>(ns_, profile, *request.profiles, std::make_shared<OMPLDefaultPlanProfile>());
cur_plan_profile = applyProfileOverrides(ns_, profile, cur_plan_profile, end_instruction.getProfileOverrides());
if (!cur_plan_profile)
throw std::runtime_error("OMPLMotionPlanner: Invalid profile");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class SimpleMotionPlanner : public MotionPlanner
using ConstPtr = std::shared_ptr<const SimpleMotionPlanner>;

/** @brief Construct a basic planner */
SimpleMotionPlanner(std::string name);
SimpleMotionPlanner(std::string ns);
~SimpleMotionPlanner() override = default;
SimpleMotionPlanner(const SimpleMotionPlanner&) = delete;
SimpleMotionPlanner& operator=(const SimpleMotionPlanner&) = delete;
Expand Down
4 changes: 2 additions & 2 deletions tesseract_motion_planners/simple/src/interpolation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1302,11 +1302,11 @@ CompositeInstruction generateInterpolatedProgram(const CompositeInstruction& ins

// Create profile dictionary
auto profiles = std::make_shared<ProfileDictionary>();
profiles->addProfile<SimplePlannerPlanProfile>(planner.getName(), instructions.getProfile(), profile);
profiles->addProfile<SimplePlannerPlanProfile>(planner.getNamespace(), instructions.getProfile(), profile);
auto flat = instructions.flatten(&moveFilter);
for (const auto& i : flat)
profiles->addProfile<SimplePlannerPlanProfile>(
planner.getName(), i.get().as<MoveInstructionPoly>().getProfile(), profile);
planner.getNamespace(), i.get().as<MoveInstructionPoly>().getProfile(), profile);

// Assign profile dictionary
request.profiles = profiles;
Expand Down
17 changes: 8 additions & 9 deletions tesseract_motion_planners/simple/src/simple_motion_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ constexpr auto FAILED_TO_FIND_VALID_SOLUTION{ "Failed to find valid solution" };

namespace tesseract_planning
{
SimpleMotionPlanner::SimpleMotionPlanner(std::string name) : MotionPlanner(std::move(name)) {}
SimpleMotionPlanner::SimpleMotionPlanner(std::string ns) : MotionPlanner(std::move(ns)) {}

bool SimpleMotionPlanner::terminate()
{
Expand All @@ -56,7 +56,7 @@ bool SimpleMotionPlanner::terminate()

void SimpleMotionPlanner::clear() {}

MotionPlanner::Ptr SimpleMotionPlanner::clone() const { return std::make_shared<SimpleMotionPlanner>(name_); }
MotionPlanner::Ptr SimpleMotionPlanner::clone() const { return std::make_shared<SimpleMotionPlanner>(ns_); }

PlannerResponse SimpleMotionPlanner::solve(const PlannerRequest& request) const
{
Expand Down Expand Up @@ -196,18 +196,17 @@ CompositeInstruction SimpleMotionPlanner::processCompositeInstruction(const Comp
SimplePlannerPlanProfile::ConstPtr plan_profile;
if (base_instruction.getPathProfile().empty())
{
std::string profile = getProfileString(name_, base_instruction.getProfile(), request.plan_profile_remapping);
std::string profile = getProfileString(ns_, base_instruction.getProfile(), request.plan_profile_remapping);
plan_profile = getProfile<SimplePlannerPlanProfile>(
name_, profile, *request.profiles, std::make_shared<SimplePlannerLVSNoIKPlanProfile>());
plan_profile = applyProfileOverrides(name_, profile, plan_profile, base_instruction.getProfileOverrides());
ns_, profile, *request.profiles, std::make_shared<SimplePlannerLVSNoIKPlanProfile>());
plan_profile = applyProfileOverrides(ns_, profile, plan_profile, base_instruction.getProfileOverrides());
}
else
{
std::string profile =
getProfileString(name_, base_instruction.getPathProfile(), request.plan_profile_remapping);
std::string profile = getProfileString(ns_, base_instruction.getPathProfile(), request.plan_profile_remapping);
plan_profile = getProfile<SimplePlannerPlanProfile>(
name_, profile, *request.profiles, std::make_shared<SimplePlannerLVSNoIKPlanProfile>());
plan_profile = applyProfileOverrides(name_, profile, plan_profile, base_instruction.getProfileOverrides());
ns_, profile, *request.profiles, std::make_shared<SimplePlannerLVSNoIKPlanProfile>());
plan_profile = applyProfileOverrides(ns_, profile, plan_profile, base_instruction.getProfileOverrides());
}

if (!plan_profile)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class TrajOptMotionPlanner : public MotionPlanner
{
public:
/** @brief Construct a basic planner */
TrajOptMotionPlanner(std::string name);
TrajOptMotionPlanner(std::string ns);

~TrajOptMotionPlanner() override = default;
TrajOptMotionPlanner(const TrajOptMotionPlanner&) = delete;
Expand Down
24 changes: 12 additions & 12 deletions tesseract_motion_planners/trajopt/src/trajopt_motion_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ using namespace trajopt;

namespace tesseract_planning
{
TrajOptMotionPlanner::TrajOptMotionPlanner(std::string name) : MotionPlanner(std::move(name)) {}
TrajOptMotionPlanner::TrajOptMotionPlanner(std::string ns) : MotionPlanner(std::move(ns)) {}

bool TrajOptMotionPlanner::terminate()
{
Expand All @@ -62,7 +62,7 @@ bool TrajOptMotionPlanner::terminate()

void TrajOptMotionPlanner::clear() {}

MotionPlanner::Ptr TrajOptMotionPlanner::clone() const { return std::make_shared<TrajOptMotionPlanner>(name_); }
MotionPlanner::Ptr TrajOptMotionPlanner::clone() const { return std::make_shared<TrajOptMotionPlanner>(ns_); }

PlannerResponse TrajOptMotionPlanner::solve(const PlannerRequest& request) const
{
Expand Down Expand Up @@ -212,10 +212,10 @@ TrajOptMotionPlanner::createProblem(const PlannerRequest& request) const
// Apply Solver parameters
std::string profile = request.instructions.getProfile();
ProfileDictionary::ConstPtr profile_overrides = request.instructions.getProfileOverrides();
profile = getProfileString(name_, profile, request.plan_profile_remapping);
profile = getProfileString(ns_, profile, request.plan_profile_remapping);
TrajOptSolverProfile::ConstPtr solver_profile = getProfile<TrajOptSolverProfile>(
name_, profile, *request.profiles, std::make_shared<TrajOptDefaultSolverProfile>());
solver_profile = applyProfileOverrides(name_, profile, solver_profile, profile_overrides);
ns_, profile, *request.profiles, std::make_shared<TrajOptDefaultSolverProfile>());
solver_profile = applyProfileOverrides(ns_, profile, solver_profile, profile_overrides);
if (!solver_profile)
throw std::runtime_error("TrajOptMotionPlanner: Invalid profile");

Expand Down Expand Up @@ -250,10 +250,10 @@ TrajOptMotionPlanner::createProblem(const PlannerRequest& request) const
throw std::runtime_error("TrajOpt, working_frame is empty!");

// Get Plan Profile
std::string profile = getProfileString(name_, move_instruction.getProfile(), request.plan_profile_remapping);
TrajOptPlanProfile::ConstPtr cur_plan_profile = getProfile<TrajOptPlanProfile>(
name_, profile, *request.profiles, std::make_shared<TrajOptDefaultPlanProfile>());
cur_plan_profile = applyProfileOverrides(name_, profile, cur_plan_profile, move_instruction.getProfileOverrides());
std::string profile = getProfileString(ns_, move_instruction.getProfile(), request.plan_profile_remapping);
TrajOptPlanProfile::ConstPtr cur_plan_profile =
getProfile<TrajOptPlanProfile>(ns_, profile, *request.profiles, std::make_shared<TrajOptDefaultPlanProfile>());
cur_plan_profile = applyProfileOverrides(ns_, profile, cur_plan_profile, move_instruction.getProfileOverrides());
if (!cur_plan_profile)
throw std::runtime_error("TrajOptMotionPlanner: Invalid profile");

Expand Down Expand Up @@ -333,11 +333,11 @@ TrajOptMotionPlanner::createProblem(const PlannerRequest& request) const
for (long i = 0; i < pci->basic_info.n_steps; ++i)
pci->init_info.data.row(i) = seed_states[static_cast<std::size_t>(i)];

profile = getProfileString(name_, request.instructions.getProfile(), request.composite_profile_remapping);
profile = getProfileString(ns_, request.instructions.getProfile(), request.composite_profile_remapping);
TrajOptCompositeProfile::ConstPtr cur_composite_profile = getProfile<TrajOptCompositeProfile>(
name_, profile, *request.profiles, std::make_shared<TrajOptDefaultCompositeProfile>());
ns_, profile, *request.profiles, std::make_shared<TrajOptDefaultCompositeProfile>());
cur_composite_profile =
applyProfileOverrides(name_, profile, cur_composite_profile, request.instructions.getProfileOverrides());
applyProfileOverrides(ns_, profile, cur_composite_profile, request.instructions.getProfileOverrides());
if (!cur_composite_profile)
throw std::runtime_error("TrajOptMotionPlanner: Invalid profile");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class TrajOptIfoptMotionPlanner : public MotionPlanner
{
public:
/** @brief Construct a basic planner */
TrajOptIfoptMotionPlanner(std::string name);
TrajOptIfoptMotionPlanner(std::string ns);

~TrajOptIfoptMotionPlanner() override = default;
TrajOptIfoptMotionPlanner(const TrajOptIfoptMotionPlanner&) = delete;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,18 +50,15 @@ using namespace trajopt_ifopt;

namespace tesseract_planning
{
TrajOptIfoptMotionPlanner::TrajOptIfoptMotionPlanner(std::string name) : MotionPlanner(std::move(name)) {}
TrajOptIfoptMotionPlanner::TrajOptIfoptMotionPlanner(std::string ns) : MotionPlanner(std::move(ns)) {}

bool TrajOptIfoptMotionPlanner::terminate()
{
CONSOLE_BRIDGE_logWarn("Termination of ongoing optimization is not implemented yet");
return false;
}

MotionPlanner::Ptr TrajOptIfoptMotionPlanner::clone() const
{
return std::make_shared<TrajOptIfoptMotionPlanner>(name_);
}
MotionPlanner::Ptr TrajOptIfoptMotionPlanner::clone() const { return std::make_shared<TrajOptIfoptMotionPlanner>(ns_); }

PlannerResponse TrajOptIfoptMotionPlanner::solve(const PlannerRequest& request) const
{
Expand Down Expand Up @@ -218,10 +215,10 @@ std::shared_ptr<TrajOptIfoptProblem> TrajOptIfoptMotionPlanner::createProblem(co
// Apply Solver parameters
std::string profile = request.instructions.getProfile();
ProfileDictionary::ConstPtr profile_overrides = request.instructions.getProfileOverrides();
profile = getProfileString(name_, profile, request.plan_profile_remapping);
profile = getProfileString(ns_, profile, request.plan_profile_remapping);
TrajOptIfoptSolverProfile::ConstPtr solver_profile = getProfile<TrajOptIfoptSolverProfile>(
name_, profile, *request.profiles, std::make_shared<TrajOptIfoptDefaultSolverProfile>());
solver_profile = applyProfileOverrides(name_, profile, solver_profile, profile_overrides);
ns_, profile, *request.profiles, std::make_shared<TrajOptIfoptDefaultSolverProfile>());
solver_profile = applyProfileOverrides(ns_, profile, solver_profile, profile_overrides);
if (!solver_profile)
throw std::runtime_error("TrajOptIfoptMotionPlanner: Invalid profile");

Expand Down Expand Up @@ -256,10 +253,10 @@ std::shared_ptr<TrajOptIfoptProblem> TrajOptIfoptMotionPlanner::createProblem(co
throw std::runtime_error("TrajOpt, working_frame is empty!");

// Get Plan Profile
std::string profile = getProfileString(name_, move_instruction.getProfile(), request.plan_profile_remapping);
std::string profile = getProfileString(ns_, move_instruction.getProfile(), request.plan_profile_remapping);
TrajOptIfoptPlanProfile::ConstPtr cur_plan_profile = getProfile<TrajOptIfoptPlanProfile>(
name_, profile, *request.profiles, std::make_shared<TrajOptIfoptDefaultPlanProfile>());
cur_plan_profile = applyProfileOverrides(name_, profile, cur_plan_profile, move_instruction.getProfileOverrides());
ns_, profile, *request.profiles, std::make_shared<TrajOptIfoptDefaultPlanProfile>());
cur_plan_profile = applyProfileOverrides(ns_, profile, cur_plan_profile, move_instruction.getProfileOverrides());
if (!cur_plan_profile)
throw std::runtime_error("TrajOptMotionPlanner: Invalid profile");

Expand Down Expand Up @@ -344,11 +341,11 @@ std::shared_ptr<TrajOptIfoptProblem> TrajOptIfoptMotionPlanner::createProblem(co
// ----------------
// Translate TCL for CompositeInstructions
// ----------------
profile = getProfileString(name_, request.instructions.getProfile(), request.composite_profile_remapping);
profile = getProfileString(ns_, request.instructions.getProfile(), request.composite_profile_remapping);
TrajOptIfoptCompositeProfile::ConstPtr cur_composite_profile = getProfile<TrajOptIfoptCompositeProfile>(
name_, profile, *request.profiles, std::make_shared<TrajOptIfoptDefaultCompositeProfile>());
ns_, profile, *request.profiles, std::make_shared<TrajOptIfoptDefaultCompositeProfile>());
cur_composite_profile =
applyProfileOverrides(name_, profile, cur_composite_profile, request.instructions.getProfileOverrides());
applyProfileOverrides(ns_, profile, cur_composite_profile, request.instructions.getProfileOverrides());
if (!cur_composite_profile)
throw std::runtime_error("DefaultTrajoptIfoptProblemGenerator: Invalid profile");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,12 @@ class TaskComposerNode
/** @brief The name of the node */
const std::string& getName() const;

/** @brief Set the namespace of the node */
void setNamespace(const std::string& ns);

/** @brief The namespace of the node */
const std::string& getNamespace() const;

/** @brief The node type TASK, GRAPH, etc */
TaskComposerNodeType getType() const;

Expand Down Expand Up @@ -142,6 +148,9 @@ class TaskComposerNode
/** @brief The name of the task */
std::string name_;

/** @brief The namespace of the task */
std::string ns_;

/** @brief The node type */
TaskComposerNodeType type_;

Expand Down
Loading
Loading