41 std::string file_name;
54 any_solver->SpecifyProblem(any_problem);
58 Eigen::VectorXd
q = Eigen::VectorXd::Zero(my_problem->N);
59 Eigen::MatrixXd solution;
61 my_problem->q_nominal = q;
63 HIGHLIGHT(
"Calling solve() in an infinite loop");
73 my_problem->cost.y = {0.6,
74 -0.1 +
sin(t * 2.0 *
M_PI * 0.5) * 0.1,
75 0.5 +
sin(t * M_PI * 0.5) * 0.2, 0, 0, 0};
78 my_problem->SetStartState(q);
79 any_solver->Solve(solution);
83 my_problem->Update(q);
84 my_problem->GetScene()->GetKinematicTree().PublishFrames();
93 int main(
int argc,
char **argv)
95 ros::init(argc, argv,
"example_cpp_init_xml_node");
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
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::UnconstrainedEndPoseProblem > UnconstrainedEndPoseProblemPtr
#define HIGHLIGHT_NAMED(name, x)
int main(int argc, char **argv)
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const std::string &type, bool prepend=true)
std::shared_ptr< PlanningProblem > PlanningProblemPtr
ROSCPP_DECL void spinOnce()
static void Load(std::string file_name, Initializer &solver, Initializer &problem, const std::string &solver_name="", const std::string &problem_name="", bool parsePathAsXML=false)