39 Initializer solver_initializer, problem_initializer;
41 std::string file_name;
54 any_solver->SpecifyProblem(any_problem);
59 if (any_problem->type() ==
"exotica::UnconstrainedTimeIndexedProblem")
62 for (
int t = 0;
t < problem->GetT() - 1; ++
t)
67 problem->
SetRho(
"Frame", 0.0,
t);
69 problem->SetRho(
"Frame", 1e3, -1);
76 Eigen::MatrixXd solution;
77 any_solver->Solve(solution);
81 int PlaybackWaitInterval = 30;
85 if (t == 0 || t == solution.rows() - 1) i = PlaybackWaitInterval;
88 any_problem->GetScene()->Update(solution.row(t).transpose());
89 any_problem->GetScene()->GetKinematicTree().PublishFrames();
94 t = t + 1 >= solution.rows() ? 0 : t + 1;
101 int main(
int argc,
char **argv)
103 ros::init(argc, argv,
"example_cpp_planner_node");
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
int main(int argc, char **argv)
static std::shared_ptr< exotica::MotionSolver > CreateSolver(const std::string &type, bool prepend=true)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static bool GetParam(const std::string &name, T ¶m)
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
std::shared_ptr< exotica::UnconstrainedTimeIndexedProblem > UnconstrainedTimeIndexedProblemPtr
#define HIGHLIGHT_NAMED(name, x)
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
std::shared_ptr< PlanningProblem > PlanningProblemPtr
ROSCPP_DECL void spinOnce()
void SetRho(const std::string &task_name, const double rho, int t=0)
static void Load(std::string file_name, Initializer &solver, Initializer &problem, const std::string &solver_name="", const std::string &problem_name="", bool parsePathAsXML=false)