35 int main(
int argc,
char **argv)
37 if (argc != 2)
ThrowPretty(
"No file argument provided.");
39 std::string file_name = argv[1];
43 if (file_name.empty())
ThrowPretty(
"ConfigurationFile not specified!");
45 ros::init(argc, argv,
"example_cpp_load_and_solve_node");
49 Eigen::MatrixXd solution;
50 solver->Solve(solution);
51 HIGHLIGHT(
"Solved in " << solver->GetPlanningTime() <<
"s");
std::shared_ptr< exotica::MotionSolver > MotionSolverPtr
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void InitRos(std::shared_ptr< ros::NodeHandle > nh, int numThreads=2)
static std::shared_ptr< exotica::MotionSolver > LoadSolver(const std::string &file_name)