39 Initializer solver_initializer, problem_initializer;
41 std::string file_name;
54 any_solver->SpecifyProblem(any_problem);
59 if (any_problem->type() ==
"exotica::UnconstrainedTimeIndexedProblem")
67 problem->cost.SetRho(
"Frame", 0.0,
t);
69 problem->cost.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");